Interfacing mavros with gazebo SITL

So I found the documentation really hard to understand. I followed instructions from these two sources,
http://dev.px4.io/simulation-ros-interface.html and http://dev.px4.io/ros-mavros-offboard.html. However, the quadrotor never rises, and the console constantly outputs error message.

I first ran the gazebo_sitl

cd <Firmware_clone>
make posix_sitl_default
source ~/catkin_ws/devel/setup.bash
source Tools/setup_gazebo.bash $(pwd) build_posix_sitl_default
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:$(pwd)
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:$(pwd)/Tools/sitl_gazebo
roslaunch px4 mavros_posix_sitl.launch

and the output is

SUMMARY
========

CLEAR PARAMETERS
 * /mavros/

PARAMETERS
 * /mavros/cmd/use_comp_id_system_control: False
 * /mavros/conn/heartbeat_rate: 1.0
 * /mavros/conn/system_time_rate: 1.0
 * /mavros/conn/timeout: 10.0
 * /mavros/conn/timesync_rate: 10.0
 * /mavros/distance_sensor/hrlv_ez4_pub/field_of_view: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/frame_id: hrlv_ez4_sonar
 * /mavros/distance_sensor/hrlv_ez4_pub/id: 0
 * /mavros/distance_sensor/hrlv_ez4_pub/orientation: ROLL_180
 * /mavros/distance_sensor/hrlv_ez4_pub/send_tf: True
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/x: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/y: 0.0
 * /mavros/distance_sensor/hrlv_ez4_pub/sensor_position/z: -0.1
 * /mavros/distance_sensor/laser_1_sub/id: 3
 * /mavros/distance_sensor/laser_1_sub/orientation: ROLL_180
 * /mavros/distance_sensor/laser_1_sub/subscriber: True
 * /mavros/distance_sensor/lidarlite_pub/field_of_view: 0.0
 * /mavros/distance_sensor/lidarlite_pub/frame_id: lidarlite_laser
 * /mavros/distance_sensor/lidarlite_pub/id: 1
 * /mavros/distance_sensor/lidarlite_pub/orientation: ROLL_180
 * /mavros/distance_sensor/lidarlite_pub/send_tf: True
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/x: 0.0
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/y: 0.0
 * /mavros/distance_sensor/lidarlite_pub/sensor_position/z: -0.1
 * /mavros/distance_sensor/sonar_1_sub/id: 2
 * /mavros/distance_sensor/sonar_1_sub/orientation: ROLL_180
 * /mavros/distance_sensor/sonar_1_sub/subscriber: True
 * /mavros/fcu_url: udp://:14540@loca...
 * /mavros/gcs_url: 
 * /mavros/global_position/frame_id: fcu
 * /mavros/global_position/rot_covariance: 99999.0
 * /mavros/global_position/tf/child_frame_id: fcu_utm
 * /mavros/global_position/tf/frame_id: local_origin
 * /mavros/global_position/tf/send: False
 * /mavros/image/frame_id: px4flow
 * /mavros/imu/angular_velocity_stdev: 0.000349065850399
 * /mavros/imu/frame_id: fcu
 * /mavros/imu/linear_acceleration_stdev: 0.0003
 * /mavros/imu/magnetic_stdev: 0.0
 * /mavros/imu/orientation_stdev: 1.0
 * /mavros/local_position/frame_id: fcu
 * /mavros/local_position/tf/child_frame_id: fcu
 * /mavros/local_position/tf/frame_id: local_origin
 * /mavros/local_position/tf/send: False
 * /mavros/local_position/tf/send_fcu: False
 * /mavros/mission/pull_after_gcs: True
 * /mavros/mocap/use_pose: True
 * /mavros/mocap/use_tf: False
 * /mavros/plugin_blacklist: ['safety_area', '...
 * /mavros/plugin_whitelist: []
 * /mavros/px4flow/frame_id: px4flow
 * /mavros/px4flow/ranger_fov: 0.0
 * /mavros/px4flow/ranger_max_range: 5.0
 * /mavros/px4flow/ranger_min_range: 0.3
 * /mavros/safety_area/p1/x: 1.0
 * /mavros/safety_area/p1/y: 1.0
 * /mavros/safety_area/p1/z: 1.0
 * /mavros/safety_area/p2/x: -1.0
 * /mavros/safety_area/p2/y: -1.0
 * /mavros/safety_area/p2/z: -1.0
 * /mavros/setpoint_accel/send_force: False
 * /mavros/setpoint_attitude/reverse_throttle: False
 * /mavros/setpoint_attitude/tf/child_frame_id: attitude
 * /mavros/setpoint_attitude/tf/frame_id: local_origin
 * /mavros/setpoint_attitude/tf/listen: False
 * /mavros/setpoint_attitude/tf/rate_limit: 10.0
 * /mavros/setpoint_position/tf/child_frame_id: setpoint
 * /mavros/setpoint_position/tf/frame_id: local_origin
 * /mavros/setpoint_position/tf/listen: False
 * /mavros/setpoint_position/tf/rate_limit: 50.0
 * /mavros/startup_px4_usb_quirk: True
 * /mavros/sys/disable_diag: False
 * /mavros/sys/min_voltage: 10.0
 * /mavros/target_component_id: 1
 * /mavros/target_system_id: 1
 * /mavros/tdr_radio/low_rssi: 40
 * /mavros/time/time_ref_source: fcu
 * /mavros/time/timesync_avg_alpha: 0.6
 * /mavros/vibration/frame_id: vibration
 * /mavros/vision_pose/tf/child_frame_id: vision
 * /mavros/vision_pose/tf/frame_id: local_origin
 * /mavros/vision_pose/tf/listen: False
 * /mavros/vision_pose/tf/rate_limit: 10.0
 * /mavros/vision_speed/listen_twist: False
 * /rosdistro: kinetic
 * /rosversion: 1.12.5
 * /use_sim_time: True

NODES
  /
    gazebo (gazebo_ros/gzserver)
    gazebo_gui (gazebo_ros/gzclient)
    mavros (mavros/mavros_node)
    sitl (px4/px4)
    vehicle_spawn_haoyu_OptiPlex_3010_20567_1160899454580069528 (gazebo_ros/spawn_model)

auto-starting new master
process[master]: started with pid [20578]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to fbb7b84a-99ae-11e6-a81c-000f6005d13e
process[rosout-1]: started with pid [20591]
started core service [/rosout]
process[sitl-2]: started with pid [20616]
node name: sitl
data path: /home/haoyu/drone/Firmware
commands file: /home/haoyu/drone/Firmware/posix-configs/SITL/init/lpe/iris
18446744073709551601 WARNING: setRealtimeSched failed (not run as root?)

______  __   __    ___ 
| ___ \ \ \ / /   /   |
| |_/ /  \ V /   / /| |
|  __/   /   \  / /_| |
| |     / /^\ \ \___  |
\_|     \/   \/     |_/

px4 starting.

process[gazebo-3]: started with pid [20618]
process[gazebo_gui-4]: started with pid [20631]
INFO  [dataman] Unkown restart, data manager file 'rootfs/fs/microsd/dataman' size is 103090 bytes
process[vehicle_spawn_haoyu_OptiPlex_3010_20567_1160899454580069528-5]: started with pid [20638]
process[mavros-6]: started with pid [20641]
INFO  [platforms__posix__drivers__ledsim] LED::init
INFO  [platforms__posix__drivers__ledsim] LED::init
INFO  [simulator] Not using /dev/ttyACM0 for radio control input. Assuming joystick input via MAVLink.
INFO  [simulator] Waiting for initial data on UDP port 14560. Please start the flight simulator to proceed..
[ INFO] [1477288751.546554162]: FCU URL: udp://:14540@localhost:14557
[ WARN] [1477288751.546975118]: init: message from ASLUAV, MSG-ID 201 ignored! Table has different entry.
[ WARN] [1477288751.547087372]: init: message from autoquad, MSG-ID 150 ignored! Table has different entry.
[ WARN] [1477288751.547100240]: init: message from autoquad, MSG-ID 152 ignored! Table has different entry.
[ WARN] [1477288751.547198072]: init: message from matrixpilot, MSG-ID 150 ignored! Table has different entry.
[ WARN] [1477288751.547209619]: init: message from matrixpilot, MSG-ID 151 ignored! Table has different entry.
[ WARN] [1477288751.547221545]: init: message from matrixpilot, MSG-ID 152 ignored! Table has different entry.
[ WARN] [1477288751.547232855]: init: message from matrixpilot, MSG-ID 153 ignored! Table has different entry.
[ WARN] [1477288751.547244769]: init: message from matrixpilot, MSG-ID 155 ignored! Table has different entry.
[ WARN] [1477288751.547256091]: init: message from matrixpilot, MSG-ID 156 ignored! Table has different entry.
[ WARN] [1477288751.547267417]: init: message from matrixpilot, MSG-ID 157 ignored! Table has different entry.
[ WARN] [1477288751.547279087]: init: message from matrixpilot, MSG-ID 158 ignored! Table has different entry.
[ WARN] [1477288751.547292601]: init: message from matrixpilot, MSG-ID 170 ignored! Table has different entry.
[ WARN] [1477288751.547303933]: init: message from matrixpilot, MSG-ID 171 ignored! Table has different entry.
[ WARN] [1477288751.547315462]: init: message from matrixpilot, MSG-ID 172 ignored! Table has different entry.
[ WARN] [1477288751.547325956]: init: message from matrixpilot, MSG-ID 173 ignored! Table has different entry.
[ WARN] [1477288751.547336219]: init: message from matrixpilot, MSG-ID 174 ignored! Table has different entry.
[ WARN] [1477288751.547348276]: init: message from matrixpilot, MSG-ID 175 ignored! Table has different entry.
[ WARN] [1477288751.547360142]: init: message from matrixpilot, MSG-ID 176 ignored! Table has different entry.
[ WARN] [1477288751.547370086]: init: message from matrixpilot, MSG-ID 177 ignored! Table has different entry.
[ WARN] [1477288751.547385050]: init: message from matrixpilot, MSG-ID 178 ignored! Table has different entry.
[ WARN] [1477288751.547395642]: init: message from matrixpilot, MSG-ID 179 ignored! Table has different entry.
[ WARN] [1477288751.547405987]: init: message from matrixpilot, MSG-ID 180 ignored! Table has different entry.
[ WARN] [1477288751.547416217]: init: message from matrixpilot, MSG-ID 181 ignored! Table has different entry.
[ WARN] [1477288751.547426419]: init: message from matrixpilot, MSG-ID 182 ignored! Table has different entry.
[ WARN] [1477288751.547521353]: init: message from paparazzi, MSG-ID 180 ignored! Table has different entry.
[ WARN] [1477288751.547533475]: init: message from paparazzi, MSG-ID 181 ignored! Table has different entry.
[ WARN] [1477288751.547543489]: init: message from paparazzi, MSG-ID 182 ignored! Table has different entry.
[ WARN] [1477288751.547553670]: init: message from paparazzi, MSG-ID 183 ignored! Table has different entry.
[ WARN] [1477288751.547563649]: init: message from paparazzi, MSG-ID 184 ignored! Table has different entry.
[ WARN] [1477288751.547660273]: init: message from slugs, MSG-ID 170 ignored! Table has different entry.
[ WARN] [1477288751.547671955]: init: message from slugs, MSG-ID 172 ignored! Table has different entry.
[ WARN] [1477288751.547682344]: init: message from slugs, MSG-ID 173 ignored! Table has different entry.
[ WARN] [1477288751.547692755]: init: message from slugs, MSG-ID 176 ignored! Table has different entry.
[ WARN] [1477288751.547703931]: init: message from slugs, MSG-ID 177 ignored! Table has different entry.
[ WARN] [1477288751.547715713]: init: message from slugs, MSG-ID 179 ignored! Table has different entry.
[ WARN] [1477288751.547726936]: init: message from slugs, MSG-ID 180 ignored! Table has different entry.
[ WARN] [1477288751.547738124]: init: message from slugs, MSG-ID 181 ignored! Table has different entry.
[ WARN] [1477288751.547749788]: init: message from slugs, MSG-ID 184 ignored! Table has different entry.
[ WARN] [1477288751.547761635]: init: message from slugs, MSG-ID 185 ignored! Table has different entry.
[ WARN] [1477288751.547771354]: init: message from slugs, MSG-ID 186 ignored! Table has different entry.
[ WARN] [1477288751.547782326]: init: message from slugs, MSG-ID 191 ignored! Table has different entry.
[ WARN] [1477288751.547792280]: init: message from slugs, MSG-ID 192 ignored! Table has different entry.
[ WARN] [1477288751.547801970]: init: message from slugs, MSG-ID 193 ignored! Table has different entry.
[ WARN] [1477288751.547812316]: init: message from slugs, MSG-ID 194 ignored! Table has different entry.
[ INFO] [1477288751.548079256]: udp0: Bind address: 0.0.0.0:14540
[ INFO] [1477288751.548136393]: udp0: Remote address: 127.0.0.1:14557
[ INFO] [1477288751.548214087]: GCS bridge disabled
[ INFO] [1477288751.594892488]: Plugin 3dr_radio loaded
[ INFO] [1477288751.596808229]: Plugin 3dr_radio initialized
[ INFO] [1477288751.596888464]: Plugin actuator_control loaded
[ INFO] [1477288751.599436382]: Plugin actuator_control initialized
[ INFO] [1477288751.599511090]: Plugin altitude loaded
[ INFO] [1477288751.600451723]: Plugin altitude initialized
[ INFO] [1477288751.626141501]: Plugin cam_imu_sync loaded
[ INFO] [1477288751.627229241]: Plugin cam_imu_sync initialized
[ INFO] [1477288751.627328416]: Plugin command loaded
[ INFO] [1477288751.631828133]: Plugin command initialized
[ INFO] [1477288751.631866451]: Plugin distance_sensor blacklisted
[ INFO] [1477288751.631971662]: Plugin ftp loaded
[ INFO] [1477288751.644808388]: Plugin ftp initialized
[ INFO] [1477288751.644935742]: Plugin global_position loaded
[ INFO] [1477288751.652192749]: Plugin global_position initialized
[ INFO] [1477288751.652302062]: Plugin hil_controls loaded
[ INFO] [1477288751.652853487]: Plugin hil_controls initialized
[ INFO] [1477288751.652932428]: Plugin imu_pub loaded
[ INFO] [1477288751.659356548]: Plugin imu_pub initialized
[ INFO] [1477288751.659462047]: Plugin local_position loaded
[ INFO] [1477288751.664583466]: Plugin local_position initialized
[ INFO] [1477288751.664681616]: Plugin manual_control loaded
[ INFO] [1477288751.665243431]: Plugin manual_control initialized
[ INFO] [1477288751.665318042]: Plugin mocap_pose_estimate loaded
[ INFO] [1477288751.669539436]: Plugin mocap_pose_estimate initialized
[ INFO] [1477288751.669649831]: Plugin param loaded
[ INFO] [1477288751.671766774]: Plugin param initialized
[ INFO] [1477288751.671852007]: Plugin px4flow loaded
[ INFO] [1477288751.676730759]: Plugin px4flow initialized
[ INFO] [1477288751.676830321]: Plugin rc_io loaded
[ INFO] [1477288751.680138330]: Plugin rc_io initialized
[ INFO] [1477288751.680160380]: Plugin safety_area blacklisted
[ INFO] [1477288751.680246006]: Plugin setpoint_accel loaded
[ INFO] [1477288751.683251713]: Plugin setpoint_accel initialized
[ INFO] [1477288751.683343350]: Plugin setpoint_attitude loaded
[ INFO] [1477288751.694248840]: Plugin setpoint_attitude initialized
[ INFO] [1477288751.694360050]: Plugin setpoint_position loaded
[ INFO] [1477288751.699920764]: Plugin setpoint_position initialized
[ INFO] [1477288751.700057701]: Plugin setpoint_raw loaded
[ INFO] [1477288751.710166169]: Plugin setpoint_raw initialized
[ INFO] [1477288751.710280287]: Plugin setpoint_velocity loaded
[ INFO] [1477288751.712643287]: Plugin setpoint_velocity initialized
[ INFO] [1477288751.712765168]: Plugin sys_status loaded
[ INFO] [1477288751.721064489]: Plugin sys_status initialized
[ INFO] [1477288751.721183241]: Plugin sys_time loaded
[ INFO] [1477288751.724197866]: Plugin sys_time initialized
[ INFO] [1477288751.724295908]: Plugin vfr_hud loaded
[ INFO] [1477288751.726131543]: Plugin vfr_hud initialized
[ INFO] [1477288751.726160356]: Plugin vibration blacklisted
[ INFO] [1477288751.726233234]: Plugin vision_pose_estimate loaded
[ INFO] [1477288751.735225493]: Plugin vision_pose_estimate initialized
[ INFO] [1477288751.735331643]: Plugin vision_speed_estimate loaded
[ INFO] [1477288751.738519658]: Plugin vision_speed_estimate initialized
[ INFO] [1477288751.738622558]: Plugin waypoint loaded
[ INFO] [1477288751.745997244]: Plugin waypoint initialized
[ INFO] [1477288751.746035123]: Autostarting mavlink via USB on PX4
[ INFO] [1477288751.746125801]: Built-in SIMD instructions: SSE, SSE2
[ INFO] [1477288751.746145922]: Built-in MAVLink package version: 2016.9.9
[ INFO] [1477288751.746166079]: Known MAVLink dialects: common ardupilotmega ASLUAV autoquad matrixpilot paparazzi slugs uAvionix ualberta
[ INFO] [1477288751.746183447]: MAVROS started. MY ID 1.240, TARGET ID 1.1
spawn_model script started
[ INFO] [1477288751.919344105]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1477288751.919843655]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[INFO] [WallTime: 1477288752.001217] [0.000000] Loading model xml from file
[INFO] [WallTime: 1477288752.001808] [0.000000] Waiting for service /gazebo/spawn_sdf_model
[ INFO] [1477288752.962463410, 0.024000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1477288752.988591888, 0.050000000]: Physics dynamic reconfigure ready.
[INFO] [WallTime: 1477288753.208745] [0.268000] Calling service /gazebo/spawn_sdf_model
[INFO] [WallTime: 1477288753.362092] [0.360000] Spawn status: SpawnModel: Successfully spawned model
[vehicle_spawn_haoyu_OptiPlex_3010_20567_1160899454580069528-5] process has finished cleanly
log file: /home/haoyu/.ros/log/fbb7b84a-99ae-11e6-a81c-000f6005d13e/vehicle_spawn_haoyu_OptiPlex_3010_20567_1160899454580069528-5*.log

