PX4 SITL with Gazebo - Custom Vehicle Model

Hi All,

Wondering if anyone can advise:

I’m trying to produce a model of our own drone for simulation using Gazebo (7.15), PX4 SITL (v1.9.1) and ROS Kinetic for offboard control but I’m running into trouble.

I have the simulation models for my custom drone in a ROS pkg (in catkin_ws/src), and although the PX4 Firmware repo exists outside my catkin_ws, I have symbolic links to both Firmware and Tools/sitl_gazebo in the src dir (I understand it’s necessary to have them in src, can anyone tell me why?).

My simulation model is urdf based, with a dir of the following form
(xacro file is used to generate the .urdf)

robot/
    robot.urdf
    meshes/
        robot_mesh.dae
    xacro/
        robot.urdf.xacro

The launch file that I’m using is

<?xml version="1.0"?>
    <launch>
        <!-- MAVROS posix SITL environment launch script -->
        <!-- launches MAVROS, PX4 SITL, Gazebo environment, and spawns vehicle -->
        <!-- vehicle pose -->
        <arg name="x" default="0"/>
        <arg name="y" default="0"/>
        <arg name="z" default="0"/>
        <arg name="R" default="0"/>
        <arg name="P" default="0"/>
        <arg name="Y" default="0"/>
        <!-- vehicle model and world -->
        <arg name="est" default="ekf2"/>
        <arg name="vehicle" default="iris"/>

        <arg name="xacro" default="false" />
        <arg unless="$(arg xacro)" name="format" default="sdf" />
        <arg if="$(arg xacro)" name="format" default="urdf" />

        <arg if="$(arg xacro)" name="description_flag" default="-param" />
        <arg unless="$(arg xacro)" name="description_flag" default="-file" />

        <arg unless="$(arg xacro)" name="description_file"
            default="$(find sim_pkg)/models/$(arg vehicle)/robot.$(arg format)" />
        <arg if="$(arg xacro)" name="description_file" 
            default="/robot_description" />

        <!-- Generate URDF file from XACRO, and load in ROS param server -->
        <param if="$(arg xacro)" name="robot_description"
          command="$(find xacro)/xacro $(find we_sim_gazebo)/models/$(arg vehicle)/xacro/robot.$(arg format).xacro --check-order" />
          <!-- $(find xacro) looks for the xacro pkg (shipped with ROS/Gazebo), NOT the xacro launch arg -->

        <arg name="world" default="$(find sim_pkg)/worlds/empty.world" />
        
        <!-- gazebo configs -->
        <arg name="gui" default="true"/>
        <arg name="debug" default="false"/>
        <arg name="verbose" default="false"/>
        <arg name="paused" default="false"/>
        <arg name="respawn_gazebo" default="false"/>
        <!-- MAVROS configs -->
        <!-- <arg name="fcu_url" default="udp://:14540@localhost:14557"/> -->
        <arg name="fcu_url" default="udp://:14540@192.168.100.89:14557"/>
        <arg name="respawn_mavros" default="false"/>
        <!-- PX4 configs -->
        <arg name="interactive" default="true"/>
        <!-- PX4 SITL and Gazebo -->
        <include file="$(find sim_pkg)/launch/posix_sitl.launch">
            <arg name="x" value="$(arg x)"/>
            <arg name="y" value="$(arg y)"/>
            <arg name="z" value="$(arg z)"/>
            <arg name="R" value="$(arg R)"/>
            <arg name="P" value="$(arg P)"/>
            <arg name="Y" value="$(arg Y)"/>
            <arg name="world" value="$(arg world)"/>
            <arg name="vehicle" value="$(arg vehicle)"/>
            <arg name="xacro" value="false" />
            <arg name="description_file" value="$(arg description_file)" />
            <arg name="description_flag" value="$(arg description_flag)" />
            <arg name="format" value="$(arg format)" />
            <arg name="gui" value="$(arg gui)"/>
            <arg name="interactive" value="$(arg interactive)"/>
            <arg name="debug" value="$(arg debug)"/>
            <arg name="verbose" value="$(arg verbose)"/>
            <arg name="paused" value="$(arg paused)"/>
            <arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
        </include>
        <!-- MAVROS -->
        <include file="$(find mavros)/launch/px4.launch">
            <!-- GCS link is provided by SITL -->
            <arg name="gcs_url" value=""/>
            <arg name="fcu_url" value="$(arg fcu_url)"/>
            <arg name="respawn_mavros" value="$(arg respawn_mavros)"/>
        </include>
    </launch>

where the second launch file (posix_sitl.launch) is:

<?xml version="1.0"?>
<launch>
    <!-- Posix SITL environment launch script -->
    <!-- launches PX4 SITL, Gazebo environment, and spawns vehicle -->
    <!-- vehicle pose -->
    <arg name="x" default="0"/>
    <arg name="y" default="0"/>
    <arg name="z" default="0"/>
    <arg name="R" default="0"/>
    <arg name="P" default="0"/>
    <arg name="Y" default="0"/>
    
    <!-- vehicle model and world -->
    <arg name="est" default="ekf2"/>
    <arg name="vehicle" default="iris"/>

    <arg name="xacro" default="false" />
    <arg unless="$(arg xacro)" name="format" default="sdf" />
    <arg if="$(arg xacro)" name="format" default="urdf" />

    <arg if="$(arg xacro)" name="description_flag" default="-param" />
    <arg unless="$(arg xacro)" name="description_flag" default="-file" />

    <arg unless="$(arg xacro)" name="description_file"
        default="$(find we_sim_gazebo)/models/$(arg vehicle)/robot.$(arg format)" />
    <arg if="$(arg xacro)" name="description_file" 
        default="/robot_description" />

    <!-- Generate URDF file from XACRO, and load in ROS param server -->
    <param if="$(arg xacro)" name="robot_description"
      command="$(find xacro)/xacro $(find we_sim_gazebo)/models/$(arg vehicle)/xacro/robot.$(arg format).xacro --check-order" />

    <arg name="world" default="$(find we_sim_gazebo)/worlds/empty.world"/>
    
    <env name="PX4_SIM_MODEL" value="hexa_x" />
    <env name="PX4_ESTIMATOR" value="$(arg est)" />

    <!-- gazebo configs -->
    <arg name="gui" default="true"/>
    <arg name="debug" default="false"/>
    <arg name="verbose" default="false"/>
    <arg name="paused" default="false"/>
    <arg name="respawn_gazebo" default="false"/>
    <!-- PX4 configs -->
    <arg name="interactive" default="true"/>
    <!-- PX4 SITL -->
    <arg unless="$(arg interactive)" name="px4_command_arg1" value="-d"/>
    <arg     if="$(arg interactive)" name="px4_command_arg1" value=""/>
    <node name="sitl" pkg="px4" type="px4" output="screen" 
      args="$(find px4)/ROMFS/px4fmu_common -s etc/init.d-posix/rcS $(arg px4_command_arg1)" required="true"/>

    <!-- Gazebo sim -->
    <include file="$(find gazebo_ros)/launch/empty_world.launch">
        <arg name="gui" value="$(arg gui)"/>
        <arg name="world_name" value="$(arg world)"/>
        <arg name="debug" value="$(arg debug)"/>
        <arg name="verbose" value="$(arg verbose)"/>
        <arg name="paused" value="$(arg paused)"/>
        <arg name="respawn_gazebo" value="$(arg respawn_gazebo)"/>
    </include>
    <!-- gazebo model -->
    <node name="$(anon vehicle_spawn)" pkg="gazebo_ros" type="spawn_model" output="screen" args="-$(arg 
      format) $(arg description_flag) $(arg description_file) -model $(arg vehicle) -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg R) -P $(arg P) -Y $(arg Y)" />

