Airsim 配置与自定义说明

Airsim 配置与自定义说明

1. 配置说明

推荐使用双电脑仿真,一台windos、一台ubuntu。这样做的好处是可以方便配置,并且保证有很好的仿真性能。具体的Airsim配置,不管是官网还是其他博客都有很好的说明,这里我不再赘述,只把相应的链接放在这里,大家照着做就好。

  • windows 配置

​ 官网说明:https://microsoft.github.io/AirSim/build_windows/

​ 更为细致的个人博客:https://www.zhihu.com/column/multiUAV (注意,这篇博客是Airsim 1.5版本。如果要配置最新版本请再参考一下英文官网(中文的wiki说明也是旧版本的)

​ 在上述教程中提供了自定义无人机的外观的例子。不过需要的注意的是,它只是改变了渲染外形,并不改变实际的气动模型和质量,转动惯量等物理特性。另外根据我个人的使用经验,后续我们在加入自己的无人机时,推荐采用solidwors绘制模型,blender转换格式的方法来实现我们自己的无人机外形。

​ 通过上述的材料,如果不出意外,你已经基本上手了Airsim的使用(在windows下)。

  • 传感器添加参考(一定要加,不然ROS里就没有传感器数据)
{
    "SettingsVersion": 1.2,
    "SimMode": "Multirotor",
    "DefaultVehicleConfig": "SimpleFlight",
    "ViewMode": "FlyWithMe",
    "UsageScenario": "",
    "LocalHostIp": "192.168.3.99",
    "RpcEnabled": true,
    "Recording": {
        "RecordOnMove": false,
        "RecordInterval": 0.05,
        "Cameras": [
            {
                "CameraID": 0,
                "ImageType": 0,
                "PixelsAsFloat": false,
                "Compress": true
            }
        ]
    },
    "SubWindows": [
        {
            "WindowID": 0,
            "CameraName": "front_left",
            "ImageType": 0,
            "Visible": true
        }
    ],
    "CameraDefaults": {
        "CaptureSettings": [
            {
                "ImageType": 0,
                "Width": 640,
                "Height": 480,
                "FOV_Degrees": 90,
                "AutoExposureSpeed": 100,
                "AutoExposureBias": 0,
                "AutoExposureMaxBrightness": 0.64,
                "AutoExposureMinBrightness": 0.03,
                "MotionBlurAmount": 0,
                "TargetGamma": 1.0
            }
        ],
        "NoiseSettings": [
            {
                "ImageType": 0,
                "Enabled": true,
                "RandContrib": 0.2,
                "RandSpeed": 100000.0,
                "RandSize": 1000.0,
                "RandDensity": 6.5,
                "HorzWaveContrib": 0,
                "HorzWaveStrength": 0.08,
                "HorzWaveVertSize": 1.0,
                "HorzWaveScreenSize": 1.0,
                "HorzNoiseLinesContrib": 0,
                "HorzNoiseLinesDensityY": 0.01,
                "HorzNoiseLinesDensityXY": 0.5,
                "HorzDistortionContrib": 0,
                "HorzDistortionStrength": 0.002
            }
        ]
    },
    "Vehicles": {
        "drone_1": {
            "VehicleType": "SimpleFlight",
            "DefaultVehicleState": "Armed",
            "EnableCollisionPassthrogh": false,
            "EnableCollisions": true,
            "AllowAPIAlways": true,
            "RC": {
                "RemoteControlID": 0,
                "AllowAPIWhenDisconnected": false
            },
            "Cameras": {
                "front_left": {
                    "CaptureSettings": [
                        {
                            "ImageType": 0,
                            "Width": 640,
                            "Height": 480,
                            "FOV_Degrees": 90,
                            "TargetGamma": 1.0
                        }
                    ],
                    "X": 0.52,
                    "Y": -0.095,
                    "Z": 0,
                    "Pitch": 0,
                    "Roll": 0,
                    "Yaw": 0
                },
                "front_right": {
                    "CaptureSettings": [
                        {
                            "ImageType": 0,
                            "Width": 640,
                            "Height": 480,
                            "FOV_Degrees": 90,
                            "TargetGamma": 1.0
                        }
                    ],
                    "X": 0.52,
                    "Y": 0.095,
                    "Z": 0,
                    "Pitch": 0,
                    "Roll": 0,
                    "Yaw": 0
                },
                "bottom_center": {
                    "CaptureSettings": [
                        {
                            "ImageType": 0,
                            "Width": 640,
                            "Height": 480,
                            "FOV_Degrees": 90,
                            "TargetGamma": 1.0
                        }
                    ],
                    "X": 0.0,
                    "Y": 0.0,
                    "Z": 0.1,
                    "Pitch": -90,
                    "Roll": 0,
                    "Yaw": 0
                }
            }
        }
    }
}
  • Ubuntu 配置

