Hi!
Iām currently trying to add a model for a Gazebo simulation, based on the Typhoon H480 hexacopter.
Since Iāve only see an airframe example available, Iāve downloaded a 3D model from here and then Iāve modified it a bit to include plugins and whatnot.
Then I created a new airframe file (named 6012_gz_typhoon_h480
), filled like this:
#!/bin/sh
#
# @name Typhoon H480
#
# @type Hexarotor x
#
. ${R}etc/init.d/rc.mc_defaults
PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=typhoon_h480}
param set-default SIM_GZ_EN 1
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 1
param set-default SENS_EN_MAGSIM 1
param set-default MAV_TYPE 13
param set-default CA_AIRFRAME 0
param set-default CA_ROTOR_COUNT 6
# Rotors
param set-default CA_ROTOR0_PX -0.00187896
param set-default CA_ROTOR0_PY 0.242705
param set-default CA_ROTOR0_KM -0.05 # CW
param set-default CA_ROTOR1_PX -0.00187896
param set-default CA_ROTOR1_PY -0.242705
param set-default CA_ROTOR1_KM 0.05 # CCW
param set-default CA_ROTOR2_PX 0.211396
param set-default CA_ROTOR2_PY -0.119762
param set-default CA_ROTOR2_KM -0.05 # CW
param set-default CA_ROTOR3_PX -0.209396
param set-default CA_ROTOR3_PY 0.122762
param set-default CA_ROTOR3_KM 0.05 # CCW
param set-default CA_ROTOR4_PX 0.211396
param set-default CA_ROTOR4_PY 0.119762
param set-default CA_ROTOR4_KM 0.05 # CCW
param set-default CA_ROTOR5_PX -0.209396
param set-default CA_ROTOR5_PY -0.122762
param set-default CA_ROTOR5_KM -0.05 # CW
# Set actuators to some functions
param set-default SIM_GZ_EC_FUNC1 101
param set-default SIM_GZ_EC_FUNC2 102
param set-default SIM_GZ_EC_FUNC3 103
param set-default SIM_GZ_EC_FUNC4 104
param set-default SIM_GZ_EC_FUNC5 105
param set-default SIM_GZ_EC_FUNC6 106
# Min-Max throttle values
param set-default SIM_GZ_EC_MIN1 150
param set-default SIM_GZ_EC_MIN2 150
param set-default SIM_GZ_EC_MIN3 150
param set-default SIM_GZ_EC_MIN4 150
param set-default SIM_GZ_EC_MIN5 150
param set-default SIM_GZ_EC_MIN6 150
param set-default SIM_GZ_EC_MAX1 1000
param set-default SIM_GZ_EC_MAX2 1000
param set-default SIM_GZ_EC_MAX3 1000
param set-default SIM_GZ_EC_MAX4 1000
param set-default SIM_GZ_EC_MAX5 1000
param set-default SIM_GZ_EC_MAX6 1000
# Throttle % needed to hover
param set-default MPC_THR_HOVER 0.60
Iāve also modified the needed CMakelists.txt
file to build everything, while I did not modify any startup file (apart from some echo
used to troubleshoot this problem).
When launching make px4_sitl gz_typhoon_h480
, Gazebo starts and the model appears, but I cannot takeoff. Hereās the output, after a make distclean
:
slim71@slim71-Ubuntu:~/Documents/git/SpartanLIFT/PX4-Autopilot$ make px4_sitl gz_typhoon_h480
-- PX4 version: v1.14.0-beta2-242-gfc357921fd (1.14.0)
-- Found PythonInterp: /usr/bin/python3 (found suitable version "3.10.6", minimum required is "3")
-- PX4 config file: /home/slim71/Documents/git/SpartanLIFT/PX4-Autopilot/boards/px4/sitl/default.px4board
-- PLATFORM posix
-- ROMFSROOT px4fmu_common
-- ROOTFSDIR .
-- TESTING y
-- ETHERNET y
-- PX4 config: px4_sitl_default
-- PX4 platform: posix
-- PX4 lockstep: enabled
-- The CXX compiler identification is GNU 11.3.0
-- The C compiler identification is GNU 11.3.0
-- The ASM compiler identification is GNU
-- Found assembler: /usr/lib/ccache/cc
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done
-- Check for working CXX compiler: /usr/lib/ccache/c++ - skipped
-- Detecting CXX compile features
-- Detecting CXX compile features - done
-- Detecting C compiler ABI info
-- Detecting C compiler ABI info - done
-- Check for working C compiler: /usr/lib/ccache/cc - skipped
-- Detecting C compile features
-- Detecting C compile features - done
-- cmake build type: RelWithDebInfo
-- ccache enabled via symlink (/usr/lib/ccache/c++ -> /usr/bin/ccache)
-- Looking for gz-transport12 -- found version 12.2.0
-- Searching for dependencies of gz-transport12
-- Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so (found suitable version "3.12.4", minimum required is "3")
-- Config-file not installed for ZeroMQ -- checking for pkg-config
-- Checking for module 'libzmq >= 4'
-- Found libzmq , version 4.3.4
-- Found ZeroMQ: TRUE (Required is at least version "4")
-- Checking for module 'uuid'
-- Found uuid, version 2.37.2
-- Found UUID: TRUE
-- Looking for gz-utils2 -- found version 2.0.0
-- Searching for dependencies of gz-utils2
-- Searching for <gz-utils2> component [cli]
-- Looking for gz-utils2-cli -- found version 2.0.0
-- Searching for dependencies of gz-utils2-cli
-- Looking for gz-msgs9 -- found version 9.4.0
-- Searching for dependencies of gz-msgs9
-- Looking for gz-math7 -- found version 7.2.0
-- Searching for dependencies of gz-math7
-- Looking for gz-utils2 -- found version 2.0.0
-- Checking for module 'tinyxml2'
-- Found tinyxml2, version 9.0.0
-- Found Java: /usr/bin/java (found version "11.0.19")
-- ROMFS: ROMFS/px4fmu_common
Architecture: amd64
==> CPACK_INSTALL_PREFIX = @DEB_INSTALL_PREFIX@
-- Configuring done
-- Generating done
-- Build files have been written to: /home/slim71/Documents/git/SpartanLIFT/PX4-Autopilot/build/px4_sitl_default
[0/903] git submodule src/drivers/gps/devices
[10/903] git submodule src/modules/mavlink/mavlink
[12/903] git submodule src/modules/uxrce_dds_client/Micro-XRCE-DDS-Client
[902/903] cd /home/slim71/Documents/git/SpartanLIFT/PX4-Autopilot/build/px4_sitl_default/src/modules...=gz_typhoon_h480 /home/slim71/Documents/git/SpartanLIFT/PX4-Autopilot/build/px4_sitl_default/bin/px4
______ __ __ ___
| ___ \ \ \ / / / |
| |_/ / \ V / / /| |
| __/ / \ / /_| |
| | / /^\ \ \___ |
\_| \/ \/ |_/
px4 starting.
INFO [px4] startup script: /bin/sh etc/init.d-posix/rcS 0
INFO [init] found model autostart file as SYS_AUTOSTART=6012
INFO [param] selected parameter default file parameters.bson
INFO [param] selected parameter backup file parameters_backup.bson
SYS_AUTOCONFIG: curr: 0 -> new: 1
reset params
autoconf yes
SYS_AUTOSTART: curr: 0 -> new: 6012
CAL_ACC0_ID: curr: 0 -> new: 1310988
CAL_GYRO0_ID: curr: 0 -> new: 1310988
CAL_ACC1_ID: curr: 0 -> new: 1310996
CAL_GYRO1_ID: curr: 0 -> new: 1310996
CAL_ACC2_ID: curr: 0 -> new: 1311004
CAL_GYRO2_ID: curr: 0 -> new: 1311004
CAL_MAG0_ID: curr: 0 -> new: 197388
CAL_MAG0_PRIO: curr: -1 -> new: 50
CAL_MAG1_ID: curr: 0 -> new: 197644
CAL_MAG1_PRIO: curr: -1 -> new: 50
SENS_BOARD_X_OFF: curr: 0.0000 -> new: 0.0000
SENS_DPRES_OFF: curr: 0.0000 -> new: 0.0010
INFO [dataman] data manager file './dataman' size is 7866640 bytes
INFO [init] starting gazebo with world: /home/slim71/Documents/git/SpartanLIFT/PX4-Autopilot/Tools/simulation/gz/worlds/default.sdf
WARN [init] PX4_GZ_MODEL_NAME or PX4_GZ_MODEL not set using PX4_SIM_MODEL.
INFO [gz_bridge] world: default, model name: typhoon_h480_0, simulation model: typhoon_h480
INFO [lockstep_scheduler] setting initial absolute time to 8000 us
INFO [commander] LED: open /dev/led0 failed (22)
INFO [tone_alarm] home set
libEGL warning: egl: failed to create dri2 screen
libEGL warning: egl: failed to create dri2 screen
INFO [mavlink] mode: Normal, data rate: 4000000 B/s on udp port 18570 remote port 14550
INFO [tone_alarm] notify negative
INFO [mavlink] mode: Onboard, data rate: 4000000 B/s on udp port 14580 remote port 14540
INFO [mavlink] mode: Onboard, data rate: 4000 B/s on udp port 14280 remote port 14030
INFO [mavlink] mode: Gimbal, data rate: 400000 B/s on udp port 13030 remote port 13280
INFO [logger] logger started (mode=all)
INFO [logger] Start file log (type: full)
INFO [logger] [logger] ./log/2023-06-15/20_21_22.ulg
INFO [logger] Opened full log file: ./log/2023-06-15/20_21_22.ulg
INFO [mavlink] MAVLink only on localhost (set param MAV_{i}_BROADCAST = 1 to enable network)
INFO [mavlink] MAVLink only on localhost (set param MAV_{i}_BROADCAST = 1 to enable network)
INFO [px4] Startup script returned successfully
pxh> WARN [health_and_arming_checks] Preflight Fail: Accel Sensor 0 missing
WARN [health_and_arming_checks] Preflight Fail: ekf2 missing data
WARN [health_and_arming_checks] Preflight Fail: Gyro Sensor 0 missing
ERROR [ekf2] start failed (-1)
PX4 Exiting...
pxh> Exiting NOW.
ninja: build stopped: interrupted by user.
make: *** [Makefile:232: px4_sitl] Interrupt
It seems like some sensors are missing, but I do not understand how to specify them for the simulation. Iāve seen the parameters for the simulated GPS, Baro and Mag, but nothing moreā¦
Am I missing some other steps?
Also, in QGroundControl I can see that the sensors are labeled as available, but at the same time the bar at the top of the homepage is red (clicking it gives me the same status), so Iām a little confused!