</launch>

I then launch with the following line:

roslaunch we_sim_gazebo mavros_posix_sitl.launch vehicle:=june xacro:=true

And get the following output in the terminal:
(Can anyone let me know what is the significance of the line “Error: Unknown model ‘hexa_x’” ?)

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.0003490659 // 0...
 * /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/landing_target/camera/fov_x: 2.0071286398
 * /mavros/landing_target/camera/fov_y: 2.0071286398
 * /mavros/landing_target/image/height: 480
 * /mavros/landing_target/image/width: 640
 * /mavros/landing_target/land_target_type: VISION_FIDUCIAL
 * /mavros/landing_target/listen_lt: False
 * /mavros/landing_target/mav_frame: LOCAL_NED
 * /mavros/landing_target/target_size/x: 0.3
 * /mavros/landing_target/target_size/y: 0.3
 * /mavros/landing_target/tf/child_frame_id: camera_center
 * /mavros/landing_target/tf/frame_id: landing_target
 * /mavros/landing_target/tf/listen: False
 * /mavros/landing_target/tf/rate_limit: 10.0
 * /mavros/landing_target/tf/send: True
 * /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/in/child_frame_id: base_link
 * /mavros/odometry/in/frame_id: odom
 * /mavros/odometry/in/frame_tf/body_frame_orientation: flu
 * /mavros/odometry/in/frame_tf/local_frame: local_origin_ned
 * /mavros/odometry/out/frame_tf/body_frame_orientation: frd
 * /mavros/odometry/out/frame_tf/local_frame: vision_ned
 * /mavros/plugin_blacklist: ['safety_area', '...
 * /mavros/plugin_whitelist: []
 * /mavros/px4flow/frame_id: px4flow
 * /mavros/px4flow/ranger_fov: 0.118682
 * /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_raw/thrust_scaling: 1.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
 * /mavros/wheel_odometry/child_frame_id: base_link
 * /mavros/wheel_odometry/count: 2
 * /mavros/wheel_odometry/frame_id: map
 * /mavros/wheel_odometry/send_raw: True
 * /mavros/wheel_odometry/send_twist: False
 * /mavros/wheel_odometry/tf/child_frame_id: base_link
 * /mavros/wheel_odometry/tf/frame_id: map
 * /mavros/wheel_odometry/tf/send: True
 * /mavros/wheel_odometry/use_rpm: False
 * /mavros/wheel_odometry/vel_error: 0.1
 * /mavros/wheel_odometry/wheel0/radius: 0.05
 * /mavros/wheel_odometry/wheel0/x: 0.0
 * /mavros/wheel_odometry/wheel0/y: -0.15
 * /mavros/wheel_odometry/wheel1/radius: 0.05
 * /mavros/wheel_odometry/wheel1/x: 0.0
 * /mavros/wheel_odometry/wheel1/y: 0.15
 * /robot_description: <?xml version="1....
 * /rosdistro: kinetic
 * /rosversion: 1.12.14
 * /use_sim_time: True

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

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

setting /run_id to c710799c-aca7-11e9-9a23-9cb6d0c132b1
process[rosout-1]: started with pid [26419]
started core service [/rosout]
process[sitl-2]: started with pid [26444]
INFO  [px4] Creating symlink /home/kieran-dwn/ROS_development/src/Firmware/ROMFS/px4fmu_common -> /home/kieran-dwn/.ros/etc
0 WARNING: setRealtimeSched failed (not run as root?)

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

px4 starting.

INFO  [px4] Calling startup script: /bin/sh etc/init.d-posix/rcS 0
Error: Unknown model 'hexa_x'
ERROR [px4] Startup script returned with return value: 256
pxh> process[gazebo-3]: started with pid [26457]
process[gazebo_gui-4]: started with pid [26465]
process[vehicle_spawn_kieran_dwn_xps15_9570_26393_8065768406667524225-5]: started with pid [26470]
process[mavros-6]: started with pid [26471]
[ INFO] [1563817222.245290990]: FCU URL: udp://:14540@192.168.100.89:14557
[ INFO] [1563817222.246993076]: udp0: Bind address: 0.0.0.0:14540
[ INFO] [1563817222.247045052]: udp0: Remote address: 192.168.100.89:14557
[ INFO] [1563817222.247261898]: GCS bridge disabled
[ INFO] [1563817222.257104743]: Plugin 3dr_radio loaded
[ INFO] [1563817222.259385322]: Plugin 3dr_radio initialized
[ INFO] [1563817222.259500716]: Plugin actuator_control loaded
[ INFO] [1563817222.262633958]: Plugin actuator_control initialized
[ INFO] [1563817222.265557070]: Plugin adsb loaded
[ INFO] [1563817222.268685648]: Plugin adsb initialized
[ INFO] [1563817222.268821621]: Plugin altitude loaded
[ INFO] [1563817222.269966672]: Plugin altitude initialized
[ INFO] [1563817222.270072623]: Plugin cam_imu_sync loaded
[ INFO] [1563817222.270706015]: Plugin cam_imu_sync initialized
[ INFO] [1563817222.270836741]: Plugin command loaded
[ INFO] [1563817222.276185484]: Plugin command initialized
[ INFO] [1563817222.276315417]: Plugin companion_process_status loaded
[ INFO] [1563817222.278605640]: Plugin companion_process_status initialized
[ INFO] [1563817222.278767930]: Plugin debug_value loaded
[ INFO] [1563817222.283322001]: Plugin debug_value initialized
[ INFO] [1563817222.283365091]: Plugin distance_sensor blacklisted
[ INFO] [1563817222.283581487]: Plugin fake_gps loaded
[ INFO] [1563817222.296636807]: Plugin fake_gps initialized
[ INFO] [1563817222.296874125]: Plugin ftp loaded
[ INFO] [1563817222.304210631]: Plugin ftp initialized
[ INFO] [1563817222.304415406]: Plugin global_position loaded
[ INFO] [1563817222.318287038]: Plugin global_position initialized
[ INFO] [1563817222.318448603]: Plugin gps_rtk loaded
[ INFO] [1563817222.320566247]: Plugin gps_rtk initialized
[ INFO] [1563817222.320754273]: Plugin hil loaded
[ INFO] [1563817222.332584141]: Plugin hil initialized
[ INFO] [1563817222.332780356]: Plugin home_position loaded
[ INFO] [1563817222.336172940]: Plugin home_position initialized
[ INFO] [1563817222.336355932]: Plugin imu loaded
[ INFO] [1563817222.344216376]: Plugin imu initialized
[ INFO] [1563817222.344414678]: Plugin landing_target loaded
[ INFO] [1563817222.356800938]: Plugin landing_target initialized
[ INFO] [1563817222.356995367]: Plugin local_position loaded
[ INFO] [1563817222.362626378]: Plugin local_position initialized
[ INFO] [1563817222.362792942]: Plugin log_transfer loaded
[ INFO] [1563817222.365625963]: Plugin log_transfer initialized
[ INFO] [1563817222.365821606]: Plugin manual_control loaded
[ INFO] [1563817222.368471671]: Plugin manual_control initialized
[ INFO] [1563817222.368615624]: Plugin mocap_pose_estimate loaded
[ INFO] [1563817222.371835490]: Plugin mocap_pose_estimate initialized
[ INFO] [1563817222.371999607]: Plugin mount_control loaded
[ INFO] [1563817222.374359692]: Plugin mount_control initialized
[ INFO] [1563817222.374479627]: Plugin obstacle_distance loaded
[ INFO] [1563817222.376492629]: Plugin obstacle_distance initialized
[ INFO] [1563817222.376605354]: Plugin odom loaded
[ INFO] [1563817222.382330979]: Plugin odom initialized
[ INFO] [1563817222.382524334]: Plugin param loaded
[ INFO] [1563817222.385288213]: Plugin param initialized
[ INFO] [1563817222.385402038]: Plugin px4flow loaded
[ INFO] [1563817222.391385004]: Plugin px4flow initialized
[ INFO] [1563817222.391415528]: Plugin rangefinder blacklisted
[ INFO] [1563817222.391564656]: Plugin rc_io loaded
[ INFO] [1563817222.394590486]: Plugin rc_io initialized
[ INFO] [1563817222.394620293]: Plugin safety_area blacklisted
[ INFO] [1563817222.394738130]: Plugin setpoint_accel loaded
[ INFO] [1563817222.398138638]: Plugin setpoint_accel initialized
[ INFO] [1563817222.398363400]: Plugin setpoint_attitude loaded
[ INFO] [1563817222.410601199]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1563817222.411009043]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1563817222.412559919]: Plugin setpoint_attitude initialized
[ INFO] [1563817222.412722838]: Plugin setpoint_position loaded
[ INFO] [1563817222.424679897]: Plugin setpoint_position initialized
[ INFO] [1563817222.424837230]: Plugin setpoint_raw loaded
[ INFO] [1563817222.439897338]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1563817222.440465270]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1563817222.442839585]: Plugin setpoint_raw initialized
[ INFO] [1563817222.442990682]: Plugin setpoint_velocity loaded
[ INFO] [1563817222.448346641]: Plugin setpoint_velocity initialized
[ INFO] [1563817222.448631773]: Plugin sys_status loaded
[ INFO] [1563817222.459322072]: Plugin sys_status initialized
[ INFO] [1563817222.459522931]: Plugin sys_time loaded
[ INFO] [1563817222.464241650]: TM: Timesync mode: MAVLINK
[ INFO] [1563817222.465241838]: Plugin sys_time initialized
[ INFO] [1563817222.465368392]: Plugin trajectory loaded
[ INFO] [1563817222.470026610]: Plugin trajectory initialized
[ INFO] [1563817222.470158861]: Plugin vfr_hud loaded
[ INFO] [1563817222.470748424]: Plugin vfr_hud initialized
[ INFO] [1563817222.470772486]: Plugin vibration blacklisted
[ INFO] [1563817222.470875487]: Plugin vision_pose_estimate loaded
[ INFO] [1563817222.477605908]: Plugin vision_pose_estimate initialized
[ INFO] [1563817222.477774061]: Plugin vision_speed_estimate loaded
[ INFO] [1563817222.481215851]: Plugin vision_speed_estimate initialized
[ INFO] [1563817222.481408166]: Plugin waypoint loaded
[ INFO] [1563817222.485875296]: Plugin waypoint initialized
[ INFO] [1563817222.485919200]: Plugin wheel_odometry blacklisted
[ INFO] [1563817222.486100629]: Plugin wind_estimation loaded
[ INFO] [1563817222.486820302]: Plugin wind_estimation initialized
[ INFO] [1563817222.486858801]: Autostarting mavlink via USB on PX4
[ INFO] [1563817222.486957501]: Built-in SIMD instructions: SSE, SSE2
[ INFO] [1563817222.486973103]: Built-in MAVLink package version: 2019.7.7
[ INFO] [1563817222.486995140]: Known MAVLink dialects: common ardupilotmega ASLUAV autoquad icarous matrixpilot paparazzi slugs standard uAvionix ualberta
[ INFO] [1563817222.487006625]: MAVROS started. MY ID 1.240, TARGET ID 1.1
SpawnModel script started
[INFO] [1563817222.705218, 0.000000]: Loading model XML from ros parameter
[INFO] [1563817222.708090, 0.000000]: Waiting for service /gazebo/spawn_urdf_model
[ INFO] [1563817223.781027385, 0.024000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1563817223.802219590, 0.044000000]: Physics dynamic reconfigure ready.
[INFO] [1563817223.913664, 0.152000]: Calling service /gazebo/spawn_urdf_model
[INFO] [1563817223.972098, 0.172000]: Spawn status: SpawnModel: Successfully spawned entity
[ INFO] [1563817224.201284557, 0.172000000]: Loading gazebo_ros_control plugin
[ INFO] [1563817224.201359332, 0.172000000]: Starting gazebo_ros_control plugin in namespace: /june
[ INFO] [1563817224.201959807, 0.172000000]: gazebo_ros_control plugin is waiting for model URDF in parameter [/robot_description] on the ROS param server.
[vehicle_spawn_kieran_dwn_xps15_9570_26393_8065768406667524225-5] process has finished cleanly
log file: /home/kieran-dwn/.ros/log/c710799c-aca7-11e9-9a23-9cb6d0c132b1/vehicle_spawn_kieran_dwn_xps15_9570_26393_8065768406667524225-5*.log
[ INFO] [1563817224.317286473, 0.172000000]: Loaded gazebo_ros_control.
[ INFO] [1563817224.346594459, 0.196000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1563817224.365535178, 0.216000000]: Physics dynamic reconfigure ready.