​ 为了方便windows和Ubuntu通信,请将有线连接的ip设置为一个你喜欢的值(eg: 192.168.3.99),还要记得关闭windows的防火墙,不然ping不通。

​ 接下来,简要说明一下ROS和Airsim的配合使用。下面给出的官方说明的是windows下WSL的使用,这里我们使用ubuntu是和WSL1一样的操作方法,只要写好windows的ip即可。当然要记得先配置ubuntu的有线网络连接,保证和windows在同一网段(eg: 192.168.3.9)。

​ How to run Airsim on Windows and ROS wrapper on WSL#

For WSL 1 execute: export WSL_HOST_IP=127.0.0.1 and for WSL 2: export WSL_HOST_IP=$(cat /etc/resolv.conf | grep nameserver | awk '{print $2}') Now, as in the running section for linux, execute the following:

source devel/setup.bash
roslaunch airsim_ros_pkgs airsim_node.launch output:=screen host:=$WSL_HOST_IP
roslaunch airsim_ros_pkgs rviz.launch

2.自定义说明

​ 为了能够更加逼近实际的飞行,做出更准确的飞行控制,实现从仿真到实机的无缝切换,只用Airsim自带的无人机模型大概是不够的。从Airsim官方文献 ,我们可以看到,其所建立的旋翼气动模型其实是很粗糙的,其精度远远不满足科研级别的要求,如果我们需要做无人机的高速飞行敏捷控制,这从仿真移植到实机将会是致命的灾难。

注意 :输入控制信号和实际输出之间有一个一阶滤波器(可以充当惯性环节的电机响应,文献中没有写)。

 static void setOutput(Output& output, const RotorParams& params, const FirstOrderFilter<real_T>& control_signal_filter, RotorTurningDirection turning_direction)
    {
        output.control_signal_input = control_signal_filter.getInput();
        output.control_signal_filtered = control_signal_filter.getOutput();
        //see relationship of rotation speed with thrust: http://physics.stackexchange.com/a/32013/14061
        output.speed = sqrt(output.control_signal_filtered * params.max_speed_square);
        output.thrust = output.control_signal_filtered * params.max_thrust;
        output.torque_scaler = output.control_signal_filtered * params.max_torque * static_cast<int>(turning_direction);
        output.turning_direction = turning_direction;
    }
  • 动力学

​ 不过,从Airsim的代码框架中,要对旋翼模型做出修改并不难。在/Airlib/include/vehicles/multirotor/RotorActuator.hpp/Airlib/include/vehicles/multirotor/RotorParams.hpp中修改源代码即可。另外飞行器阻力也应该进行修改(搜索一下drag)

​ 此外,除了旋翼模型,我们也需要和真机质量和转动惯量更相符合的刚体模型。在/Airlib/include/vehicles/multirotor/MultiRotorParams.hppvoid setupFrameGenericQuad(Params& params)修改即可。

​ 最后,如果需要其它的无人机动力学仿真,那么可以参考这个issue

更进一步阻力模型的建立: 有一说一,这个阻力模型也挺粗糙的。(在这里我们可以注意到如何将风添加到动力学模型中,这对我们修改旋翼气动模型也是有用的)

// drag term in Airsim   

