Skip to content

Commit

Permalink
[fix] update airsim simulation configuration. [doc] added airsim usag…
Browse files Browse the repository at this point in the history
…e doc.
  • Loading branch information
cyanine-gi committed Aug 27, 2021
1 parent a243705 commit 58ab5b9
Show file tree
Hide file tree
Showing 3 changed files with 114 additions and 31 deletions.
53 changes: 53 additions & 0 deletions simulation/Airsim/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
Steps to start airsim:
0. setup env.
mkdir -p ~/Downloads/Airsim/ && https://github.com/microsoft/AirSim.git && cd ~/Downloads/Airsim/AirSim && git checkout v1.5.0-linux

# install airsim with the scripts setup.sh and build.sh manually.

sudo ln -s /usr/lib/x86_64-linux-gnu/libstdc++.so.6 /usr/lib/x86_64-linux-gnu/libstdc++.so # for clang+llvm we need cpplib files end with .so.

mkdir -p ~/Downloads/Airsim/AirSim/cmake/airsim_sensors && cp ~/GAAS/simulation/src/airsim_sensors/CMakeLists.txt ~/Downloads/Airsim/AirSim/cmake/airsim_sensors/CMakeLists.txt

cp -r ~/GAAS/simulation/src/airsim_sensors/ ~/Downloads/Airsim/AirSim/

cd ~/Downloads/Airsim/AirSim && ./build.sh

1. prepare for simulation:

cp simulation/Airsim/mavros_launch/* /opt/ros/melodic/share/mavros/launch/px4_airsim.launch

cp ~/GAAS/simulation/Airsim/vehicles/{YOUR_VEHICLE_CONFIG_FILE} ~/Documents/AirSim/settings.json

2. start airsim simulator:

cd ~/Downloads/Airsim/${MAP_NAME}/LinuxNoEditor && ./${MAP_NAME}.sh

3. start px4 simulation:

cd ~/Downloads/Airsim/AirSim/PX4/PX4-Autopilot && make px4_sitl_default none_iris

4. start mavros for airsim.

roslaunch mavros px4_airsim.launch

5. start airsim sensor msgs publisher.

cd ~/Downloads/Airsim/AirSim/ros && source devel/setup.bash && roslaunch airsim_sensors airsim_sensors.launch

6. (optional) start QGroundControl.




If you wanna use airsim node:

cd ~/Downloads/Airsim/AirSim/ros && catkin build -DCMAKE_C_COMPILER=gcc-8 -DCMAKE_CXX_COMPILER=g++-8
roslaunch airsim_ros_pkgs airsim_node.launch

You can also run:

./scripts/run_airsim.sh

and stop it with:

./scripts/stop_airsim.sh
2 changes: 1 addition & 1 deletion simulation/Airsim/mavros_launch/px4_airsim.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<!-- vim: set ft=xml noet : -->
<!-- example launch script for PX4 based FCU's -->

<arg name="fcu_url" default="udp://:14550@localhost:14557" />
<arg name="fcu_url" default="udp://:14540@localhost:14557" />
<arg name="gcs_url" default="" />
<arg name="tgt_system" default="1" />
<arg name="tgt_component" default="1" />
Expand Down
90 changes: 60 additions & 30 deletions simulation/Airsim/vehicles/settings.json.px4.lidar
Original file line number Diff line number Diff line change
Expand Up @@ -4,49 +4,79 @@
"ClockType": "SteppableClock",
"Vehicles": {
"PX4": {
"X":-3,
"Y":145,
"Z":0,
"VehicleType": "PX4Multirotor",
"UseSerial": false,
"LockStep": true,
"UseTcp": true,
"TcpPort": 4560,
"ControlPortLocal": 14540,
"ControlPortLocal": 14530,
"ControlPortRemote": 14580,
"Sensors":{
"Barometer":{
"SensorType": 1,
"Enabled": true,
"PressureFactorSigma": 0.0001825
},
"Imu": {
"SensorType": 2,
"Enabled": true,
"Roll" : 180,"Pitch": 0, "Yaw" : 0,
"X": 0, "Y": 0, "Z": -1.2
},
"user_imu": {
"SensorType": 2,
"Enabled": true,
"Roll" : 180,"Pitch": 0, "Yaw" : 0,
"X": 0, "Y": 0, "Z": -1.2
},

"Gps": {
"SensorType": 3,
"Enabled": false
},
"Magnetometer": {
"SensorType": 4,
"Enabled": true
},
"Distance": {
"SensorType": 5,
"Enabled": true
},
"Lidar1": {
"SensorType": 6,
"Enabled": true,
"Roll" : 180,"Pitch": 0, "Yaw" : 0,
"X": 0, "Y": 0, "Z": -1.2,
"NumberOfChannels": 32,
"PointsPerSecond": 160000,
"RotationsPerSecond": 10,
"VerticalFOVUpper": 45,
"VerticalFOVLower": -45,
"Range": 180,
"ExternalController": false,
"DataFrame": "SensorLocalFrame",
"DrawDebugPoints": false
},
"Lidar2": {
"SensorType": 6,
"Enabled": true,
"Roll" : 90,"Pitch": 0, "Yaw" : 0,
"X": 0, "Y": 0, "Z": -1.2,
"NumberOfChannels": 32,
"PointsPerSecond": 160000,
"RotationsPerSecond": 10,
"VerticalFOVUpper": 45,
"VerticalFOVLower": -45,
"Range": 180,
"ExternalController": false,
"DataFrame": "SensorLocalFrame",
"DrawDebugPoints": false
}


"Imu": {
"SensorType": 2,
"Enabled": true
},
"Gps": {
"SensorType": 3,
"Enabled": false
},
"Magnetometer": {
"SensorType": 4,
"Enabled": true
},
"Distance": {
"SensorType": 5,
"Enabled": true
},
"Lidar1": {
"SensorType": 6,
"Enabled": true,
"NumberOfChannels": 32,
"PointsPerSecond": 57600,
"RotationsPerSecond": 10,
"VerticalFOVUpper": 45,
"VerticalFOVLower": -45,
"Range": 110,
"ExternalController": false,
"DataFrame": "SensorLocalFrame",
"DrawDebugPoints": true
}

},
"Parameters": {
Expand Down

0 comments on commit 58ab5b9

Please sign in to comment.