And following a (failed) attempt to speak to mavros,

rosservice call /mavros/set_mode "base_mode: 0
custom_mode: 'OFFBOARD'"

the following is displayed (in the terminal px4/mavros/gazebo[_spawn] was launched from):

[ERROR] [1563817277.697662954, 53.472000000]: MODE: Unsupported FCU

How can I get mavros to communicate with the model I have of the drone - I have the same problem with our drone and the iris model pulled from the px4 dirs (identical except from location)?

I’ve included the custom xacro (slightly censored) in a comment below.

Any help would be greatly appreciated - I’ve tried to be as comprehensive as possible but please let me know if any more information is needed.

Thanks,
K

<?xml version="1.0"?>
<!-- ROBOT PLATFORM: -->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="robot">
    
    <gazebo>
        <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
            <robotNamespace>/robot</robotNamespace>
            <!-- <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType> -->
            <legacyModeNS>true</legacyModeNS> 
            <!-- Line above is fix found here: -->
            <!-- https://answers.ros.org/question/292444/gazebo_ros_control-plugin-gazeboroscontrolplugin-missing-legacymodens-defaultrobothwsim/ -->
        </plugin>
    </gazebo>

    <!-- *** MACROS *** -->
    <xacro:property name="PI" value="3.1415926535897931" />

    <xacro:macro name="default_origin">
        <origin rpy="0 0 0" xyz="0 0 0" />
    </xacro:macro>

    <xacro:macro name="rotor_model" params="id xyz dir col">
        <!-- Propeller -->
        <link name="rotor_${id}">
          <pose frame=''>${xyz} 0 -0 0</pose>
          <inertial>
            <pose frame=''>0 0 0 0 -0 0</pose>
            <mass value="0.005" />
            <inertia ixx="9.75e-07" ixy="0" ixz="0" iyy="0.000273104" iyz="0" izz="0.000274004" />
          </inertial>
          <collision name='rotor_${id}_collision'>
            <pose frame=''>0 0 0 0 -0 0</pose>
            <geometry>
              <cylinder length="0.005" radius="0.128" />
            </geometry>
            <surface>
              <contact>
                <ode/>
              </contact>
              <friction>
                <ode/>
              </friction>
            </surface>
          </collision>
          <visual name='rotor_${id}_visual'>
            <pose frame=''>0 0 0 0 -0 0</pose>
            <geometry>
              <mesh scale="0.8 0.8 0.8" 
                filename="/path/to/catkin_ws/src/Firmware/Tools/sitl_gazebo/models/rotors_description/meshes/iris_prop_${dir}.dae" />
            </geometry>
          </visual>
        </link>
        <joint name='rotor_${id}_joint' type='fixed'>
          <parent link="base_link" />
          <child link="rotor_${id}" />
          <origin rpy="0 0 0" xyz="${xyz}"/>
          <axis xyz="0 0 1" />
          <limit lower="-1e+16" upper="1e+16" effort="1e+06" velocity="1e+06"/>
        </joint>

        <!-- Gazebo tags (non-URDF) -->
        <gazebo reference="rotor_${id}">
            <material>${col}</material> <!--colour-->
            <!-- <gravity>1</gravity> -->
            <velocity_decay />
        </gazebo>
        <gazebo reference="rotor_${id}_joint">
            <implicitSpringDamper>true</implicitSpringDamper>
            <springStiffness>0</springStiffness>
            <springReference>0</springReference>
        </gazebo>

        <!-- Plugin -->
        <plugin name='motor_${id}_model' filename='libgazebo_motor_model.so'>
          <robotNamespace/>
          <jointName>rotor_${id}_joint</jointName>
          <linkName>rotor_${id}</linkName>
          <turningDirection>${dir}</turningDirection>
          <timeConstantUp>0.0125</timeConstantUp>
          <timeConstantDown>0.025</timeConstantDown>
          <maxRotVelocity>1100</maxRotVelocity>
          <motorConstant>8.54858e-06</motorConstant>
          <momentConstant>0.06</momentConstant>
          <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
          <motorNumber>${id}</motorNumber>
          <rotorDragCoefficient>0.000806428</rotorDragCoefficient>
          <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
          <motorSpeedPubTopic>/motor_speed/${id}</motorSpeedPubTopic>
          <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
        </plugin>
    </xacro:macro>

    <!-- *** ROBOT DESCRIPTION *** -->
    <link name="base_link">
      <!-- VISUAL MODEL -->
      <visual>
          <origin rpy="0 0 0" xyz="0 0 0" />
          <geometry>
              <mesh filename="$(find sim_pkg)/models/robot/meshes/robot_mesh.dae"/>
          </geometry>
      </visual>

      <!-- COLLISION MODEL -->
      <!-- Simple shape to reduce computational expense. -->
      <collision>
          <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
          <geometry>
              <cylinder radius="0.765" length="0.020" />
          </geometry>
      </collision>

      <!-- INERTIAL MODEL -->
      <inertial>
          <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
          <mass value="7.40" />
          <inertia ixx="0.14368" ixy="0" ixz="0" iyy="0.14368" iyz="0" izz="0.27244" />
      </inertial>
    </link>

    <!-- PROPELLERS -->
    <!-- Front Right -->
    <xacro:rotor_model id="0" dir="ccw" xyz="0.2625 -0.150 0.050" col="Gazebo/Blue"/>

    <!-- Mid Right -->
    <xacro:rotor_model id="1" dir="cw" xyz="0 -0.240 0.050" col="Gazebo/Black"/>

    <!-- Rear Right -->
    <xacro:rotor_model id="2" dir="ccw" xyz="-0.2625 -0.150 0.050" col="Gazebo/Black"/>

    <!-- Rear Left -->
    <xacro:rotor_model id="3" dir="cw" xyz="-0.2625 0.150 0.050" col="Gazebo/Black"/>

    <!-- Mid Left -->
    <xacro:rotor_model id="4" dir="ccw" xyz="0 0.240 0.050" col="Gazebo/Black"/>

    <!-- Front Left -->
    <xacro:rotor_model id="5" dir="cw" xyz="0.2625 0.150 0.050" col="Gazebo/Blue"/>

    <!-- REQUIRED? -->
    <plugin name='rosbag' filename='libgazebo_multirotor_base_plugin.so'>
      <robotNamespace/>
      <linkName>base_link</linkName>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>

    <!-- GAZEBO PHYSICAL PROPERTIES -->
    <!-- Sets physical properties for use in Gazebo simulation. -->
    <gazebo reference="base_link">
        <kp>100000.0</kp> <!--static contant stiffness-->
        <kd>100000.0</kd> <!--dynamic contant stiffness-->
        <mu1>10.0</mu1> <!--static coeff. friction-->
        <mu2>10.0</mu2> <!--dynamic coeff. friction-->
        <material>Gazebo/Grey</material> <!--colour-->
    </gazebo>

    <!-- custom model -->
    <gazebo>
        <plugin name="drag_model" filename="libdrag_model.so">
          <rho>1.225</rho>
          <coeff>0.6</coeff>
          <aref>1.0</aref>
          <cpx>0.0</cpx> <!-- Centre of Pressure Position - Constant? -->
          <cpy>0.0</cpy>
          <cpz>0.0</cpz>
        </plugin>
    </gazebo>

    <!-- PX4 SENSORS -->
    <plugin name='gps_plugin' filename='libgazebo_gps_plugin.so'>
      <robotNamespace/>
      <gpsNoise>true</gpsNoise>
    </plugin>
    <plugin name='magnetometer_plugin' filename='libgazebo_magnetometer_plugin.so'>
      <robotNamespace/>
      <pubRate>20</pubRate>
      <noiseDensity>0.0004</noiseDensity>
      <randomWalk>6.4e-06</randomWalk>
      <biasCorrelationTime>600</biasCorrelationTime>
      <magTopic>/mag</magTopic>
    </plugin>
    <plugin name='barometer_plugin' filename='libgazebo_barometer_plugin.so'>
      <robotNamespace/>
      <pubRate>10</pubRate>
      <baroTopic>/baro</baroTopic>
    </plugin>
    <plugin name='rotors_gazebo_imu_plugin' filename='libgazebo_imu_plugin.so'>
      <robotNamespace/>
      <linkName>/imu_link</linkName>
      <imuTopic>/imu</imuTopic>
      <gyroscopeNoiseDensity>0.0003394</gyroscopeNoiseDensity>
      <gyroscopeRandomWalk>3.8785e-05</gyroscopeRandomWalk>
      <gyroscopeBiasCorrelationTime>1000.0</gyroscopeBiasCorrelationTime>
      <gyroscopeTurnOnBiasSigma>0.0087</gyroscopeTurnOnBiasSigma>
      <accelerometerNoiseDensity>0.004</accelerometerNoiseDensity>
      <accelerometerRandomWalk>0.006</accelerometerRandomWalk>
      <accelerometerBiasCorrelationTime>300.0</accelerometerBiasCorrelationTime>
      <accelerometerTurnOnBiasSigma>0.196</accelerometerTurnOnBiasSigma>
    </plugin>

    <!-- PX4 CONTROL INTERFACE -->
    <plugin name='mavlink_interface' filename='libgazebo_mavlink_interface.so'>
      <robotNamespace/>
      <imuSubTopic>/imu</imuSubTopic>
      <gpsSubTopic>/gps</gpsSubTopic>
      <magSubTopic>/mag</magSubTopic>
      <baroSubTopic>/baro</baroSubTopic>
      <mavlink_addr>INADDR_ANY</mavlink_addr>
      <mavlink_udp_port>14560</mavlink_udp_port>
      <mavlink_tcp_port>4560</mavlink_tcp_port>
      <serialEnabled>false</serialEnabled>
      <serialDevice>/dev/ttyACM0</serialDevice>
      <baudRate>921600</baudRate>
      <qgc_addr>INADDR_ANY</qgc_addr>
      <qgc_udp_port>14550</qgc_udp_port>
      <sdk_addr>INADDR_ANY</sdk_addr>
      <sdk_udp_port>14540</sdk_udp_port>
      <hil_mode>false</hil_mode>
      <hil_state_level>false</hil_state_level>
      <vehicle_is_tailsitter>false</vehicle_is_tailsitter>
      <send_vision_estimation>true</send_vision_estimation>
      <send_odometry>false</send_odometry>
      <enable_lockstep>true</enable_lockstep>
      <use_tcp>true</use_tcp>
      <motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic>
      <control_channels>
        <channel name='rotor1'>
          <input_index>0</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1000</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>100</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
        </channel>
        <channel name='rotor2'>
          <input_index>1</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1000</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>100</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
        </channel>
        <channel name='rotor3'>
          <input_index>2</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1000</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>100</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
        </channel>
        <channel name='rotor4'>
          <input_index>3</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1000</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>100</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
        </channel>
         <channel name='rotor5'>
          <input_index>4</input_index>
          <input_offset>1</input_offset>
          <input_scaling>324.6</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>0</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
          <joint_control_pid>
            <p>0.1</p>
            <i>0</i>
            <d>0</d>
            <iMax>0.0</iMax>
            <iMin>0.0</iMin>
            <cmdMax>2</cmdMax>
            <cmdMin>-2</cmdMin>
          </joint_control_pid>
          <joint_name>zephyr_delta_wing::propeller_joint</joint_name>
        </channel>
        <channel name='rotor6'>
          <input_index>5</input_index>
          <input_offset>0</input_offset>
          <input_scaling>0.524</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>0</zero_position_armed>
          <joint_control_type>position</joint_control_type>
          <joint_name>zephyr_delta_wing::flap_left_joint</joint_name>
          <joint_control_pid>
            <p>10.0</p>
            <i>0</i>
            <d>0</d>
            <iMax>0</iMax>
            <iMin>0</iMin>
            <cmdMax>20</cmdMax>
            <cmdMin>-20</cmdMin>
          </joint_control_pid>
        </channel>
        <channel name='rotor7'>
          <input_index>6</input_index>
          <input_offset>0</input_offset>
          <input_scaling>0.524</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>0</zero_position_armed>
          <joint_control_type>position</joint_control_type>
          <joint_name>zephyr_delta_wing::flap_right_joint</joint_name>
          <joint_control_pid>
            <p>10.0</p>
            <i>0</i>
            <d>0</d>
            <iMax>0</iMax>
            <iMin>0</iMin>
            <cmdMax>20</cmdMax>
            <cmdMin>-20</cmdMin>
          </joint_control_pid>
        </channel>
        <channel name='rotor8'>
          <input_index>7</input_index>
          <input_offset>0</input_offset>
          <input_scaling>0.524</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>0</zero_position_armed>
          <joint_control_type>position</joint_control_type>
        </channel> 
      </control_channels>
    </plugin>
