Firmware Structure (Adding VTOL support) - Clarifications
-
Dear all,
I am trying to enable VTOL frame in HITL simulation. I have been looking through PX4 documentation and the custom px4 fork modalai is using. So far my understanding is that I should turn on missing modules in the
boards/modalai/voxl2/default.px4board
file. I have successfully rebuild px4 firmware using these instructions. However, I am still not seeing necessary parameters appearing in QCG. This makes me wondering about dependencies between different parts of the code. If you could provide clarifications on the following I would highly appreciate it:- Here is the SDK and PX4 versions I am running:
-------------------------------------------------------------------------------- system-image: 1.8.02-M0054-14.1a-perf kernel: #1 SMP PREEMPT Mon Nov 11 22:47:44 UTC 2024 4.19.125 -------------------------------------------------------------------------------- hw platform: M0054 mach.var: 1.0.1 -------------------------------------------------------------------------------- voxl-suite: 1.4.1 -------------------------------------------------------------------------------- current IP: wlan0: <IP HERE> --------------------------------------------------------------------------------
voxl2:/$ px4-versions modalai-slpi/unknown,now 1.1.19 arm64 [installed,automatic] px4-support/now 1.0-6 arm64 [installed,local] voxl-fpv-px4/unknown 1.14.0-8.93.1 arm64 voxl-px4/unknown,now 1.14.0-2.0.94 arm64 [installed,automatic] voxl-px4-imu-server/unknown,now 0.1.2 arm64 [installed,automatic] voxl-px4-params/unknown,now 0.6.3 arm64 [installed,automatic] libfc-sensor/unknown,now 1.0.7 arm64 [installed] 1.8.02-M0054-14.1a-perf
voxl2:/$ px4-ver all HW arch: MODALAI_VOXL2 PX4 git-hash: 5e6a8c257371b6c45e55662daac5fe9fbd08040b PX4 version: 1.14.0 0 (17694720) Vendor version: 2.0.94 0 (33578496) OS: Linux OS version: Release 4.19.125 (68386303) Build datetime: Jul 1 2025 17:48:13 Build uri: localhost Build variant: default Toolchain: GNU GCC, 7.5.0 PX4GUID: 100a41444f4d5649414c324c584f30303030 UNKNOWN MCU
-
there seem to be two ways to deploy the code. I wonder what the difference is. Can I just always rely on the
boards/modalai/voxl2/scripts/install-voxl.sh
script or should I do .deb package instead? what is the general rule of thumb for using one vs the other? -
Is enabling modules in
default.px4board
file enough to enable functionality I am looking for? What exactly is this file accomplishing? My understanding from px4 documentation is that modules are running the whole show. However, I wonder if modules need extra setup to communicate with uORB or any custom modalai parts of the code ? -
I have been looking at the voxl-px4, voxl-px4-hitl, voxl-px4--start and voxl-px4-hitl-start scripts and noticed there is a bunch of modules being initialized that are not in the
default.px4board
file. For example, in voxl-px4-hitl-start
# Start all of the processing modules on DSP qshell sensors start -h qshell ekf2 start qshell mc_pos_control start qshell mc_att_control start qshell mc_rate_control start qshell mc_hover_thrust_estimator start qshell mc_autotune_attitude_control start qshell land_detector start multicopter qshell manual_control start qshell control_allocator start qshell rc_update start qshell commander start -h qshell commander mode posctl qshell load_mon start
Does that mean I can enable modules manually without rebuilding the firmware ? Can i just enable VTOL by adding modules required to the
voxl-px4-hitl-start
file?- what is editable in qgc vs what needs to be done in code? Can I enable the functionality I need through just QGC?
Thank you in advance for your response
-
This post is deleted! -
@garret quick update from me. i was able to get "vtol_att_control" module to start along with all the fw_* and mc_* controllers. i now seem to have access to the necessary vtol parameters through QGC. However, the connecting to QGC is super slow now and also I am getting
mag0: Timeout
andbaro0: Timeout
errors after runningvoxl-px4-hitl
.here is the full boot up log just in case:
voxl2:/$ voxl-px4-hitl Found DSP signature file INFO [px4] mlockall() enabled. PX4's virtual address space is locked into RAM. INFO [px4] assuming working directory is rootfs, no symlinks needed. INFO [muorb] Got muorb init command Sending initialization request Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete Got topic data before configuration complete INFO [muorb] SLPI: muorb aggregator thread running INFO [muorb] muorb protobuf initalize method succeeded INFO [muorb] succesfully did ADVERTISE_TEST_TYPE INFO [muorb] SLPI: Creating pthread test_MUORB INFO [muorb] SLPI: Successfully created px4 task PX4_test_MUORB with tid 2097656 INFO [muorb] succesfully did SUBSCRIBE_TEST_TYPE INFO [muorb] SLPI: Creating pthread test_MUORB INFO [muorb] SLPI: Successfully created px4 task PX4_test_MUORB with tid 2097655 INFO [muorb] succesfully did TOPIC_TEST_TYPE INFO [muorb] SLPI: Creating pthread test_MUORB INFO [muorb] SLPI: Successfully created px4 task PX4_test_MUORB with tid 2097654 INFO [muorb] succesfully did UNSUBSCRIBE_TEST_TYPE INFO [muorb] SLPI: Creating pthread test_MUORB INFO [muorb] SLPI: Successfully created px4 task PX4_test_MUORB with tid 2097653 INFO [muorb] muorb test passed ______ __ __ ___ | ___ \ \ \ / / / | | |_/ / \ V / / /| | | __/ / \ / /_| | | | / /^\ \ \___ | \_| \/ \/ |_/ px4 starting. INFO [parameters] Starting param sync THREAD INFO [muorb] SLPI: Advertising remote topic log_message INFO [px4] startup script: /bin/sh /usr/bin/voxl-px4-hitl-start 0 INFO [muorb] SLPI: Starting param sync THREAD Running on M0054 INFO [muorb] SLPI: before starting the qshell_entry task INFO [muorb] SLPI: Creating pthread qshell INFO [muorb] SLPI: qshell entry..... INFO [muorb] SLPI: Successfully created px4 task PX4_qshell with tid 2097652 INFO [muorb] SLPI: Init app map initialized INFO [muorb] SLPI: after starting the qshell_entry task INFO [param] selected parameter default file /data/px4/param/hitl_parameters INFO [muorb] SLPI: Marking DeviceNode(parameter_client_reset_request) as advertised in process_remote_topic INFO [uORB] Marking DeviceNode(parameter_client_reset_response) as advertised in process_remote_topic INFO [muorb] SLPI: Advertising remote topic parameter_update INFO [muorb] SLPI: Marking DeviceNode(parameter_client_set_value_request) as advertised in process_remote_to INFO [uORB] Marking DeviceNode(parameter_server_set_used_request) as advertised in process_remote_topic INFO [muorb] SLPI: Marking DeviceNode(parameter_server_set_used_response) as advertised in process_remote_to INFO [uORB] Marking DeviceNode(parameter_client_set_value_response) as advertised in process_remote_topic INFO [parameters] BSON document size 2018 bytes, decoded 2018 bytes (INT32:53, FLOAT:43) INFO [logger] logger started (mode=all) INFO [logger] Start file log (type: full) INFO [logger] [logger] /data/px4/log/2025-07-02/19_36_21.ulg INFO [muorb] SLPI: Advertising remote topic mavlink_log INFO [muorb] SLPI: Advertising remote topic event INFO [logger] Opened full log file: /data/px4/log/2025-07-02/19_36_21.ulg INFO [muorb] SLPI: Advertising remote topic logger_status INFO [qshell] Send cmd: 'sensors start -h' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: sensors start -h INFO [muorb] SLPI: arg0 = 'sensors' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = '-h' INFO [uORB] Advertising remote topic sensor_selection INFO [uORB] Advertising remote topic sensors_status_imu INFO [uORB] Advertising remote topic vehicle_acceleration INFO [uORB] Advertising remote topic vehicle_angular_velocity INFO [uORB] Advertising remote topic sensor_combined INFO [uORB] Advertising remote topic vehicle_air_data INFO [uORB] Advertising remote topic vehicle_gps_position INFO [uORB] Advertising remote topic vehicle_magnetometer INFO [uORB] Advertising remote topic sensor_preflight_mag INFO [muorb] SLPI: Ok executing command: sensors start -h INFO [uORB] Advertising remote topic qshell_retval INFO [qshell] qshell return value timestamp: 70283703, local time: 70289506 INFO [qshell] Send cmd: 'ekf2 start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: ekf2 start INFO [muorb] SLPI: arg0 = 'ekf2' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Advertising remote topic vehicle_attitude INFO [uORB] Advertising remote topic vehicle_local_position INFO [uORB] Advertising remote topic estimator_event_flags INFO [uORB] Advertising remote topic estimator_innovation_test_ratios INFO [uORB] Advertising remote topic estimator_innovation_variances INFO [uORB] Advertising remote topic estimator_innovations INFO [uORB] Advertising remote topic estimator_sensor_bias INFO [uORB] Advertising remote topic estimator_states INFO [uORB] Advertising remote topic estimator_status_flags INFO [uORB] Advertising remote topic estimator_status INFO [muorb] SLPI: Ok executing command: ekf2 start INFO [qshell] qshell return value timestamp: 70697060, local time: 70701423 INFO [qshell] Send cmd: 'mc_pos_control start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: mc_pos_control start INFO [muorb] SLPI: arg0 = 'mc_pos_control' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Advertising remote topic takeoff_status INFO [muorb] SLPI: Ok executing command: mc_pos_control start INFO [qshell] qshell return value timestamp: 70881803, local time: 70884861 INFO [qshell] Send cmd: 'fw_pos_control start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: fw_pos_control start INFO [muorb] SLPI: arg0 = 'fw_pos_control' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Advertising remote topic position_controller_status INFO [uORB] Advertising remote topic position_controller_landing_status INFO [uORB] Advertising remote topic tecs_status INFO [uORB] Advertising remote topic launch_detection_status INFO [uORB] Advertising remote topic landing_gear INFO [uORB] Advertising remote topic flaps_setpoint INFO [uORB] Advertising remote topic spoilers_setpoint INFO [muorb] SLPI: Ok executing command: fw_pos_control start INFO [qshell] qshell return value timestamp: 71194603, local time: 71197800 INFO [qshell] Send cmd: 'mc_att_control start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: mc_att_control start INFO [muorb] SLPI: arg0 = 'mc_att_control' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: Ok executing command: mc_att_control start INFO [qshell] qshell return value timestamp: 71291921, local time: 71293922 INFO [qshell] Send cmd: 'fw_att_control start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: fw_att_control start INFO [muorb] SLPI: arg0 = 'fw_att_control' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: Ok executing command: fw_att_control start INFO [qshell] qshell return value timestamp: 71376777, local time: 71378810 INFO [qshell] Send cmd: 'mc_rate_control start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: mc_rate_control start INFO [muorb] SLPI: arg0 = 'mc_rate_control' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Advertising remote topic rate_ctrl_status INFO [muorb] SLPI: Ok executing command: mc_rate_control start INFO [qshell] qshell return value timestamp: 71542510, local time: 71544910 INFO [qshell] Send cmd: 'fw_rate_control start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: fw_rate_control start INFO [muorb] SLPI: arg0 = 'fw_rate_control' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Marking DeviceNode(rate_ctrl_status) as advertised in process_remote_topic INFO [muorb] SLPI: Ok executing command: fw_rate_control start INFO [qshell] qshell return value timestamp: 71685112, local time: 71688487 INFO [qshell] Send cmd: 'vtol_att_control start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: vtol_att_control start INFO [muorb] SLPI: arg0 = 'vtol_att_control' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Marking DeviceNode(flaps_setpoint) as advertised in process_remote_topic INFO [uORB] Marking DeviceNode(spoilers_setpoint) as advertised in process_remote_topic INFO [uORB] Advertising remote topic vtol_vehicle_status INFO [uORB] Advertising remote topic vehicle_thrust_setpoint INFO [uORB] Advertising remote topic vehicle_torque_setpoint INFO [uORB] Marking DeviceNode(vehicle_thrust_setpoint) as advertised in process_remote_topic INFO [uORB] Marking DeviceNode(vehicle_torque_setpoint) as advertised in process_remote_topic INFO [muorb] SLPI: Ok executing command: vtol_att_control start INFO [qshell] qshell return value timestamp: 71820328, local time: 71823028 INFO [qshell] Send cmd: 'mc_hover_thrust_estimator start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: mc_hover_thrust_estimator start INFO [muorb] SLPI: arg0 = 'mc_hover_thrust_estimator' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: Ok executing command: mc_hover_thrust_estimator start INFO [qshell] qshell return value timestamp: 71866787, local time: 71869655 INFO [qshell] Send cmd: 'mc_autotune_attitude_control start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: mc_autotune_attitude_control start INFO [muorb] SLPI: arg0 = 'mc_autotune_attitude_control' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Advertising remote topic autotune_attitude_control_status INFO [muorb] SLPI: Ok executing command: mc_autotune_attitude_control start INFO [qshell] qshell return value timestamp: 71922119, local time: 71924972 INFO [qshell] Send cmd: 'land_detector start multicopter' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: land_detector start multicopter INFO [muorb] SLPI: arg0 = 'land_detector' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = 'multicopter' INFO [muorb] SLPI: Ok executing command: land_detector start multicopter INFO [qshell] qshell return value timestamp: 71981835, local time: 71985165 INFO [qshell] Send cmd: 'manual_control start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: manual_control start INFO [muorb] SLPI: arg0 = 'manual_control' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Advertising remote topic vehicle_land_detected INFO [muorb] SLPI: Ok executing command: manual_control start INFO [qshell] qshell return value timestamp: 72060721, local time: 72063250 INFO [uORB] Advertising remote topic manual_control_setpoint INFO [qshell] Send cmd: 'control_allocator start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: control_allocator start INFO [muorb] SLPI: arg0 = 'control_allocator' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Advertising remote topic control_allocator_status INFO [uORB] Marking DeviceNode(control_allocator_status) as advertised in process_remote_topic INFO [uORB] Advertising remote topic actuator_motors INFO [uORB] Advertising remote topic actuator_servos INFO [uORB] Advertising remote topic actuator_servos_trim INFO [muorb] SLPI: Ok executing command: control_allocator start INFO [qshell] qshell return value timestamp: 72577791, local time: 72580927 INFO [qshell] Send cmd: 'rc_update start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: rc_update start INFO [muorb] SLPI: arg0 = 'rc_update' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: Ok executing command: rc_update start INFO [qshell] qshell return value timestamp: 73009950, local time: 73012100 INFO [qshell] Send cmd: 'commander start -h' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: commander start -h INFO [muorb] SLPI: arg0 = 'commander' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = '-h' INFO [muorb] SLPI: Creating pthread commander INFO [muorb] SLPI: Successfully created px4 task PX4_commander with tid 2097647 INFO [uORB] Advertising remote topic led_control INFO [muorb] SLPI: LED: open /dev/led0 failed (22) INFO [uORB] Advertising remote topic tune_control INFO [muorb] SLPI: Ok executing command: commander start -h INFO [qshell] qshell return value timestamp: 73282818, local time: 73285620 INFO [muorb] SLPI: Preflight Fail: Accel Sensor 0 missing INFO [muorb] SLPI: Preflight Fail: barometer 0 missing INFO [muorb] SLPI: Preflight Fail: ekf2 missing data INFO [muorb] SLPI: Preflight Fail: Gyro Sensor 0 missing INFO [muorb] SLPI: Preflight Fail: Compass Sensor 0 missing INFO [uORB] Advertising remote topic health_report INFO [uORB] Advertising remote topic failsafe_flags INFO [uORB] Advertising remote topic actuator_armed INFO [uORB] Advertising remote topic vehicle_control_mode INFO [uORB] Advertising remote topic vehicle_status INFO [uORB] Advertising remote topic failure_detector_status INFO [qshell] Send cmd: 'commander mode posctl' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: commander mode posctl INFO [muorb] SLPI: arg0 = 'commander' INFO [muorb] SLPI: arg1 = 'mode' INFO [muorb] SLPI: arg2 = 'posctl' INFO [uORB] Advertising remote topic vehicle_command INFO [muorb] SLPI: Ok executing command: commander mode posctl INFO [uORB] Advertising remote topic vehicle_command_ack INFO [qshell] qshell return value timestamp: 73321888, local time: 73324809 INFO [qshell] Send cmd: 'load_mon start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: load_mon start INFO [muorb] SLPI: arg0 = 'load_mon' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: Ok executing command: load_mon start INFO [uORB] Advertising remote topic cpuload INFO [qshell] qshell return value timestamp: 73355849, local time: 73358005 INFO [qshell] Send cmd: 'flight_mode_manager start' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: flight_mode_manager start INFO [muorb] SLPI: arg0 = 'flight_mode_manager' INFO [muorb] SLPI: arg1 = 'start' INFO [uORB] Marking DeviceNode(vehicle_command) as advertised in process_remote_topic INFO [muorb] SLPI: Ok executing command: flight_mode_manager start INFO [qshell] qshell return value timestamp: 73487516, local time: 73488991 INFO [dataman] data manager file '/data/px4/dataman' size is 7866640 bytes INFO [muorb] SLPI: Advertising remote topic transponder_report INFO [muorb] SLPI: Advertising remote topic rtl_time_estimate INFO [muorb] SLPI: Advertising remote topic position_setpoint_triplet INFO [qshell] Send cmd: 'pwm_out_sim start -m hil' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: pwm_out_sim start -m hil INFO [muorb] SLPI: arg0 = 'pwm_out_sim' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = '-m' INFO [muorb] SLPI: arg3 = 'hil' INFO [uORB] Advertising remote topic actuator_outputs INFO [muorb] SLPI: Ok executing command: pwm_out_sim start -m hil INFO [qshell] qshell return value timestamp: 74688971, local time: 74692095 INFO [uORB] Advertising remote topic actuator_outputs_sim INFO [qshell] Send cmd: 'dsp_hitl start -g -m -o' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: dsp_hitl start -g -m -o INFO [muorb] SLPI: arg0 = 'dsp_hitl' INFO [muorb] SLPI: arg1 = 'start' INFO [muorb] SLPI: arg2 = '-g' INFO [muorb] SLPI: arg3 = '-m' INFO [muorb] SLPI: arg4 = '-o' INFO [muorb] SLPI: Creating pthread dsp_hitl__main INFO [muorb] SLPI: Successfully created px4 task PX4_dsp_hitl__main with tid 2097645 INFO [muorb] SLPI: Ok executing command: dsp_hitl start -g -m -o INFO [muorb] SLPI: DSP HITL Serial Port is open: 0 INFO [uORB] Advertising remote topic sensor_accel INFO [uORB] Advertising remote topic sensor_gyro INFO [muorb] SLPI: Got 5 from orb_subscribe INFO [qshell] qshell return value timestamp: 74734798, local time: 74736644 INFO [uORB] Advertising remote topic esc_status INFO [mavlink] mode: Onboard, data rate: 100000 B/s on udp port 14556 remote port 14557 INFO [muorb] SLPI: Advertising remote topic telemetry_status INFO [uORB] Advertising remote topic sensor_mag INFO [uORB] Advertising remote topic battery_status ERROR [muorb] SLPI: Sending updates at 74781185, delta 45889 INFO [uORB] Advertising remote topic sensor_baro INFO [uORB] Advertising remote topic sensor_gps INFO [uORB] Advertising remote topic vehicle_imu INFO [uORB] Advertising remote topic vehicle_imu_status INFO [uORB] Advertising remote topic home_position INFO [mavlink] partner IP: 127.0.0.1 INFO [muorb] SLPI: Advertising remote topic obstacle_distance INFO [uORB] Advertising remote topic vehicle_odometry INFO [uORB] Advertising remote topic estimator_aid_src_fake_pos INFO [uORB] Advertising remote topic estimator_aid_src_fake_hgt INFO [uORB] Advertising remote topic estimator_aid_src_gravity INFO [uORB] Advertising remote topic ekf2_timestamps INFO [uORB] Marking DeviceNode(vehicle_thrust_setpoint) as advertised in process_remote_topic INFO [uORB] Marking DeviceNode(vehicle_thrust_setpoint) as advertised in process_remote_topic INFO [uORB] Marking DeviceNode(vehicle_torque_setpoint) as advertised in process_remote_topic INFO [uORB] Marking DeviceNode(vehicle_torque_setpoint) as advertised in process_remote_topic INFO [uORB] Marking DeviceNode(flaps_setpoint) as advertised in process_remote_topic INFO [uORB] Marking DeviceNode(spoilers_setpoint) as advertised in process_remote_topic INFO [uORB] Advertising remote topic vehicle_local_position_setpoint INFO [uORB] Advertising remote topic vehicle_attitude_setpoint INFO [uORB] Advertising remote topic trajectory_setpoint INFO [uORB] Advertising remote topic vehicle_constraints INFO [uORB] Marking DeviceNode(landing_gear) as advertised in process_remote_topic INFO [muorb] SLPI: Advertising remote topic offboard_control_mode INFO [muorb] SLPI: Advertising remote topic mission_result INFO [muorb] SLPI: Advertising remote topic timesync_status INFO [mavlink] mode: Normal, data rate: 100000 B/s on udp port 14558 remote port 14559 INFO [muorb] SLPI: Marking DeviceNode(telemetry_status) as advertised in process_remote_topic INFO [uORB] Advertising remote topic vehicle_rates_setpoint INFO [uORB] Advertising remote topic landing_gear_wheel INFO [uORB] Advertising remote topic actuator_controls_status_0 INFO [uORB] Marking DeviceNode(actuator_controls_status_0) as advertised in process_remote_topic INFO [uORB] Advertising remote topic sensors_status_mag INFO [uORB] Advertising remote topic sensors_status_baro INFO [uORB] Advertising remote topic estimator_aid_src_mag_heading INFO [uORB] Advertising remote topic estimator_aid_src_mag INFO [uORB] Advertising remote topic estimator_aid_src_baro_hgt INFO [uORB] Advertising remote topic estimator_gps_status INFO [uORB] Advertising remote topic estimator_aid_src_gnss_hgt INFO [uORB] Advertising remote topic estimator_aid_src_gnss_pos INFO [uORB] Advertising remote topic estimator_aid_src_gnss_vel INFO [mavlink] MAVLink only on localhost (set param MAV_{i}_BROADCAST = 1 to enable network) INFO [px4] Startup script returned successfully pxh> ERROR [muorb] SLPI: MAG #0 failed: TIMEOUT! ERROR [muorb] SLPI: BARO #0 failed: TIMEOUT! pxh> qsheERROR [muorb] SLPI: BARO #0 failed: TIMEOUT! pxh> qshell dsp_hitl statERROR [muorb] SLPI: MAG #0 failed: TIMEOUT! ERROR [muorb] SLPI: BARO #0 failed: TIMEOUT! pxh> qshell dsp_hitl statusINFO [uORB] Advertising remote topic vehicle_global_position INFO [uORB] Advertising remote topic estimator_baro_bias INFO [muorb] SLPI: Advertising remote topic geofence_result INFO [qshell] Send cmd: 'dsp_hitl status' INFO [muorb] SLPI: Marking DeviceNode(qshell_req) as advertised in process_remote_topic INFO [muorb] SLPI: qshell gotten: dsp_hitl status INFO [muorb] SLPI: arg0 = 'dsp_hitl' INFO [muorb] SLPI: arg1 = 'status' INFO [muorb] SLPI: Running: yes INFO [muorb] SLPI: Messages received from simulator: INFO [muorb] SLPI: Heartbeat received: 150 INFO [muorb] SLPI: HIL Sensor received: 1003 INFO [muorb] SLPI: Odometry received: 0 INFO [muorb] SLPI: GPS received: 12 INFO [muorb] SLPI: Outputs to PX4: INFO [muorb] SLPI: IMU updates: 2412 INFO [muorb] SLPI: Current accel x, y, z: -0.135196, 0.199197, -9.980605 INFO [muorb] SLPI: Current gyro x, y, z: 0.002064, 0.002343, -0.004121 INFO [muorb] SLPI: Magnetometer sent: 850 INFO [muorb] SLPI: Barometer sent: 500 INFO [muorb] SLPI: GPS sent: 12 INFO [muorb] SLPI: Odometry sent: 0 INFO [muorb] SLPI: Outputs to simulator: INFO [muorb] SLPI: Heartbeats sent: 12 INFO [muorb] SLPI: Actuator updates sent: 4828 INFO [muorb] SLPI: Unknown messages received: 0 INFO [muorb] SLPI: Ok executing command: dsp_hitl status INFO [qshell] qshell return value timestamp: 86887060, local time: 86898155 pxh> ERROR [muorb] SLPI: BARO #0 failed: TIMEOUT! ERROR [muorb] SLPI: MAG #0 failed: TIMEOUT! ERROR [muorb] SLPI: BARO #0 failed: TIMEOUT! ERROR [muorb] SLPI: MAG #0 failed: TIMEOUT! ERROR [muorb] SLPI: MAG #0 failed: TIMEOUT! ERROR [muorb] SLPI: BARO #0 failed: TIMEOUT! ERROR [muorb] SLPI: MAG #0 failed: TIMEOUT! ERROR [muorb] SLPI: BARO #0 failed: TIMEOUT! ERROR [muorb] SLPI: MAG #0 failed: TIMEOUT! ERROR [muorb] SLPI: BARO #0 failed: TIMEOUT! ERROR [muorb] SLPI: MAG #0 failed: TIMEOUT! ERROR [muorb] SLPI: BARO #0 failed: TIMEOUT! ERROR [muorb] SLPI: BARO #0 failed: TIMEOUT! ERROR [muorb] SLPI: MAG #0 failed: TIMEOUT! ERROR [muorb] SLPI: MAG #0 failed: TIMEOUT! ERROR [muorb] SLPI: BARO #0 failed: TIMEOUT! ERROR [muorb] SLPI: MAG #0 failed: TIMEOUT!
I am wondering if slow connection to QGC and sensor timeouts are because of chocking communication channel with all the extra data. Do you think voxl2 can handle increasing mavlink stream of data? If so, where can I take a look to increase it?
-
@garret The
install-voxl.sh
and related scripts are only there for developer use. They can help speed things up when making and testing many changes. Normally the package should be built and deployed. The default.px4board file controls what gets built. So, if you have new modules you first have to make sure they are built by adding them into that file. There is one for the Linux side (akavoxl2
) and one for the DSP side (akavoxl2-slpi
). High level stuff like Mavlink and logging go on the Linux side, all real time flight control functionality goes on the DSP side. Once it has been built it needs to be started. That is done by adding the start command into the startup fileboards/modalai/voxl2/target/voxl-px4-start
. If the driver / module is on the DSP side it has to be started with theqshell
command. -
@Eric-Katzfey Those timeouts indicate that the processor is overloaded. Perhaps try enabling the new modules one by one to see if you can figure out which one is taking up too much time.
-
@Eric-Katzfey surprisingly after leaving voxl2 overnight the QGC connection stopped being an issue. However, baro/mag timeout still occurs.
However, I wonder how I can check if this is indeed processor overload. When I am running voxl-px4-hitl + connect voxl2 to QGC the total CPU usage is only slightly over 70%:
Similarly, when I looked at mavlink messages, nothing really stood out as too heavy:
-
onboard services:
-
from gcs:
Some of the things I tried:
- adjusting -r parameter in
voxl-px4-hitl-start
script. I went as high as 500000. That affected neither the cpu use nor the frequency of timeout error for baro/mag. Specifically, this is line I changed
# start the onboard fast link to connect to voxl-mavlink-server mavlink start -x -u 14556 -o 14557 -r 100000 -n lo -m onboard
- I also tried adjusting upd_mtu in
/etc/modalai/voxl-mavlink-server.conf
. I went as high as 300, but it had no effect either. - adjusted dsp_hitl baudrate to 2000000 in
voxl-px4-hitl-start
. Also with little to no effect
qshell dsp_hitl start -g -m -o -b 2000000
Correct me if I am wrong, but as far as I understand the issue must be DSP communicating with Linux side. Where could I look to try and speed it up if possible?
i also may be able to get ARK V6 Flight Controller to run with voxl2 - would that be able to solve my issue?
Thank you in advance for your response
-
-
@garret also of note, the timeout happens only when I launch the instance of gazebo to display vtol. When I launch the default reccomended gazebo for iris, even with all the additional modules, timeout errors do not occur.
I am using this command:
docker run --rm -it --net=host --privileged -e DISPLAY=$DISPLAY -v /dev/input:/dev/input:rw -v /tmp/.X11-unix:/tmp/.X11-unix:ro --device=/dev/ttyUSB0:/dev/ttyUSB0 -v $(pwd)/run_gazebo_local_copy.bash:/usr/workspace/voxl2_hitl_gazebo/run_gazebo.bash -v $(pwd)/standard_vtol_hitl_local_copy.sdf:/usr/workspace/voxl2_hitl_gazebo/models/standard_vtol_hitl/standard_vtol_hitl.sdf voxl-gazebo-docker ./run_gazebo.bash
My custom files are:
- "run_gazebo_local_copy.bash":
#!/bin/bash # # Run gazebo in support of voxl2 hitl # # setup Gazebo env and update package path export GAZEBO_PLUGIN_PATH=$GAZEBO_PLUGIN_PATH:$(pwd) export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:$(pwd)/models export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:$(pwd)/build echo -e "GAZEBO_PLUGIN_PATH $GAZEBO_PLUGIN_PATH" echo -e "GAZEBO_MODEL_PATH $GAZEBO_MODEL_PATH" echo -e "LD_LIBRARY_PATH $LD_LIBRARY_PATH" # gazebo worlds/hitl_iris_vio.world -> modified by Nikita Shakhraichuk to launch vtol model in the gazebo gazebo worlds/hitl_standard_vtol.world
- "standard_vtol_hitl.sdf":
<?xml version="1.0"?> <sdf version='1.5'> <model name='standard_vtol_hitl'> <pose>0 0 0.246 0 0 0</pose> <link name='base_link'> <pose>0 0 0 0 0 0</pose> <inertial> <pose>0 0 0 0 0 0</pose> <mass>5</mass> <inertia> <ixx>0.477708333333</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.341666666667</iyy> <iyz>0</iyz> <izz>0.811041666667</izz> </inertia> </inertial> <collision name='base_link_collision'> <pose>0 0 -0.07 0 0 0</pose> <geometry> <box> <size>0.55 2.144 0.05</size> </box> </geometry> <surface> <contact> <ode> <kp>100000</kp> <kd>1.0</kd> <max_vel>0.1</max_vel> <min_depth>0.001</min_depth> </ode> </contact> <friction> <ode/> </friction> </surface> </collision> <visual name='base_link_visual'> <pose>0.53 -1.072 -0.1 1.5707963268 0 3.1415926536</pose> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://standard_vtol/meshes/x8_wing.dae</uri> </mesh> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>__default__</uri> </script> </material> </visual> <visual name='left_motor_column'> <pose>0 0.35 0.01 0 0 0</pose> <geometry> <box> <size>0.74 0.03 0.03</size> </box> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>__default__</uri> </script> </material> </visual> <visual name='right_motor_column'> <pose>0 -0.35 0.01 0 0 0</pose> <geometry> <box> <size>0.74 0.03 0.03</size> </box> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>__default__</uri> </script> </material> </visual> <visual name='m0'> <pose>-0.35 0.35 0.045 0 0 0</pose> <geometry> <cylinder> <length>0.035</length> <radius>0.02</radius> </cylinder> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>__default__</uri> </script> </material> </visual> <visual name='m1'> <pose>-0.35 -0.35 0.045 0 0 0</pose> <geometry> <cylinder> <length>0.035</length> <radius>0.02</radius> </cylinder> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>__default__</uri> </script> </material> </visual> <visual name='m2'> <pose>0.35 -0.35 0.045 0 0 0</pose> <geometry> <cylinder> <length>0.035</length> <radius>0.02</radius> </cylinder> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>__default__</uri> </script> </material> </visual> <visual name='m3'> <pose>0.35 0.35 0.045 0 0 0</pose> <geometry> <cylinder> <length>0.035</length> <radius>0.02</radius> </cylinder> </geometry> <material> <script> <name>Gazebo/DarkGrey</name> <uri>__default__</uri> </script> </material> </visual> <gravity>1</gravity> <velocity_decay/> <self_collide>0</self_collide> </link> <link name='standard_vtol_hitl/imu_link'> <pose>0 0 0 0 0 0</pose> <inertial> <pose>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='standard_vtol_hitl/imu_joint' type='revolute'> <child>standard_vtol_hitl/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> <include> <uri>model://airspeed</uri> <pose>0 0 0 0 0 0</pose> <name>airspeed</name> </include> <joint name='airspeed_joint' type='fixed'> <child>airspeed::link</child> <parent>base_link</parent> </joint> <link name='rotor_0'> <pose>0.35 -0.35 0.07 0 0 0</pose> <inertial> <pose>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.000166704</iyy> <iyz>0</iyz> <izz>0.000167604</izz> </inertia> </inertial> <collision name='rotor_0_collision'> <pose>0 0 0 0 0 0</pose> <geometry> <cylinder> <length>0.005</length> <radius>0.1</radius> </cylinder> </geometry> <surface> <contact> <ode/> </contact> <friction> <ode/> </friction> </surface> </collision> <visual name='rotor_0_visual'> <pose>0 0 0 0 0 0</pose> <geometry> <mesh> <scale>1 1 1</scale> <uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri> </mesh> </geometry> <material> <script> <name>Gazebo/Blue</name> <uri>__default__</uri> </script> </material> </visual> <gravity>1</gravity> <velocity_decay/> <self_collide>0</self_collide> </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> <link name='rotor_1'> <pose>-0.35 0.35 0.07 0 0 0</pose> <inertial> <pose>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.000166704</iyy> <iyz>0</iyz> <izz>0.000167604</izz> </inertia> </inertial> <collision name='rotor_1_collision'> <pose>0 0 0 0 0 0</pose> <geometry> <cylinder> <length>0.005</length> <radius>0.1</radius> </cylinder> </geometry> <surface> <contact> <ode/> </contact> <friction> <ode/> </friction> </surface> </collision> <visual name='rotor_1_visual'> <pose>0 0 0 0 0 0</pose> <geometry> <mesh> <scale>1 1 1</scale> <uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri> </mesh> </geometry> <material> <script> <name>Gazebo/Blue</name> <uri>__default__</uri> </script> </material> </visual> <gravity>1</gravity> <velocity_decay/> <self_collide>0</self_collide> </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> <link name='rotor_2'> <pose>0.35 0.35 0.07 0 0 0</pose> <inertial> <pose>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.000166704</iyy> <iyz>0</iyz> <izz>0.000167604</izz> </inertia> </inertial> <collision name='rotor_2_collision'> <pose>0 0 0 0 0 0</pose> <geometry> <cylinder> <length>0.005</length> <radius>0.1</radius> </cylinder> </geometry> <surface> <contact> <ode/> </contact> <friction> <ode/> </friction> </surface> </collision> <visual name='rotor_2_visual'> <pose>0 0 0 0 0 0</pose> <geometry> <mesh> <scale>1 1 1</scale> <uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri> </mesh> </geometry> <material> <script> <name>Gazebo/Blue</name> <uri>__default__</uri> </script> </material> </visual> <gravity>1</gravity> <velocity_decay/> <self_collide>0</self_collide> </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> <link name='rotor_3'> <pose>-0.35 -0.35 0.07 0 0 0</pose> <inertial> <pose>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.000166704</iyy> <iyz>0</iyz> <izz>0.000167604</izz> </inertia> </inertial> <collision name='rotor_3_collision'> <pose>0 0 0 0 0 0</pose> <geometry> <cylinder> <length>0.005</length> <radius>0.1</radius> </cylinder> </geometry> <surface> <contact> <ode/> </contact> <friction> <ode/> </friction> </surface> </collision> <visual name='rotor_3_visual'> <pose>0 0 0 0 0 0</pose> <geometry> <mesh> <scale>1 1 1</scale> <uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri> </mesh> </geometry> <material> <script> <name>Gazebo/Blue</name> <uri>__default__</uri> </script> </material> </visual> <gravity>1</gravity> <velocity_decay/> <self_collide>0</self_collide> </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> <link name='rotor_puller'> <pose>-0.22 0 0.0 0 1.57 0</pose> <inertial> <pose>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.000166704</iyy> <iyz>0</iyz> <izz>0.000167604</izz> </inertia> </inertial> <collision name='rotor_puller_collision'> <pose>0.0 0 -0.04 0 0 0</pose> <geometry> <cylinder> <length>0.005</length> <radius>0.06</radius> </cylinder> </geometry> <surface> <contact> <ode/> </contact> <friction> <ode/> </friction> </surface> </collision> <visual name='rotor_puller_visual'> <pose>0 0 -0.04 0 0 0</pose> <geometry> <mesh> <scale>0.8 0.8 0.8</scale> <uri>model://standard_vtol/meshes/iris_prop_ccw.dae</uri> </mesh> </geometry> <material> <script> <name>Gazebo/Blue</name> <uri>__default__</uri> </script> </material> </visual> <gravity>1</gravity> <velocity_decay/> <self_collide>0</self_collide> </link> <joint name='rotor_puller_joint' type='revolute'> <child>rotor_puller</child> <parent>base_link</parent> <axis> <xyz>1 0 0</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> <link name="left_elevon"> <inertial> <mass>0.00000001</mass> <inertia> <ixx>0.000001</ixx> <ixy>0.0</ixy> <iyy>0.000001</iyy> <ixz>0.0</ixz> <iyz>0.0</iyz> <izz>0.000001</izz> </inertia> <pose>0 0.3 0 0.00 0 0.0</pose> </inertial> <visual name='left_elevon_visual'> <pose>-0.105 0.004 -0.034 1.5707963268 0 3.1415926536</pose> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://standard_vtol/meshes/x8_elevon_left.dae</uri> </mesh> </geometry> <material> <script> <name>Gazebo/Blue</name> <uri>__default__</uri> </script> </material> </visual> </link> <link name="right_elevon"> <inertial> <mass>0.00000001</mass> <inertia> <ixx>0.000001</ixx> <ixy>0.0</ixy> <iyy>0.000001</iyy> <ixz>0.0</ixz> <iyz>0.0</iyz> <izz>0.000001</izz> </inertia> <pose>0 -0.6 0 0.00 0 0.0</pose> </inertial> <visual name='right_elevon_visual'> <pose>0.281 -1.032 -0.034 1.5707963268 0 3.1415926536</pose> <geometry> <mesh> <scale>0.001 0.001 0.001</scale> <uri>model://standard_vtol/meshes/x8_elevon_right.dae</uri> </mesh> </geometry> <material> <script> <name>Gazebo/Blue</name> <uri>__default__</uri> </script> </material> </visual> </link> <link name="elevator"> <inertial> <mass>0.00000001</mass> <inertia> <ixx>0.000001</ixx> <ixy>0.0</ixy> <iyy>0.000001</iyy> <ixz>0.0</ixz> <iyz>0.0</iyz> <izz>0.000001</izz> </inertia> <pose> -0.5 0 0 0.00 0 0.0</pose> </inertial> </link> <link name="rudder"> <inertial> <mass>0.00000001</mass> <inertia> <ixx>0.000001</ixx> <ixy>0.0</ixy> <iyy>0.000001</iyy> <ixz>0.0</ixz> <iyz>0.0</iyz> <izz>0.000001</izz> </inertia> <pose>-0.5 0 0.05 0 0 0 </pose> </inertial> </link> <joint name='left_elevon_joint' type='revolute'> <parent>base_link</parent> <child>left_elevon</child> <pose>-0.18 0.6 -0.005 0 0 0.265</pose> <axis> <xyz>0 1 0</xyz> <limit> <!-- -30/+30 deg. --> <lower>-0.53</lower> <upper>0.53</upper> </limit> <dynamics> <damping>1.000</damping> </dynamics> </axis> <physics> <ode> <implicit_spring_damper>1</implicit_spring_damper> </ode> </physics> </joint> <joint name='right_elevon_joint' type='revolute'> <parent>base_link</parent> <child>right_elevon</child> <pose>-0.18 -0.6 -0.005 0 0 -0.265</pose> <axis> <xyz>0 1 0</xyz> <limit> <!-- -30/+30 deg. --> <lower>-0.53</lower> <upper>0.53</upper> </limit> <dynamics> <damping>1.000</damping> </dynamics> </axis> <physics> <ode> <implicit_spring_damper>1</implicit_spring_damper> </ode> </physics> </joint> <joint name='elevator_joint' type='revolute'> <parent>base_link</parent> <child>elevator</child> <pose> -0.5 0 0 0 0 0</pose> <axis> <xyz>0 1 0</xyz> <limit> <!-- -30/+30 deg. --> <lower>-0.53</lower> <upper>0.53</upper> </limit> <dynamics> <damping>1.000</damping> </dynamics> </axis> <physics> <ode> <implicit_spring_damper>1</implicit_spring_damper> </ode> </physics> </joint> <joint name='rudder_joint' type='revolute'> <parent>base_link</parent> <child>rudder</child> <pose>-0.5 0 0.05 0.00 0 0.0</pose> <axis> <xyz>1 0 0</xyz> <limit> <!-- -30/+30 deg. --> <lower>-0.01</lower> <upper>0.01</upper> </limit> <dynamics> <damping>1.000</damping> </dynamics> </axis> <physics> <ode> <implicit_spring_damper>1</implicit_spring_damper> </ode> </physics> </joint> <include> <uri>model://gps</uri> <pose>0 0 0 0 0 0</pose> <name>gps0</name> </include> <joint name='gps0_joint' type='fixed'> <child>gps0::link</child> <parent>base_link</parent> </joint> <plugin name="left_wing_lift" filename="libLiftDragPlugin.so"> <a0>0.05984281113</a0> <cla>4.752798721</cla> <cda>0.6417112299</cda> <cma>0.0</cma> <alpha_stall>0.3391428111</alpha_stall> <cla_stall>-3.85</cla_stall> <cda_stall>-0.9233984055</cda_stall> <cma_stall>0</cma_stall> <cp>-0.05 0.3 0.05</cp> <area>0.50</area> <air_density>1.2041</air_density> <forward>1 0 0</forward> <upward>0 0 1</upward> <link_name>base_link</link_name> <control_joint_name> left_elevon_joint </control_joint_name> <control_joint_rad_to_cl>-1.0</control_joint_rad_to_cl> <robotNamespace></robotNamespace> <windSubTopic>world_wind</windSubTopic> </plugin> <plugin name="right_wing_lift" filename="libLiftDragPlugin.so"> <a0>0.05984281113</a0> <cla>4.752798721</cla> <cda>0.6417112299</cda> <cma>0.0</cma> <alpha_stall>0.3391428111</alpha_stall> <cla_stall>-3.85</cla_stall> <cda_stall>-0.9233984055</cda_stall> <cma_stall>0</cma_stall> <cp>-0.05 -0.3 0.05</cp> <area>0.50</area> <air_density>1.2041</air_density> <forward>1 0 0</forward> <upward>0 0 1</upward> <link_name>base_link</link_name> <control_joint_name> right_elevon_joint </control_joint_name> <control_joint_rad_to_cl>-1.0</control_joint_rad_to_cl> <robotNamespace></robotNamespace> <windSubTopic>world_wind</windSubTopic> </plugin> <plugin name="elevator_lift" filename="libLiftDragPlugin.so"> <a0>-0.2</a0> <cla>4.752798721</cla> <cda>0.6417112299</cda> <cma>0.0</cma> <alpha_stall>0.3391428111</alpha_stall> <cla_stall>-3.85</cla_stall> <cda_stall>-0.9233984055</cda_stall> <cma_stall>0</cma_stall> <cp>-0.5 0 0</cp> <area>0.01</area> <air_density>1.2041</air_density> <forward>1 0 0</forward> <upward>0 0 1</upward> <link_name>base_link</link_name> <control_joint_name> elevator_joint </control_joint_name> <control_joint_rad_to_cl>-12.0</control_joint_rad_to_cl> <robotNamespace></robotNamespace> <windSubTopic>world_wind</windSubTopic> </plugin> <plugin name="rudder_lift" filename="libLiftDragPlugin.so"> <a0>0.0</a0> <cla>4.752798721</cla> <cda>0.6417112299</cda> <cma>0.0.</cma> <alpha_stall>0.3391428111</alpha_stall> <cla_stall>-3.85</cla_stall> <cda_stall>-0.9233984055</cda_stall> <cma_stall>0</cma_stall> <cp>-0.5 0 0.05</cp> <area>0.02</area> <air_density>1.2041</air_density> <forward>1 0 0</forward> <upward>0 1 0</upward> <link_name>base_link</link_name> <robotNamespace></robotNamespace> <windSubTopic>world_wind</windSubTopic> </plugin> <plugin name='front_right_motor_model' filename='libgazebo_motor_model.so'> <robotNamespace></robotNamespace> <jointName>rotor_0_joint</jointName> <linkName>rotor_0</linkName> <turningDirection>ccw</turningDirection> <timeConstantUp>0.0125</timeConstantUp> <timeConstantDown>0.025</timeConstantDown> <maxRotVelocity>1500</maxRotVelocity> <motorConstant>2e-05</motorConstant> <momentConstant>0.06</momentConstant> <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic> <motorNumber>0</motorNumber> <rotorDragCoefficient>0.000106428</rotorDragCoefficient> <rollingMomentCoefficient>1e-06</rollingMomentCoefficient> <motorSpeedPubTopic>/motor_speed/0</motorSpeedPubTopic> <rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim> </plugin> <plugin name='back_left_motor_model' filename='libgazebo_motor_model.so'> <robotNamespace></robotNamespace> <jointName>rotor_1_joint</jointName> <linkName>rotor_1</linkName> <turningDirection>ccw</turningDirection> <timeConstantUp>0.0125</timeConstantUp> <timeConstantDown>0.025</timeConstantDown> <maxRotVelocity>1500</maxRotVelocity> <motorConstant>2e-05</motorConstant> <momentConstant>0.06</momentConstant> <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic> <motorNumber>1</motorNumber> <rotorDragCoefficient>0.000106428</rotorDragCoefficient> <rollingMomentCoefficient>1e-06</rollingMomentCoefficient> <motorSpeedPubTopic>/motor_speed/1</motorSpeedPubTopic> <rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim> </plugin> <plugin name='front_left_motor_model' filename='libgazebo_motor_model.so'> <robotNamespace></robotNamespace> <jointName>rotor_2_joint</jointName> <linkName>rotor_2</linkName> <turningDirection>cw</turningDirection> <timeConstantUp>0.0125</timeConstantUp> <timeConstantDown>0.025</timeConstantDown> <maxRotVelocity>1500</maxRotVelocity> <motorConstant>2e-05</motorConstant> <momentConstant>0.06</momentConstant> <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic> <motorNumber>2</motorNumber> <rotorDragCoefficient>0.000106428</rotorDragCoefficient> <rollingMomentCoefficient>1e-06</rollingMomentCoefficient> <motorSpeedPubTopic>/motor_speed/2</motorSpeedPubTopic> <rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim> </plugin> <plugin name='back_right_motor_model' filename='libgazebo_motor_model.so'> <robotNamespace></robotNamespace> <jointName>rotor_3_joint</jointName> <linkName>rotor_3</linkName> <turningDirection>cw</turningDirection> <timeConstantUp>0.0125</timeConstantUp> <timeConstantDown>0.025</timeConstantDown> <maxRotVelocity>1500</maxRotVelocity> <motorConstant>2e-05</motorConstant> <momentConstant>0.06</momentConstant> <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic> <motorNumber>3</motorNumber> <rotorDragCoefficient>0.000106428</rotorDragCoefficient> <rollingMomentCoefficient>1e-06</rollingMomentCoefficient> <motorSpeedPubTopic>/motor_speed/3</motorSpeedPubTopic> <rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim> </plugin> <plugin name='puller_motor_model' filename='libgazebo_motor_model.so'> <robotNamespace></robotNamespace> <jointName>rotor_puller_joint</jointName> <linkName>rotor_puller</linkName> <turningDirection>cw</turningDirection> <timeConstantUp>0.0125</timeConstantUp> <timeConstantDown>0.025</timeConstantDown> <maxRotVelocity>3500</maxRotVelocity> <motorConstant>8.54858e-06</motorConstant> <momentConstant>0.01</momentConstant> <commandSubTopic>/gazebo/command/motor_speed</commandSubTopic> <motorNumber>4</motorNumber> <rotorDragCoefficient>0.000106428</rotorDragCoefficient> <rollingMomentCoefficient>1e-06</rollingMomentCoefficient> <motorSpeedPubTopic>/motor_speed/4</motorSpeedPubTopic> <rotorVelocitySlowdownSim>20</rotorVelocitySlowdownSim> </plugin> <plugin name='gazebo_imu_plugin' filename='libgazebo_imu_plugin.so'> <robotNamespace></robotNamespace> <linkName>standard_vtol_hitl/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> <plugin name='groundtruth_plugin' filename='libgazebo_groundtruth_plugin.so'> <robotNamespace/> </plugin> <plugin name='magnetometer_plugin' filename='libgazebo_magnetometer_plugin.so'> <robotNamespace/> <pubRate>500</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>250</pubRate> <baroTopic>/baro</baroTopic> </plugin> <plugin name='mavlink_interface' filename='libgazebo_mavlink_interface.so'> <robotNamespace/> <imuSubTopic>/imu</imuSubTopic> <magSubTopic>/mag</magSubTopic> <gpsSubTopic>/gps0</gpsSubTopic> <baroSubTopic>/baro</baroSubTopic> <mavlink_addr>INADDR_ANY</mavlink_addr> <mavlink_udp_port>14560</mavlink_udp_port> <mavlink_tcp_port>4560</mavlink_tcp_port> <serialEnabled>1</serialEnabled> <serialDevice>/dev/ttyUSB0</serialDevice> <baudRate>2000000</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>1</hil_mode> <hil_state_level>0</hil_state_level> <send_vision_estimation>0</send_vision_estimation> <send_odometry>1</send_odometry> <enable_lockstep>0</enable_lockstep> <use_tcp>1</use_tcp> <motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic> <control_channels> <channel name="rotor0"> <input_index>0</input_index> <input_offset>0</input_offset> <input_scaling>1500</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>0</zero_position_armed> <joint_control_type>velocity</joint_control_type> <joint_name>rotor_0_joint</joint_name> </channel> <channel name="rotor1"> <input_index>1</input_index> <input_offset>0</input_offset> <input_scaling>1500</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>0</zero_position_armed> <joint_control_type>velocity</joint_control_type> <joint_name>rotor_1_joint</joint_name> </channel> <channel name="rotor2"> <input_index>2</input_index> <input_offset>0</input_offset> <input_scaling>1500</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>0</zero_position_armed> <joint_control_type>velocity</joint_control_type> <joint_name>rotor_2_joint</joint_name> </channel> <channel name="rotor3"> <input_index>3</input_index> <input_offset>0</input_offset> <input_scaling>1500</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>0</zero_position_armed> <joint_control_type>velocity</joint_control_type> <joint_name>rotor_3_joint</joint_name> </channel> <channel name="rotor4"> <input_index>4</input_index> <input_offset>0</input_offset> <input_scaling>5500</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>0</zero_position_armed> <joint_control_type>velocity</joint_control_type> <joint_name>rotor_puller_joint</joint_name> </channel> <channel name="left_elevon"> <input_index>5</input_index> <input_offset>0</input_offset> <input_scaling>1</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>0</zero_position_armed> <joint_control_type>position_kinematic</joint_control_type> <joint_name>left_elevon_joint</joint_name> </channel> <channel name="right_elevon"> <input_index>6</input_index> <input_offset>0</input_offset> <input_scaling>1</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>0</zero_position_armed> <joint_control_type>position_kinematic</joint_control_type> <joint_name>right_elevon_joint</joint_name> </channel> <channel name="elevator"> <input_index>7</input_index> <input_offset>0</input_offset> <input_scaling>1</input_scaling> <zero_position_disarmed>0</zero_position_disarmed> <zero_position_armed>0</zero_position_armed> <joint_control_type>position_kinematic</joint_control_type> <joint_name>elevator_joint</joint_name> </channel> </control_channels> </plugin> <static>0</static> </model> </sdf>
-
@garret You need to look at the CPU utilization in the DSP where the majority of the PX4 code is running.
top
will show you only what's happening on the applications processor (Linux) side. The PX4 log contains this information. -
@garret If the Iris configuration doesn't produce timeouts then possibly it's Gazebo not sending sensor updates fast enough. But I'm just guessing at this point. We've never tried a VTOL configuration so you are in new territory here. I'd first take a PX4 log and verify that the DSP CPU load is not exceeding 65 - 70%. Then perhaps start putting some diagnostic prints around the reception of the sensor messages from Gazebo and see how often they are being sent. Just have to start isolating the root cause.