and then opened another terminal, ran offb node provided by the example page.
rosrun offb offb_node. This terminal outputs nothing, the SITL terminal starts outputing

[ERROR] [1477288885.212484531, 132.118000000]: MODE: Unsupported FCU
[ERROR] [1477288890.266680427, 137.170000000]: MODE: Unsupported FCU
[ERROR] [1477288895.319149494, 142.218000000]: MODE: Unsupported FCU
[ERROR] [1477288900.372950770, 147.268000000]: MODE: Unsupported FCU
[ERROR] [1477288905.426608270, 152.318000000]: MODE: Unsupported FCU
[ERROR] [1477288910.480156131, 157.370000000]: MODE: Unsupported FCU
[ERROR] [1477288915.534747092, 162.418000000]: MODE: Unsupported FCU
[ERROR] [1477288920.587531491, 167.468000000]: MODE: Unsupported FCU
[ERROR] [1477288925.640700239, 172.518000000]: MODE: Unsupported FCU
[ERROR] [1477288930.694841505, 177.568000000]: MODE: Unsupported FCU
[ERROR] [1477288935.747741297, 182.618000000]: MODE: Unsupported FCU
[ERROR] [1477288940.811222596, 187.668000000]: MODE: Unsupported FCU
[ERROR] [1477288945.866302657, 192.720000000]: MODE: Unsupported FCU
[ERROR] [1477288950.918057774, 197.768000000]: MODE: Unsupported FCU
[ERROR] [1477288955.971626596, 202.818000000]: MODE: Unsupported FCU
[ERROR] [1477288961.025242546, 207.852000000]: MODE: Unsupported FCU
[ERROR] [1477288966.078283087, 212.918000000]: MODE: Unsupported FCU
[ERROR] [1477288971.133451537, 217.968000000]: MODE: Unsupported FCU
[ERROR] [1477288976.194463373, 223.018000000]: MODE: Unsupported FCU
[ERROR] [1477288981.248755791, 228.070000000]: MODE: Unsupported FCU
[ERROR] [1477288986.301387819, 233.118000000]: MODE: Unsupported FCU
[ERROR] [1477288991.354523686, 238.168000000]: MODE: Unsupported FCU
[ERROR] [1477288996.407573064, 243.218000000]: MODE: Unsupported FCU
[ERROR] [1477289001.460926055, 248.270000000]: MODE: Unsupported FCU
[ERROR] [1477289006.513461784, 253.318000000]: MODE: Unsupported FCU
[ERROR] [1477289011.566814832, 258.368000000]: MODE: Unsupported FCU
[ERROR] [1477289016.620408010, 263.418000000]: MODE: Unsupported FCU
[ERROR] [1477289021.675254041, 268.468000000]: MODE: Unsupported FCU
[ERROR] [1477289026.729104645, 273.518000000]: MODE: Unsupported FCU
[ERROR] [1477289031.783777507, 278.568000000]: MODE: Unsupported FCU
[ERROR] [1477289036.838509354, 283.618000000]: MODE: Unsupported FCU
[ERROR] [1477289041.892448828, 288.668000000]: MODE: Unsupported FCU
[ERROR] [1477289046.947357703, 293.718000000]: MODE: Unsupported FCU
[ERROR] [1477289052.000189320, 298.768000000]: MODE: Unsupported FCU
[ERROR] [1477289057.054740632, 303.818000000]: MODE: Unsupported FCU
[ERROR] [1477289062.108534809, 308.868000000]: MODE: Unsupported FCU
[ERROR] [1477289067.161737856, 313.918000000]: MODE: Unsupported FCU