</robot>

I see a few issues here. Let’s dig in.

I have the simulation models for my custom drone in a ROS pkg (in catkin_ws/src), and although the PX4 Firmware repo exists outside my catkin_ws, I have symbolic links to both Firmware and Tools/sitl_gazebo in the src dir (I understand it’s necessary to have them in src, can anyone tell me why?)

I’m not sure about this. I don’t see why you need that. This all depends on how your environment is sourced. You should just need this (as described in the docs) and ROS will find everything:

source ${PX4_SRC_DIR}/Tools/setup_gazebo.bash ${PX4_SRC_DIR} ${PX4_SRC_DIR}/build/px4_sitl_default
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:${PX4_SRC_DIR}:${PX4_SRC_DIR}/Tools/sitl_gazebo

Where PX4_SRC_DIR is the path to your Firmware repo.

You have vehicle:=june and the following:

<param if="$(arg xacro)" name="robot_description"
      command="$(find xacro)/xacro $(find we_sim_gazebo)/models/$(arg vehicle)/xacro/robot.$(arg format).xacro --check-order" />

The directory tree above does not match this.

In your launch file you have:

<include file="$(find sim_pkg)/launch/posix_sitl.launch">
...
    <arg name="xacro" value="false" />

The value should be $(arg xacro).

Now that we’ve addressed the ROS side (I think)… we need to fix what’s going on with PX4. You’re using this modified version of posix_sitl.launch. The following line is used to setup the startup script (rcS) for PX4 and is the result of your “Error: Unknown model ‘hexa_x’”:

    <env name="PX4_SIM_MODEL" value="hexa_x" />

