Correct start MAVROS+PX4+GAZEBO+IRIS

Good evening everyone!

I have the following problem. I want to connect 1, PX4 and Gazebo using the IRIS model. I followed the manual, here are my actions:

  • Install ROS Kinetic
  • Install GeographicLib
  • Install MAVROS
  • Install common dependencies
  • Install FastRTPS 1.5.0 and FastCDR-1.0.7
  • Clone PX4/Firmware

After that I go to srs/Firmware and run:

    cd ~/src/Firmware
    sudo make px4_sitl gazebo

This is the output:

ninja: Entering directory `/home/art/src/Firmware/build/px4_sitl_default'
[2/6] Performing configure step for 'sitl_gazebo'
-- install-prefix: /usr/local
-- Boost version: 1.58.0
-- Found the following Boost libraries:
--   system
--   thread
--   timer
--   chrono
--   date_time
--   atomic
-- Boost version: 1.58.0
-- Building klt_feature_tracker without catkin
-- Building OpticalFlow with OpenCV
-- catkin DISABLED
Gazebo version: 7.0
-- Using C++14 compiler
-- Configuring done
-- Generating done
-- Build files have been written to: /home/art/src/Firmware/build/px4_sitl_default/build_gazebo
[3/6] Performing build step for 'sitl_gazebo'
ninja: no work to do.
[6/6] cd /home/art/src/Firmware/build/...rt/src/Firmware/build/px4_sitl_default
SITL ARGS
sitl_bin: /home/art/src/Firmware/build/px4_sitl_default/bin/px4
debugger: none
program: gazebo
model: none
src_path: /home/art/src/Firmware
build_path: /home/art/src/Firmware/build/px4_sitl_default
empty model, setting iris as default
GAZEBO_PLUGIN_PATH :/home/art/src/Firmware/build/px4_sitl_default/build_gazebo
GAZEBO_MODEL_PATH :/home/art/src/Firmware/Tools/sitl_gazebo/models
LD_LIBRARY_PATH :/home/art/src/Firmware/build/px4_sitl_default/build_gazebo
Gazebo multi-robot simulator, version 7.0.0
Copyright (C) 2012-2016 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.1.41
[Dbg] [gazebo_mavlink_interface.cpp:137] <joint_name> not found for channel[0] no joint control will be performed for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:137] <joint_name> not found for channel[1] no joint control will be performed for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:137] <joint_name> not found for channel[2] no joint control will be performed for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:137] <joint_name> not found for channel[3] no joint control will be performed for this channel.
[Wrn] [gazebo_mavlink_interface.cpp:126] joint [zephyr_delta_wing::propeller_joint] not found for channel[4] no joint control for this channel.
[Wrn] [gazebo_mavlink_interface.cpp:126] joint [zephyr_delta_wing::flap_left_joint] not found for channel[5] no joint control for this channel.
[Wrn] [gazebo_mavlink_interface.cpp:126] joint [zephyr_delta_wing::flap_right_joint] not found for channel[6] no joint control for this channel.
[Dbg] [gazebo_mavlink_interface.cpp:137] <joint_name> not found for channel[7] no joint control will be performed for this channel.
[Msg] Conecting to PX4 SITL using TCP
[Msg] Lockstep is enabled
[Msg] Speed factor set to: 1
SITL COMMAND: "/home/art/src/Firmware/build/px4_sitl_default/bin/px4" "/home/art/src/Firmware"/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -t "/home/art/src/Firmware"/test_data
INFO  [px4] Creating symlink /home/art/src/Firmware/ROMFS/px4fmu_common -> /home/art/src/Firmware/build/px4_sitl_default/tmp/rootfs/etc

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

px4 starting.

INFO  [px4] Calling startup script: /bin/sh etc/init.d-posix/rcS 0
INFO  [dataman] Unknown restart, data manager file './dataman' size is 11405132 bytes
INFO  [simulator] Waiting for simulator to connect on TCP port 4560
INFO  [simulator] Simulator connected on TCP port 4560.
[Msg] Using MAVLink protocol v2.0
Gazebo multi-robot simulator, version 7.0.0
Copyright (C) 2012-2016 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.1.41
[Wrn] [Event.cc:87] Warning: Deleteing a connection right after creation. Make sure to save the ConnectionPtr from a Connect call
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris/motors, deleting message. This warning is printed only once.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris/motor_speed/0, deleting message. This warning is printed only once.
[Wrn] [Publisher.cc:140] Queue limit reached for topic /gazebo/default/iris/motor_speed/1, deleting message. This warning is printed only once.
INFO  [init] Mixer: etc/mixers/quad_w.main.mix on /dev/pwm_output0
INFO  [mavlink] mode: Normal, data rate: 4000000 B/s on udp port 14570 remote port 14550
INFO  [mavlink] mode: Onboard, data rate: 4000000 B/s on udp port 14580 remote port 14540
INFO  [logger] logger started (mode=all)
INFO  [logger] Start file log (type: full)
INFO  [logger] Opened full log file: ./log/2019-01-01/22_08_52.ulg
INFO  [mavlink] MAVLink only on localhost (set param MAV_BROADCAST = 1 to enable network)
INFO  [px4] Startup script returned successfully
pxh> INFO  [ecl/EKF] EKF aligned, (pressure height, IMU buf: 22, OBS buf: 14)
INFO  [ecl/EKF] EKF GPS checks passed (WGS-84 origin set)
INFO  [ecl/EKF] EKF commencing GPS fusion

First question, why i have [Wrn] messages? Is it ok?

After that I open new terminal and run:

    roslaunch mavros px4.launch fcu_url:="udp://:14540@192.168.1.36:14557"

The output is:

... logging to /home/art/.ros/log/4abd3c60-0e12-11e9-81d1-704d7b719e3a/roslaunch-art-29932.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://art:36427/

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: PITCH_270
 * /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: PITCH_270
 * /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: PITCH_270
 * /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: PITCH_270
 * /mavros/distance_sensor/sonar_1_sub/subscriber: True
 * /mavros/fake_gps/eph: 2.0
 * /mavros/fake_gps/epv: 2.0
 * /mavros/fake_gps/fix_type: 3
 * /mavros/fake_gps/geo_origin/alt: 408.0
 * /mavros/fake_gps/geo_origin/lat: 47.3667
 * /mavros/fake_gps/geo_origin/lon: 8.55
 * /mavros/fake_gps/gps_rate: 5.0
 * /mavros/fake_gps/mocap_transform: True
 * /mavros/fake_gps/satellites_visible: 5
 * /mavros/fake_gps/tf/child_frame_id: fix
 * /mavros/fake_gps/tf/frame_id: map
 * /mavros/fake_gps/tf/listen: False
 * /mavros/fake_gps/tf/rate_limit: 10.0
 * /mavros/fake_gps/tf/send: False
 * /mavros/fake_gps/use_mocap: True
 * /mavros/fake_gps/use_vision: False
 * /mavros/fcu_protocol: v2.0
 * /mavros/fcu_url: udp://:14540@192....
 * /mavros/gcs_url: 
 * /mavros/global_position/child_frame_id: base_link
 * /mavros/global_position/frame_id: map
 * /mavros/global_position/gps_uere: 1.0
 * /mavros/global_position/rot_covariance: 99999.0
 * /mavros/global_position/tf/child_frame_id: base_link
 * /mavros/global_position/tf/frame_id: map
 * /mavros/global_position/tf/global_frame_id: earth
 * /mavros/global_position/tf/send: False
 * /mavros/global_position/use_relative_alt: True
 * /mavros/image/frame_id: px4flow
 * /mavros/imu/angular_velocity_stdev: 0.000349065850399
 * /mavros/imu/frame_id: base_link
 * /mavros/imu/linear_acceleration_stdev: 0.0003
 * /mavros/imu/magnetic_stdev: 0.0
 * /mavros/imu/orientation_stdev: 1.0
 * /mavros/local_position/frame_id: map
 * /mavros/local_position/tf/child_frame_id: base_link
 * /mavros/local_position/tf/frame_id: map
 * /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/odometry/frame_tf/body_frame_orientation: frd
 * /mavros/odometry/frame_tf/local_frame: vision_ned
 * /mavros/plugin_blacklist: ['safety_area', 
 * /mavros/plugin_whitelist: []
 * /mavros/px4flow/frame_id: px4flow
 * /mavros/px4flow/ranger_fov: 0.118682389136
 * /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_thrust: False
 * /mavros/setpoint_attitude/tf/child_frame_id: target_attitude
 * /mavros/setpoint_attitude/tf/frame_id: map
 * /mavros/setpoint_attitude/tf/listen: False
 * /mavros/setpoint_attitude/tf/rate_limit: 50.0
 * /mavros/setpoint_attitude/use_quaternion: False
 * /mavros/setpoint_position/mav_frame: LOCAL_NED
 * /mavros/setpoint_position/tf/child_frame_id: target_position
 * /mavros/setpoint_position/tf/frame_id: map
 * /mavros/setpoint_position/tf/listen: False
 * /mavros/setpoint_position/tf/rate_limit: 50.0
 * /mavros/setpoint_velocity/mav_frame: LOCAL_NED
 * /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/time/timesync_mode: MAVLINK
 * /mavros/vibration/frame_id: base_link
 * /mavros/vision_pose/tf/child_frame_id: vision_estimate
 * /mavros/vision_pose/tf/frame_id: map
 * /mavros/vision_pose/tf/listen: False
 * /mavros/vision_pose/tf/rate_limit: 10.0
 * /mavros/vision_speed/listen_twist: True
 * /mavros/vision_speed/twist_cov: True
 * /rosdistro: kinetic
 * /rosversion: 1.12.14

NODES
  /
    mavros (mavros/mavros_node)

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

setting /run_id to 4abd3c60-0e12-11e9-81d1-704d7b719e3a
process[rosout-1]: started with pid [29958]
started core service [/rosout]
process[mavros-2]: started with pid [29976]
[ INFO] [1546380734.947659633]: FCU URL: udp://:14540@192.168.1.36:14557
[ INFO] [1546380734.949963197]: udp0: Bind address: 0.0.0.0:14540
[ INFO] [1546380734.950042996]: udp0: Remote address: 192.168.1.36:14557
[ INFO] [1546380734.950307136]: GCS bridge disabled
[ INFO] [1546380734.955994616]: udp0: Remote address: 127.0.0.1:14580
[ INFO] [1546380734.974533920]: Plugin 3dr_radio loaded
[ INFO] [1546380734.979422538]: Plugin 3dr_radio initialized
[ INFO] [1546380734.979886523]: Plugin actuator_control loaded
[ INFO] [1546380734.986615628]: Plugin actuator_control initialized
[ INFO] [1546380734.991960429]: Plugin adsb loaded
[ INFO] [1546380735.001563922]: Plugin adsb initialized
[ INFO] [1546380735.001747321]: Plugin altitude loaded
[ INFO] [1546380735.003718545]: Plugin altitude initialized
[ INFO] [1546380735.003907883]: Plugin cam_imu_sync loaded
[ INFO] [1546380735.004963479]: Plugin cam_imu_sync initialized
[ INFO] [1546380735.005224423]: Plugin command loaded
[ INFO] [1546380735.023306477]: Plugin command initialized
[ INFO] [1546380735.023546373]: Plugin debug_value loaded
[ INFO] [1546380735.039473866]: Plugin debug_value initialized
[ INFO] [1546380735.039536425]: Plugin distance_sensor blacklisted
[ INFO] [1546380735.040017692]: Plugin fake_gps loaded
[ INFO] [1546380735.095075778]: Plugin fake_gps initialized
[ INFO] [1546380735.095315516]: Plugin ftp loaded
[ INFO] [1546380735.115279588]: Plugin ftp initialized
[ INFO] [1546380735.116041892]: Plugin global_position loaded
[ INFO] [1546380735.159335025]: Plugin global_position initialized
[ INFO] [1546380735.159629813]: Plugin gps_rtk loaded
[ INFO] [1546380735.166748755]: Plugin gps_rtk initialized
[ INFO] [1546380735.167115098]: Plugin hil loaded
[ INFO] [1546380735.201455158]: Plugin hil initialized
[ INFO] [1546380735.201973174]: Plugin home_position loaded
[ INFO] [1546380735.215699911]: Plugin home_position initialized
[ INFO] [1546380735.216039466]: Plugin imu loaded
[ INFO] [1546380735.237388033]: Plugin imu initialized
[ INFO] [1546380735.237646991]: Plugin local_position loaded
[ INFO] [1546380735.253823057]: Plugin local_position initialized
[ INFO] [1546380735.254044523]: Plugin log_transfer loaded
[ INFO] [1546380735.263467441]: Plugin log_transfer initialized
[ INFO] [1546380735.264013450]: Plugin manual_control loaded
[ INFO] [1546380735.273053383]: Plugin manual_control initialized
[ INFO] [1546380735.273270064]: Plugin mocap_pose_estimate loaded
[ INFO] [1546380735.283866407]: Plugin mocap_pose_estimate initialized
[ INFO] [1546380735.284049020]: Plugin obstacle_distance loaded
[ INFO] [1546380735.290744171]: Plugin obstacle_distance initialized
[ INFO] [1546380735.290951943]: Plugin odom loaded
[ INFO] [1546380735.305990187]: Plugin odom initialized
[ INFO] [1546380735.306415944]: Plugin param loaded
[ INFO] [1546380735.311829492]: Plugin param initialized
[ INFO] [1546380735.312007970]: Plugin px4flow loaded
[ INFO] [1546380735.330017687]: Plugin px4flow initialized
[ INFO] [1546380735.330066679]: Plugin rangefinder blacklisted
[ INFO] [1546380735.330322914]: Plugin rc_io loaded
[ INFO] [1546380735.345095737]: Plugin rc_io initialized
[ INFO] [1546380735.345146180]: Plugin safety_area blacklisted
[ INFO] [1546380735.345361162]: Plugin setpoint_accel loaded
[ INFO] [1546380735.356214938]: Plugin setpoint_accel initialized
[ INFO] [1546380735.356564776]: Plugin setpoint_attitude loaded
[ INFO] [1546380735.385892450]: Plugin setpoint_attitude initialized
[ INFO] [1546380735.386145617]: Plugin setpoint_position loaded
[ INFO] [1546380735.424888488]: Plugin setpoint_position initialized
[ INFO] [1546380735.425140000]: Plugin setpoint_raw loaded
[ INFO] [1546380735.452127694]: Plugin setpoint_raw initialized
[ INFO] [1546380735.452344765]: Plugin setpoint_velocity loaded
[ INFO] [1546380735.469560711]: Plugin setpoint_velocity initialized
[ INFO] [1546380735.469896109]: Plugin sys_status loaded
[ INFO] [1546380735.495772962]: Plugin sys_status initialized
[ INFO] [1546380735.496016337]: Plugin sys_time loaded
[ INFO] [1546380735.514040676]: TM: Timesync mode: MAVLINK
[ INFO] [1546380735.515882797]: Plugin sys_time initialized
[ INFO] [1546380735.516059654]: Plugin trajectory loaded
[ INFO] [1546380735.532392123]: Plugin trajectory initialized
[ INFO] [1546380735.532651099]: Plugin vfr_hud loaded
[ INFO] [1546380735.533984934]: Plugin vfr_hud initialized
[ INFO] [1546380735.534040266]: Plugin vibration blacklisted
[ INFO] [1546380735.534225083]: Plugin vision_pose_estimate loaded
[ INFO] [1546380735.555498815]: Plugin vision_pose_estimate initialized
[ INFO] [1546380735.555661684]: Plugin vision_speed_estimate loaded
[ INFO] [1546380735.571258605]: Plugin vision_speed_estimate initialized
[ INFO] [1546380735.571471899]: Plugin waypoint loaded
[ INFO] [1546380735.582521170]: Plugin waypoint initialized
[ INFO] [1546380735.583231313]: Plugin wind_estimation loaded
[ INFO] [1546380735.587251027]: Plugin wind_estimation initialized
[ INFO] [1546380735.587428824]: Autostarting mavlink via USB on PX4
[ INFO] [1546380735.587610976]: Built-in SIMD instructions: SSE, SSE2
[ INFO] [1546380735.587685371]: Built-in MAVLink package version: 2018.12.12
[ INFO] [1546380735.587722872]: Known MAVLink dialects: common ardupilotmega ASLUAV autoquad icarous matrixpilot paparazzi slugs standard uAvionix ualberta
[ INFO] [1546380735.587769790]: MAVROS started. MY ID 1.240, TARGET ID 1.1
[ INFO] [1546380735.589210172]: IMU: Attitude quaternion IMU detected!
[ INFO] [1546380735.599585363]: IMU: High resolution IMU detected!
[ INFO] [1546380735.935644496]: CON: Got HEARTBEAT, connected. FCU: PX4 Autopilot
[ INFO] [1546380735.937629041]: IMU: High resolution IMU detected!
[ INFO] [1546380735.946715274]: IMU: Attitude quaternion IMU detected!
[ INFO] [1546380736.939360733]: VER: 1.1: Capabilities         0x000000000000e4ef
[ INFO] [1546380736.939420231]: VER: 1.1: Flight software:     01090040 (000000007BA76664)
[ INFO] [1546380736.939451032]: VER: 1.1: Middleware software: 01090040 (000000007BA76664)
[ INFO] [1546380736.939474912]: VER: 1.1: OS software:         040f00ff (0000000000000000)
[ INFO] [1546380736.939495185]: VER: 1.1: Board hardware:      00000001
[ INFO] [1546380736.939523836]: VER: 1.1: VID/PID:             0000:0000
[ INFO] [1546380736.939545404]: VER: 1.1: UID:                 4954414c44494e4f
[ WARN] [1546380737.003614811]: CMD: Unexpected command 520, result 0
[ INFO] [1546380750.937887596]: WP: mission received

There is WARNING
[ WARN] [1546380737.003614811]: CMD: Unexpected command 520, result 0
Is it ok?

And I have this at Gazebo:

After I run at new terminal:

    rosservice call /mavros/cmd/arming "value: true"

Output:

    success: True
    result: 0
    rosservice call /mavros/cmd/takeoff "{min_pitch: 0.0, yaw: 0.0, latitude: 0.0, longitude: 0.0, altitude: 3.0}"    

Output:

    success: True
    result: 0

Quadrocopter does not have time to take off. It immediately takes away

PX4 output:

WARN  [navigator] Using minimum takeoff altitude: 2.50 m
INFO  [logger] Start file log (type: mission)
INFO  [logger] Opened mission log file: ./mission_log/2019-01-01/22_31_41.ulg
INFO  [commander] Takeoff detected

I dont know, why I see warning and how to make a quadcopter just take off. Could you help me?

And i see this error at MAVROS terminal:

[ERROR] [1546381750.724092572]: TM : Time jump detected. Resetting time synchroniser.

I don’t understand it too.

Thank you all in advance for your help!

This seems to happen when your system is lagging and it needs more computing power to catch up with the simulation time.

Thank you!
What about another questions?)

Warnings are not errors. I can’t see anything wrong apart from the time jump.

But why quadcopter starts to fly sideways? I understand that this is most likely due to some parameter, but I cannot find with which.

Same problem mine is also flying sideway. Did you find a solution ? @Zenkin

The takeoff service expects a the latitude and longitude to be provided. These are not (0,0) by default. Use rostopic echo /mavros/global_position/global to find your latitude and longitude and then put those values in the command. Example:

rosservice call /mavros/cmd/takeoff "{min_pitch: 0.0, yaw: 0.0, latitude: 47.397742, longitude: 8.5455936, altitude: 3.0}"    
2 Likes

Hi!! thanks for your answer.
I run this command

rosservice call /mavros/cmd/takeoff "{min_pitch: 0.0, yaw: 0.0, latitude: 47.397742, longitude: 8.5455936, altitude: 3.0}"

and the drone flies but I still have this message
FCU: Using minimum takeoff altitude: 2.50 m and is not flying at 3m…

Hi did you solve this issue? I have too!

Where you able to solve it?

I couldnt solve it .