try taking off without the offboard example - working? (using the “commander takeoff” in the SITL terminal)

Thanks @edigotlieb. Yes. The regular SITL works. If I run the regular SITL, I can do manual command. But if I run rosluanch, I can’t issue manual commands directly to FCU.

Do you want to do it without running a mavros node? Try running roslaunch mavros px4.launch fcu_url:=udp://:14540@14557

or whatever ports you’ve got and then try running the offboard node

1 Like

Thanks @sriniv27. Before I go ahead to try, can you explain what 14540 and 14557 mean respectively?

14540 is the port of the bind host and 14557 is the remote port. The full url would be something like fcu_url:=udp://:14540@127.0.0.1:14557 but if you’re running everything on te same machine then it can be condensed to udp://:14540@14557

To know which ports to bind to, look at the log when you run make posix gazebo

3 Likes

Wow @sriniv27. This is awesome!!! Thanks.

I’ve been having this problem too, I think you’ve been misunderstanding what the issue actually is. It’s not that mavros is listening to the wrong port, it’s that the port is not there at all. If you pay close attention to the log he gave, notice how for the simulator there is nothing after
INFO [simulator] Waiting for initial data on UDP port 14560. Please start the flight simulator to proceed…

Normally, if ros is not in the loop, the simulator would output
INFO [simulator] Got initial simuation data, running sim…