This error is causing PX4 to exit, which is why mavros can’t talk to anything. rcS scripts currently live in Firmware/ROMFS/px4fmu_common/init.d-posix. This directory doesn’t contain a startup for a vehicle with that name. I don’t know what kind of vehicle june is. Either you need to make a rcS for that vehicle and put it in that folder, or you need to set PX4_SIM_MODEL to match a vehicle that shares the same configuration as your model. This magic happens here if you’re curious: PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/rcS at 2fbb70d9ca94f442de1345221be18ba738cda952 · PX4/PX4-Autopilot · GitHub

I did not look at your xacro, other than to see that you have ports in there for communication. Hope that helps.

Hi,

Thanks for getting back to me, appreciate it.

I’ve fixed everything you mentioned above, and managed to get a copied version of Iris to fly from the same location as my own model.

Next I’ve been trying to alter the Iris model so it’s closer to our own drone (June): the first step being to have 6 rotors instead of 4.

To do this I’ve added the rotors and libgazebo_motor_model.so’s to the sdf, ensuring they are consistent with the Iris’s first 4 for now - as well as the rotor control channels as part of the libgazebo_mavlink_interface.so.

I’ve duplicated the Iris rcS script and replaced the quad_w mixer with the hexa_x. This is the only alteration I’ve made except to ensure that it matches the model name and the prepending number is unique.