/**\AirSim\AirLib\include\vehicles\multirotor\MultiRotorPhysicsBody.hpp**/
 void createDragVertices()
    {
        const auto& params = params_->getParams();

        //Drone is seen as central body that is connected to propellers via arm. We approximate central body as box of size x, y, z.
        //The drag depends on area exposed so we also add area of propellers to approximate drag they may introduce due to their area.
        //while moving along any axis, we find area that will be exposed in that direction
        real_T propeller_area = M_PIf * params.rotor_params.propeller_diameter * params.rotor_params.propeller_diameter;
        real_T propeller_xsection = M_PIf * params.rotor_params.propeller_diameter * params.rotor_params.propeller_height;

        real_T top_bottom_area = params.body_box.x() * params.body_box.y();
        real_T left_right_area = params.body_box.x() * params.body_box.z();
        real_T front_back_area = params.body_box.y() * params.body_box.z();
        Vector3r drag_factor_unit = Vector3r(
            front_back_area + rotors_.size() * propeller_xsection, 
            left_right_area + rotors_.size() * propeller_xsection, 
            top_bottom_area + rotors_.size() * propeller_area) 
            * params.linear_drag_coefficient / 2; 

        //add six drag vertices representing 6 sides
        drag_faces_.clear();
        drag_faces_.emplace_back(Vector3r(0, 0, -params.body_box.z() / 2.0f), Vector3r(0, 0, -1), drag_factor_unit.z());
        drag_faces_.emplace_back(Vector3r(0, 0,  params.body_box.z() / 2.0f), Vector3r(0, 0,  1), drag_factor_unit.z());
        drag_faces_.emplace_back(Vector3r(0, -params.body_box.y() / 2.0f, 0), Vector3r(0, -1, 0), drag_factor_unit.y());
        drag_faces_.emplace_back(Vector3r(0,  params.body_box.y() / 2.0f, 0), Vector3r(0,  1, 0), drag_factor_unit.y());
        drag_faces_.emplace_back(Vector3r(-params.body_box.x() / 2.0f, 0, 0), Vector3r(-1, 0, 0), drag_factor_unit.x());
        drag_faces_.emplace_back(Vector3r( params.body_box.x() / 2.0f, 0, 0), Vector3r( 1, 0, 0), drag_factor_unit.x());

    }

/** \AirSim\AirLib\include\physics\FastPhysicsEngine.hpp  **/
static Wrench getDragWrench(const PhysicsBody& body, const Quaternionr& orientation, 
        const Vector3r& linear_vel, const Vector3r& angular_vel_body, const Vector3r& wind_world)
    {
        //add linear drag due to velocity we had since last dt seconds + wind
        //drag vector magnitude is proportional to v^2, direction opposite of velocity
        //total drag is b*v + c*v*v but we ignore the first term as b << c (pg 44, Classical Mechanics, John Taylor)
        //To find the drag force, we find the magnitude in the body frame and unit vector direction in world frame
        //http://physics.stackexchange.com/questions/304742/angular-drag-on-body
        //similarly calculate angular drag
        //note that angular velocity, acceleration, torque are already in body frame

        Wrench wrench = Wrench::zero();
        const real_T air_density = body.getEnvironment().getState().air_density;

        // Use relative velocity of the body wrt wind
        const Vector3r relative_vel = linear_vel - wind_world;
        const Vector3r linear_vel_body = VectorMath::transformToBodyFrame(relative_vel, orientation);

        for (uint vi = 0; vi < body.dragVertexCount(); ++vi) {
            const auto& vertex = body.getDragVertex(vi);
            const Vector3r vel_vertex = linear_vel_body + angular_vel_body.cross(vertex.getPosition());
            const real_T vel_comp = vertex.getNormal().dot(vel_vertex);
            //if vel_comp is -ve then we cull the face. If velocity too low then drag is not generated
            if (vel_comp > kDragMinVelocity) {
                const Vector3r drag_force = vertex.getNormal() * (- vertex.getDragFactor() * air_density * vel_comp * vel_comp); //this is wrong! TLK 2022-9-14 
                const Vector3r drag_torque = vertex.getPosition().cross(drag_force);// drag_torque is always zero

                wrench.force += drag_force;
                wrench.torque += drag_torque;
            }
        }
  • 天气

https://zhaoxuhui.top/blog/2021/12/06/airsim-note7-weather-system-in-airsim.html

https://zhuanlan.zhihu.com/p/425804207

总结

Airsim 作为微软推出的用于推动自动驾驶和飞行的一款高保真仿真软件,其整个框架和文档是清晰完善的。基于unreal engine, Airsim可以得到保真度很高的视频画面,用于端到端的AI训练与部署。但是Airsim中无人机的动力学引擎部分依旧是粗糙的,对于低速场景其可以使用。但是对于高速飞行来收,保真度与state of the art的文章来说,有较大差距。如果后续对控制规划做深入深入,这部分需要参考相应的文献来进行修改。

  • 4
    点赞
  • 18
    收藏
    觉得还不错? 一键收藏
  • 6
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 6
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值