and everything would be fine. But in this case the simulator is not even getting the data from gazebo in the first place even when gazebo is open, that is why mavros cannot hear anything, since the simulator is stalled trying to get initial simulation data from gazebo

@eric1221bday. I agree. I tried what @sriniv27 suggested,

  1. using the normal make posix_sitl_defualt gazebo
  2. starting up a mavros node, roslaunch mavros px4.launch fcu_url:=udp://:14540@14557
  3. opening another terminal for my own ROS node

Surprisingly this works. I figure the problem lies in the launch file provided by the example. If you just run the regular launch file, it actually starts a MAVLINK service listening to the right port.

@zhahaoyu Yeah that would work, since the simulator is the one responsible for outputting the mavlink, and as long as it gets data from gazebo, it’s alright. The downside of this approach is that you would not be able to take advantage of gazebo plugins and ros wrappers to directly output sensor outputs (such as px4flow). It used to work, but I think they broke the whole thing in the past month or so causing gazebo and ros to no longer be able to take properly

@eric1221bday Hello, I meet the same problem too. When I run the offb_node, the gazebo SITL give the information:
[ERROR] [1479732255.769622699, 7.760000000]: MODE: Unsupported FCU
And the rqt_graph is:
I want to know how to solve this problem(and I need gazebo plugins and ros wrapper), could you help me?

@zhahaoyu I did what you said[quote=“zhahaoyu, post:9, topic:1552”]
1.using the normal make posix_sitl_defualt gazebo

2.starting up a mavros node, roslaunch mavros px4.launch fcu_url:=udp://:14540@14557

3.opening another terminal for my own ROS node
[/quote]
but the gazebo did not open, how can I see the simulation?

So I’ve since then been able to run gazebo simulations successfully with ROS. The first thing to note is that the entire firmware folder can be conceived as a ROS package with the px4 package being defined. Normally the make posix_sitl_default gazebo command actually builds both the px4 package and the sitl_gazebo package, unfortunately this results in a bit of a dependency mess, if you take a look at the devguide they list out 5 lines just to setup the correct ROS environment. The best way I found so far is to have both the firmware folder and a separately cloned sitl_gazebo both in a catkin workspace, use catkin build to build both, then use ros to launch the mavros_posix_sitl launch file in the px4 package

4 Likes

@Oh, thanks a lot!!! Now I can do my next work.

I am simulating Px4 SITL with ROS. But I am getting error. attached image of terminal.

Use px4_sitl_default