I’ve included the full SDF in the comment below because I’m over the character limit again.

I’ve reworked my package and separated the terminal output now for easier reading, and I can now bring the model into Gazebo although it spawns partly underground:

$ roslaunch simulation spawn_model.launch 
... logging to -.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 -/

SUMMARY
========

PARAMETERS
 * /rosdistro: kinetic
 * /rosversion: 1.12.14

NODES
  /
    vehicle_spawn- (gazebo_ros/spawn_model)

ROS_MASTER_URI=http://localhost:11311

process[-]: started with pid [8828]
SpawnModel script started
[INFO] [1564000543.465352, 0.000000]: Loading model XML from file
[INFO] [1564000543.465592, 0.000000]: Waiting for service /gazebo/spawn_sdf_model
[INFO] [1564000543.466422, 0.000000]: Calling service /gazebo/spawn_sdf_model
[INFO] [1564000543.723530, 12.628000]: Spawn status: SpawnModel: Successfully spawned entity
[-] process has finished cleanly
log file: /home/kieran-dwn/.ros/log/93119e08-ae52-11e9-9c19-9cb6d0c132b1/vehicle_spawn*.log
all processes on machine have died, roslaunch will exit
shutting down processing monitor...
... shutting down processing monitor complete
done

This seems odd but when I work with the unmodifed Iris model in the same location it first spawns underground then rights itself when the px4 sitl side is launched. Now, an error is thrown (on the gazebo side) when I start the px4 sitl process. The full output is shown below, although I’ve separated the part describing the error which thrown on the px4 launch:

$  roslaunch simulation gazebo_default.launch 
... logging to -.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 -/

SUMMARY
========

PARAMETERS
 * /rosdistro: kinetic
 * /rosversion: 1.12.14
 * /use_sim_time: True

NODES
  /
    gazebo (gazebo_ros/gzserver)
    gazebo_gui (gazebo_ros/gzclient)

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

setting /run_id to 93119e08-ae52-11e9-9c19-9cb6d0c132b1
process[rosout-1]: started with pid [8364]
started core service [/rosout]
process[gazebo-2]: started with pid [8371]
process[gazebo_gui-3]: started with pid [8388]
[ INFO] [1564000529.776155829]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1564000529.776536470]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1564000529.795712666]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1564000529.796181726]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1564000531.015222245, 0.024000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1564000531.034922467, 0.044000000]: Physics dynamic reconfigure ready.
[ INFO] [1564000531.130010058, 0.136000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1564000531.151399839, 0.156000000]: Physics dynamic reconfigure ready.

~

terminate called after throwing an instance of 'std::out_of_range'
  what():  vector::_M_range_check: __n (which is 0) >= this->size() (which is 0)
Aborted (core dumped)
[gazebo-2] process has died [pid 8371, exit code 134, cmd /opt/ros/kinetic/lib/gazebo_ros/gzserver -e ode /home/kieran-dwn/ws_2/src/simulation/worlds/empty.world __name:=gazebo __log:=/home/kieran-dwn/.ros/log/93119e08-ae52-11e9-9c19-9cb6d0c132b1/gazebo-2.log].
log file: /home/kieran-dwn/.ros/log/93119e08-ae52-11e9-9c19-9cb6d0c132b1/gazebo-2*.log

The px4 sitl window doesn’t seem to indicate any error (to my knowledge):

$  roslaunch simulation px4_sitl.launch 
... logging to -.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://kieran-dwn-xps15-9570:45619/

SUMMARY
========

PARAMETERS
 * /rosdistro: kinetic
 * /rosversion: 1.12.14

NODES
  /
    sitl (px4/px4)

ROS_MASTER_URI=http://localhost:11311

process[sitl-1]: started with pid [8924]
INFO  [px4] Creating symlink -/src/Firmware/ROMFS/px4fmu_common -> /home/kieran-dwn/.ros/etc
0 WARNING: setRealtimeSched failed (not run as root?)

______  __   __    ___ 
| ___ \ \ \ / /   /   |
| |_/ /  \ 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 11798680 bytes
INFO  [simulator] Waiting for simulator to connect on TCP port 4560
INFO  [simulator] Simulator connected on TCP port 4560.
  MAV_TYPE: curr: 2 -> new: 13
INFO  [init] Mixer: etc/mixers/hexa_x.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-07-24/20_35_49.ulg
INFO  [mavlink] MAVLink only on localhost (set param MAV_BROADCAST = 1 to enable network)
INFO  [px4] Startup script returned successfully
pxh> 

Any thoughts?

Let me know if there’s any more information that can help.

Thanks a lot for taking the time :slight_smile:

Kieran

The full sdf:

<sdf version='1.6'>
  <model name='iris_custom'>
    <link name='base_link'>
      <pose frame=''>0 0 0 0 -0 0</pose>
      <inertial>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <mass>1.5</mass>
        <inertia>
          <ixx>0.0347563</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.0458929</iyy>
          <iyz>0</iyz>
          <izz>0.0977</izz>
        </inertia>
      </inertial>
      <collision name='base_link_inertia_collision'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <box>
            <size>0.47 0.47 0.11</size>
          </box>
        </geometry>
        <surface>
          <contact>
            <ode>
              <min_depth>0.001</min_depth>
              <max_vel>0</max_vel>
            </ode>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='base_link_inertia_visual'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://iris_june/meshes/MAYA_MainAssembly_V1.1.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/DarkGrey</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
    </link>
    <link name='/imu_link'>
      <pose frame=''>0 0 0 0 -0 0</pose>
      <inertial>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <mass>0.015</mass>
        <inertia>
          <ixx>1e-05</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>1e-05</iyy>
          <iyz>0</iyz>
          <izz>1e-05</izz>
        </inertia>
      </inertial>
    </link>
    <joint name='/imu_joint' type='revolute'>
      <child>/imu_link</child>
      <parent>base_link</parent>
      <axis>
        <xyz>1 0 0</xyz>
        <limit>
          <lower>0</lower>
          <upper>0</upper>
          <effort>0</effort>
          <velocity>0</velocity>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>
    <!-- Front Right -->
    <link name='rotor_0'>
      <pose frame=''>0.2625 -0.150 0.050 0 -0 0</pose>
      <inertial>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <mass>0.005</mass>
        <inertia>
          <ixx>9.75e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000273104</iyy>
          <iyz>0</iyz>
          <izz>0.000274004</izz>
        </inertia>
      </inertial>
      <collision name='rotor_0_collision'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <cylinder>
            <length>0.005</length>
            <radius>0.128</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='rotor_0_visual'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rotors_description/meshes/iris_prop_ccw.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Blue</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
    </link>
    <joint name='rotor_0_joint' type='revolute'>
      <child>rotor_0</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>
    <!-- Rear Left -->
    <link name='rotor_1'>
      <pose frame=''>-0.2625 0.150 0.050 0 -0 0</pose>
      <inertial>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <mass>0.005</mass>
        <inertia>
          <ixx>9.75e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000273104</iyy>
          <iyz>0</iyz>
          <izz>0.000274004</izz>
        </inertia>
      </inertial>
      <collision name='rotor_1_collision'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <cylinder>
            <length>0.005</length>
            <radius>0.128</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='rotor_1_visual'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rotors_description/meshes/iris_prop_ccw.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/DarkGrey</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
    </link>
    <joint name='rotor_1_joint' type='revolute'>
      <child>rotor_1</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>
    <!-- Front Left -->
    <link name='rotor_2'>
      <pose frame=''>0.2625 0.150 0.050 0 -0 0</pose>
      <inertial>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <mass>0.005</mass>
        <inertia>
          <ixx>9.75e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000273104</iyy>
          <iyz>0</iyz>
          <izz>0.000274004</izz>
        </inertia>
      </inertial>
      <collision name='rotor_2_collision'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <cylinder>
            <length>0.005</length>
            <radius>0.128</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='rotor_2_visual'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rotors_description/meshes/iris_prop_cw.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/Blue</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
    </link>
    <joint name='rotor_2_joint' type='revolute'>
      <child>rotor_2</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>
    <!-- Rear Right -->
    <link name='rotor_3'>
      <pose frame=''>-0.2625 -0.150 0.050 0 -0 0</pose>
      <inertial>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <mass>0.005</mass>
        <inertia>
          <ixx>9.75e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000273104</iyy>
          <iyz>0</iyz>
          <izz>0.000274004</izz>
        </inertia>
      </inertial>
      <collision name='rotor_3_collision'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <cylinder>
            <length>0.005</length>
            <radius>0.128</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='rotor_3_visual'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rotors_description/meshes/iris_prop_cw.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/DarkGrey</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
    </link>
    <joint name='rotor_3_joint' type='revolute'>
      <child>rotor_3</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>
    <!-- Mid Right -->
    <link name='rotor_4'>
      <pose frame=''>0 -0.240 0.050 0 -0 0</pose>
      <inertial>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <mass>0.005</mass>
        <inertia>
          <ixx>9.75e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000273104</iyy>
          <iyz>0</iyz>
          <izz>0.000274004</izz>
        </inertia>
      </inertial>
      <collision name='rotor_4_collision'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <cylinder>
            <length>0.005</length>
            <radius>0.128</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='rotor_4_visual'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rotors_description/meshes/iris_prop_cw.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/DarkGrey</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
    </link>
    <joint name='rotor_4_joint' type='revolute'>
      <child>rotor_4</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>
    <!-- Mid Left -->
    <link name='rotor_5'>
      <pose frame=''>0 0.240 0.050 0 -0 0</pose>
      <inertial>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <mass>0.005</mass>
        <inertia>
          <ixx>9.75e-07</ixx>
          <ixy>0</ixy>
          <ixz>0</ixz>
          <iyy>0.000273104</iyy>
          <iyz>0</iyz>
          <izz>0.000274004</izz>
        </inertia>
      </inertial>
      <collision name='rotor_5_collision'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <cylinder>
            <length>0.005</length>
            <radius>0.128</radius>
          </cylinder>
        </geometry>
        <surface>
          <contact>
            <ode/>
          </contact>
          <friction>
            <ode/>
          </friction>
        </surface>
      </collision>
      <visual name='rotor_5_visual'>
        <pose frame=''>0 0 0 0 -0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://rotors_description/meshes/iris_prop_cw.dae</uri>
          </mesh>
        </geometry>
        <material>
          <script>
            <name>Gazebo/DarkGrey</name>
            <uri>file://media/materials/scripts/gazebo.material</uri>
          </script>
        </material>
      </visual>
      <gravity>1</gravity>
      <velocity_decay/>
    </link>
    <joint name='rotor_5_joint' type='revolute'>
      <child>rotor_3</child>
      <parent>base_link</parent>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-1e+16</lower>
          <upper>1e+16</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
        <use_parent_model_frame>1</use_parent_model_frame>
      </axis>
    </joint>
    <plugin name='rosbag' filename='libgazebo_multirotor_base_plugin.so'>
      <robotNamespace/>
      <linkName>base_link</linkName>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>
    <plugin name='front_right_motor_model' filename='libgazebo_motor_model.so'>
      <robotNamespace/>
      <jointName>rotor_0_joint</jointName>
      <linkName>rotor_0</linkName>
      <turningDirection>ccw</turningDirection>
      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>1100</maxRotVelocity>
      <motorConstant>8.54858e-06</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>0</motorNumber>
      <rotorDragCoefficient>0.000806428</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/0</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>
    <plugin name='back_left_motor_model' filename='libgazebo_motor_model.so'>
      <robotNamespace/>
      <jointName>rotor_1_joint</jointName>
      <linkName>rotor_1</linkName>
      <turningDirection>ccw</turningDirection>
      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>1100</maxRotVelocity>
      <motorConstant>8.54858e-06</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>1</motorNumber>
      <rotorDragCoefficient>0.000806428</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/1</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>
    <plugin name='front_left_motor_model' filename='libgazebo_motor_model.so'>
      <robotNamespace/>
      <jointName>rotor_2_joint</jointName>
      <linkName>rotor_2</linkName>
      <turningDirection>cw</turningDirection>
      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>1100</maxRotVelocity>
      <motorConstant>8.54858e-06</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>2</motorNumber>
      <rotorDragCoefficient>0.000806428</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/2</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>
    <plugin name='back_right_motor_model' filename='libgazebo_motor_model.so'>
      <robotNamespace/>
      <jointName>rotor_3_joint</jointName>
      <linkName>rotor_3</linkName>
      <turningDirection>cw</turningDirection>
      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>1100</maxRotVelocity>
      <motorConstant>8.54858e-06</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>3</motorNumber>
      <rotorDragCoefficient>0.000806428</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/3</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>
    <plugin name='right_motor_model' filename='libgazebo_motor_model.so'>
      <robotNamespace/>
      <jointName>rotor_4_joint</jointName>
      <linkName>rotor_4</linkName>
      <turningDirection>cw</turningDirection>
      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>1100</maxRotVelocity>
      <motorConstant>8.54858e-06</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>4</motorNumber>
      <rotorDragCoefficient>0.000806428</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/4</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>
    <plugin name='left_motor_model' filename='libgazebo_motor_model.so'>
      <robotNamespace/>
      <jointName>rotor_5_joint</jointName>
      <linkName>rotor_5</linkName>
      <turningDirection>cw</turningDirection>
      <timeConstantUp>0.0125</timeConstantUp>
      <timeConstantDown>0.025</timeConstantDown>
      <maxRotVelocity>1100</maxRotVelocity>
      <motorConstant>8.54858e-06</motorConstant>
      <momentConstant>0.06</momentConstant>
      <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
      <motorNumber>5</motorNumber>
      <rotorDragCoefficient>0.000806428</rotorDragCoefficient>
      <rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
      <motorSpeedPubTopic>/motor_speed/5</motorSpeedPubTopic>
      <rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
    </plugin>
    <plugin name='gps_plugin' filename='libgazebo_gps_plugin.so'>
      <robotNamespace/>
      <gpsNoise>true</gpsNoise>
    </plugin>
    <plugin name='magnetometer_plugin' filename='libgazebo_magnetometer_plugin.so'>
      <robotNamespace/>
      <pubRate>20</pubRate>
      <noiseDensity>0.0004</noiseDensity>
      <randomWalk>6.4e-06</randomWalk>
      <biasCorrelationTime>600</biasCorrelationTime>
      <magTopic>/mag</magTopic>
    </plugin>
    <plugin name='barometer_plugin' filename='libgazebo_barometer_plugin.so'>
      <robotNamespace/>
      <pubRate>10</pubRate>
      <baroTopic>/baro</baroTopic>
    </plugin>
    <plugin name='mavlink_interface' filename='libgazebo_mavlink_interface.so'>
      <robotNamespace/>
      <imuSubTopic>/imu</imuSubTopic>
      <gpsSubTopic>/gps</gpsSubTopic>
      <magSubTopic>/mag</magSubTopic>
      <baroSubTopic>/baro</baroSubTopic>
      <mavlink_addr>INADDR_ANY</mavlink_addr>
      <mavlink_udp_port>14560</mavlink_udp_port>
      <mavlink_tcp_port>4560</mavlink_tcp_port>
      <serialEnabled>false</serialEnabled>
      <serialDevice>/dev/ttyACM0</serialDevice>
      <baudRate>921600</baudRate>
      <qgc_addr>INADDR_ANY</qgc_addr>
      <qgc_udp_port>14550</qgc_udp_port>
      <sdk_addr>INADDR_ANY</sdk_addr>
      <sdk_udp_port>14540</sdk_udp_port>
      <hil_mode>false</hil_mode>
      <hil_state_level>false</hil_state_level>
      <vehicle_is_tailsitter>false</vehicle_is_tailsitter>
      <send_vision_estimation>true</send_vision_estimation>
      <send_odometry>false</send_odometry>
      <enable_lockstep>true</enable_lockstep>
      <use_tcp>true</use_tcp>
      <motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic>
      <control_channels>
        <channel name='rotor1'>
          <input_index>0</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1000</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>100</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
        </channel>
        <channel name='rotor2'>
          <input_index>1</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1000</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>100</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
        </channel>
        <channel name='rotor3'>
          <input_index>2</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1000</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>100</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
        </channel>
        <channel name='rotor4'>
          <input_index>3</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1000</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>100</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
        </channel>
        <channel name='rotor5'>
          <input_index>4</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1000</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>100</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
          <!-- <joint_control_pid>
            <p>0.1</p>
            <i>0</i>
            <d>0</d>
            <iMax>0.0</iMax>
            <iMin>0.0</iMin>
            <cmdMax>2</cmdMax>
            <cmdMin>-2</cmdMin>
          </joint_control_pid> -->
          <!-- <joint_name>zephyr_delta_wing::propeller_joint</joint_name> -->
        </channel>
        <channel name='rotor6'>
          <input_index>5</input_index>
          <input_offset>0</input_offset>
          <input_scaling>1000</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>100</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
          <!-- <joint_name>zephyr_delta_wing::flap_left_joint</joint_name>
          <joint_control_pid>
            <p>10.0</p>
            <i>0</i>
            <d>0</d>
            <iMax>0</iMax>
            <iMin>0</iMin>
            <cmdMax>20</cmdMax>
            <cmdMin>-20</cmdMin>
          </joint_control_pid> -->
        </channel>
        <channel name='rotor7'>
          <input_index>6</input_index>
          <input_offset>0</input_offset>
          <input_scaling>0.524</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>0</zero_position_armed>
          <joint_control_type>position</joint_control_type>
          <joint_name>zephyr_delta_wing::flap_right_joint</joint_name>
          <joint_control_pid>
            <p>10.0</p>
            <i>0</i>
            <d>0</d>
            <iMax>0</iMax>
            <iMin>0</iMin>
            <cmdMax>20</cmdMax>
            <cmdMin>-20</cmdMin>
          </joint_control_pid>
        </channel>
        <channel name='rotor8'>
          <input_index>7</input_index>
          <input_offset>0</input_offset>
          <input_scaling>0.524</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>0</zero_position_armed>
          <joint_control_type>position</joint_control_type>
        </channel>
      </control_channels>
    </plugin>
    <static>0</static>
    <plugin name='rotors_gazebo_imu_plugin' filename='libgazebo_imu_plugin.so'>
      <robotNamespace/>
      <linkName>/imu_link</linkName>
      <imuTopic>/imu</imuTopic>
      <gyroscopeNoiseDensity>0.0003394</gyroscopeNoiseDensity>
      <gyroscopeRandomWalk>3.8785e-05</gyroscopeRandomWalk>
      <gyroscopeBiasCorrelationTime>1000.0</gyroscopeBiasCorrelationTime>
      <gyroscopeTurnOnBiasSigma>0.0087</gyroscopeTurnOnBiasSigma>
      <accelerometerNoiseDensity>0.004</accelerometerNoiseDensity>
      <accelerometerRandomWalk>0.006</accelerometerRandomWalk>
      <accelerometerBiasCorrelationTime>300.0</accelerometerBiasCorrelationTime>
      <accelerometerTurnOnBiasSigma>0.196</accelerometerTurnOnBiasSigma>
    </plugin>
  </model>
</sdf>

UPDATE: FIXED

Tracked the issue to out-of-range index error in the mavlink_interface plugin. This was caused by an invalid parent reference in one of my joints defined in the SDF. Corrected this and all works now as it should.

Thanks for your help @lamping.ap

1 Like

Hi, I have same concerns. I have SDF file of my drone. First if I have added the launch file with my own sdf and the mavros node. It says cannot find my robot.

Ok I try to fix this by going to airframes folder and add the file with similar content as multicopter, add my robot to Cmakelists, but nothing has changed

How to remove compilation issue?