diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4003_gz_rc_cessna b/ROMFS/px4fmu_common/init.d-posix/airframes/4003_gz_rc_cessna index e87e013e5d77..bfecc1a0ca87 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4003_gz_rc_cessna +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4003_gz_rc_cessna @@ -11,14 +11,13 @@ PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} PX4_SIM_MODEL=${PX4_SIM_MODEL:=rc_cessna} param set-default SIM_GZ_EN 1 +param set-default SIM_GZ_RUN_GZSIM 0 param set-default SENS_EN_GPSSIM 1 -param set-default SENS_EN_BAROSIM 0 +param set-default SENS_EN_BAROSIM 1 param set-default SENS_EN_MAGSIM 1 param set-default SENS_EN_ARSPDSIM 1 - - param set-default FW_LND_ANG 8 param set-default NPFG_PERIOD 12 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol index 39f5f8f3e25d..9841c988c614 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol @@ -12,9 +12,10 @@ PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} PX4_SIM_MODEL=${PX4_SIM_MODEL:=standard_vtol} param set-default SIM_GZ_EN 1 +param set-default SIM_GZ_RUN_GZSIM 0 param set-default SENS_EN_GPSSIM 1 -param set-default SENS_EN_BAROSIM 0 +param set-default SENS_EN_BAROSIM 1 param set-default SENS_EN_MAGSIM 1 param set-default SENS_EN_ARSPDSIM 1 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4401_gz_ssrc_fog_x b/ROMFS/px4fmu_common/init.d-posix/airframes/4401_gz_ssrc_fog_x new file mode 100644 index 000000000000..708253259623 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4401_gz_ssrc_fog_x @@ -0,0 +1,71 @@ +#!/bin/sh +# +# @name Gazebo x500 +# +# @type Quadrotor 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:=holybro-x500} + +param set-default SIM_GZ_EN 1 +param set-default SIM_GZ_RUN_GZSIM 0 + +param set-default SENS_EN_GPSSIM 1 +param set-default SENS_EN_BAROSIM 1 +param set-default SENS_EN_MAGSIM 1 + +param set-default CA_AIRFRAME 0 +param set-default CA_ROTOR_COUNT 4 + +param set-default CA_ROTOR0_PX 0.175 +param set-default CA_ROTOR0_PY 0.175 +param set-default CA_ROTOR0_KM 0.05 + +param set-default CA_ROTOR1_PX -0.175 +param set-default CA_ROTOR1_PY -0.175 +param set-default CA_ROTOR1_KM 0.05 + +param set-default CA_ROTOR2_PX 0.175 +param set-default CA_ROTOR2_PY -0.175 +param set-default CA_ROTOR2_KM -0.05 + +param set-default CA_ROTOR3_PX -0.175 +param set-default CA_ROTOR3_PY 0.175 +param set-default CA_ROTOR3_KM -0.05 + +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_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_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 MPC_THR_HOVER 0.60 + +# extra +param set COM_RCL_EXCEPT 4 +param set NAV_DLL_ACT 0 +param set NAV_RCL_ACT 0 +param set MAV_0_BROADCAST 1 +param set IMU_GYRO_CUTOFF 60 +param set IMU_DGYRO_CUTOFF 30 +param set MC_ROLLRATE_P 0.14 +param set MC_PITCHRATE_P 0.14 +param set MC_ROLLRATE_I 0.3 +param set MC_PITCHRATE_I 0.3 +param set MC_ROLLRATE_D 0.004 +param set MC_PITCHRATE_D 0.004 +param set BAT_N_CELLS 4 +param set SDLOG_MODE 0 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4440_gz_ssrc_skywalker_x8 b/ROMFS/px4fmu_common/init.d-posix/airframes/4440_gz_ssrc_skywalker_x8 new file mode 100644 index 000000000000..d2ede5ef2686 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4440_gz_ssrc_skywalker_x8 @@ -0,0 +1,95 @@ +#!/bin/sh +# +# @name SSRC Skywalker X8 +# +# @type Flying Wing +# @class Plane +# + +. /etc/init.d/rc.fw_defaults + +PX4_SIMULATOR=${PX4_SIMULATOR:=gz} +PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} +PX4_SIM_MODEL=${PX4_SIM_MODEL:=skywalker_x8} + +param set-default SIM_GZ_EN 1 +param set-default SIM_GZ_RUN_GZSIM 0 + +param set-default SENS_EN_GPSSIM 1 +param set-default SENS_BAROSIM 0 +param set-default SENS_EN_MAGSIM 1 +param set-default SENS_EN_ARSPDSIM 1 + +# Control allocator parameters +param set-default CA_AIRFRAME 1 +param set-default CA_ROTOR_COUNT 1 +param set-default CA_SV_CS_COUNT 2 +param set-default CA_SV_CS0_TYPE 5 +param set-default CA_SV_CS0_TRQ_P 0.5 +param set-default CA_SV_CS0_TRQ_R -0.5 +param set-default CA_SV_CS1_TYPE 6 +param set-default CA_SV_CS1_TRQ_P 0.5 +param set-default CA_SV_CS1_TRQ_R 0.5 + +# GZ SIM +param set-default SIM_GZ_EC_FUNC1 101 +param set-default SIM_GZ_EC_MIN1 0 +param set-default SIM_GZ_EC_MAX1 1000 + +param set-default SIM_GZ_SV_FUNC1 201 +param set-default SIM_GZ_SV_FUNC2 202 + +# Airspeed parameters +param set-default ASPD_PRIMARY 1 +# param set-default FW_AIRSPD_MAX 22.0 +# param set-default FW_AIRSPD_MIN 14.0 +# param set-default FW_AIRSPD_STALL 12.0 +# param set-default FW_AIRSPD_TRIM 18.0 + +# Maximum landing slope angle in deg +param set-default FW_LND_ANG 8 + +# RC loss failsafe to HOLD mode +param set-default COM_RC_IN_MODE 1 + +# Fixed wing control +# Pitch rate +param set-default FW_PR_P 0.9 +param set-default FW_PR_FF 0.5 +param set-default FW_PR_I 0.5 +param set-default TRIM_PITCH -0.15 +# Pitch angle in deg +param set-default FW_PSP_OFF 0 +param set-default FW_P_LIM_MIN -15 +# Roll rate +param set-default FW_RR_FF 0.5 +param set-default FW_RR_P 0.3 +param set-default FW_RR_I 0.5 +# Yaw rate +param set-default FW_YR_FF 0.5 +param set-default FW_YR_P 0.6 +param set-default FW_YR_I 0.5 +# Throttle limit +# param set-default FW_THR_MAX 0.6 +# param set-default FW_THR_MIN 0.05 +# param set-default FW_THR_TRIM 0.25 +# Climb and sink rate +param set-default FW_T_CLMB_MAX 8 +param set-default FW_T_SINK_MAX 2.7 +param set-default FW_T_SINK_MIN 2.2 + +# Navigation +param set-default NAV_ACC_RAD 15 +param set-default NAV_DLL_ACT 2 + +# Misc +param set-default MIS_TAKEOFF_ALT 30.0 +param set-default RTL_RETURN_ALT 30.0 + +# Disable internal magnetometer +param set CAL_MAG0_PRIO 0 + +# Catapult launch with acc threshold trigger +param set-default FW_LAUN_DETCN_ON 1 +param set-default FW_THR_IDLE 0.1 # needs to be running before throw as that's how gazebo detects arming +param set-default FW_LAUN_AC_THLD 10 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/50005_gz_ssrc_scout_mini_rover b/ROMFS/px4fmu_common/init.d-posix/airframes/50005_gz_ssrc_scout_mini_rover new file mode 100644 index 000000000000..37689eeb9e8e --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/50005_gz_ssrc_scout_mini_rover @@ -0,0 +1,77 @@ +#!/bin/sh +# +# @name SSRC SCOUT MINI UGV +# +# @url https://global.agilex.ai/products/scout-mini +# +# @type Rover +# @class Rover +# + +. ${R}etc/init.d/rc.rover_defaults + +PX4_SIMULATOR=${PX4_SIMULATOR:=gz} +PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} +PX4_SIM_MODEL=${PX4_SIM_MODEL:=scout_mini} + +param set-default SIM_GZ_EN 1 +param set-default SIM_GZ_RUN_GZSIM 0 + +param set-default CA_AIRFRAME 6 + +param set-default SENS_EN_GPSSIM 1 +param set-default SENS_EN_BAROSIM 1 +param set-default SENS_EN_MAGSIM 1 + +param set IMU_GYRO_CUTOFF 60 +param set IMU_DGYRO_CUTOFF 30 + +param set-default SYS_HAS_BARO 0 + +param set-default BAT1_N_CELLS 4 + +param set-default MIS_TAKEOFF_ALT 0.01 + +param set-default NAV_ACC_RAD 0.5 # reached when within 0.5m of waypoint + +# Enable Airspeed check circuit breaker because Rovers will have no airspeed sensor +param set-default CBRK_AIRSPD_CHK 162128 + +# EKF2 +param set-default EKF2_GBIAS_INIT 0.01 +param set-default EKF2_ANGERR_INIT 0.01 +param set-default EKF2_MAG_TYPE 1 +param set-default EKF2_REQ_SACC 1.0 +param set-default EKF2_REQ_VDRIFT 0.4 +param set-default EKF2_REQ_HDRIFT 0.2 + + +################################# +# Rover Position Control Module # +################################# + +param set-default GND_SP_CTRL_MODE 1 +param set-default GND_L1_DIST 5 +param set-default GND_L1_PERIOD 3 +param set-default GND_THR_CRUISE 1 +param set-default GND_THR_MAX 1 + +# Because this is differential drive, it can make a turn with radius 0. +# This corresponds to a turn angle of pi radians. +# If a special case is made for differential-drive, this will need to change. +param set-default GND_MAX_ANG 3.142 +param set-default GND_WHEEL_BASE 0.45 + +# TODO: Set to -1.0, to allow reversing. This will require many changes in the codebase +# to support negative throttle. +param set-default GND_THR_MIN 0 +param set-default GND_SPEED_P 0.4 +param set-default GND_SPEED_I 1 +param set-default GND_SPEED_D 0.001 +param set-default GND_SPEED_MAX 3.0 +param set-default GND_SPEED_TRIM 3.0 +param set-default GND_SPEED_THR_SC 1.0 +param set-default GND_VEL_CTRL 1 +param set-default GND_ANG_VEL_CTRL 1 +param set-default GND_ACC_LIMIT 10 +param set-default GND_DEC_LIMIT 50 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index a588010d1f2e..ed2d57ae77bc 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt @@ -79,6 +79,9 @@ px4_add_romfs_files( 4004_gz_standard_vtol 4005_gz_x500_vision 4006_gz_px4vision + 4401_gz_ssrc_fog_x + 4440_gz_ssrc_skywalker_x8 + 50005_gz_ssrc_scout_mini_rover 6011_gazebo-classic_typhoon_h480 6011_gazebo-classic_typhoon_h480.post diff --git a/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator b/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator index 1f4693d4c1b3..e5e2ab5f1441 100644 --- a/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator +++ b/ROMFS/px4fmu_common/init.d-posix/px4-rc.simulator @@ -38,44 +38,50 @@ if [ "$PX4_SIMULATOR" = "sihsim" ] || [ "$(param show -q SYS_AUTOSTART)" -eq "0" elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; then - # source generated gz_env.sh for GZ_SIM_RESOURCE_PATH - if [ -f ./gz_env.sh ]; then - . ./gz_env.sh + # allow starting of gz sim optionally + if [ "$(param show -q SIM_GZ_RUN_GZSIM)" -eq "1" ]; + then + # source generated gz_env.sh for GZ_SIM_RESOURCE_PATH + if [ -f ./gz_env.sh ]; then + . ./gz_env.sh - elif [ -f ../gz_env.sh ]; then - . ../gz_env.sh - fi + elif [ -f ../gz_env.sh ]; then + . ../gz_env.sh + fi - # "gz sim" only avaiilable in Garden and later - GZ_SIM_VERSIONS=$(gz sim --versions 2>&1) - if [ $? -eq 0 ] && [ "${GZ_SIM_VERSIONS}" != "" ] - then - # "gz sim" from Garden on - gz_command="gz" - gz_sub_command="sim" - else - echo "ERROR [init] Gazebo gz please install gz-garden" - exit 1 - fi + # "gz sim" only avaiilable in Garden and later + GZ_SIM_VERSIONS=$(gz sim --versions 2>&1) + if [ $? -eq 0 ] && [ "${GZ_SIM_VERSIONS}" != "" ] + then + # "gz sim" from Garden on + gz_command="gz" + gz_sub_command="sim" + else + echo "ERROR [init] Gazebo gz please install gz-garden" + exit 1 + fi - # look for running ${gz_command} gazebo world - gz_world=$( ${gz_command} topic -l | grep -m 1 -e "/world/.*/clock" | sed 's/\/world\///g; s/\/clock//g' ) + # look for running ${gz_command} gazebo world + gz_world=$( ${gz_command} topic -l | grep -m 1 -e "/world/.*/clock" | sed 's/\/world\///g; s/\/clock//g' ) - # shellcheck disable=SC2153 - if [ -z "${gz_world}" ] && [ -n "${PX4_GZ_WORLDS}" ] && [ -n "${PX4_GZ_WORLD}" ]; then + # shellcheck disable=SC2153 + if [ -z "${gz_world}" ] && [ -n "${PX4_GZ_WORLDS}" ] && [ -n "${PX4_GZ_WORLD}" ]; then - echo "INFO [init] starting gazebo with world: ${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf" + echo "INFO [init] starting gazebo with world: ${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf" - ${gz_command} ${gz_sub_command} --verbose=1 -r -s "${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf" & + ${gz_command} ${gz_sub_command} --verbose=1 -r -s "${PX4_GZ_WORLDS}/${PX4_GZ_WORLD}.sdf" & - if [ -z "${HEADLESS}" ]; then - # HEADLESS not set, starting gui - ${gz_command} ${gz_sub_command} -g & - fi + if [ -z "${HEADLESS}" ]; then + # HEADLESS not set, starting gui + ${gz_command} ${gz_sub_command} -g & + fi + else + echo "INFO [init] gazebo already running world: ${gz_world}" + PX4_GZ_WORLD=${gz_world} + fi else - echo "INFO [init] gazebo already running world: ${gz_world}" - PX4_GZ_WORLD=${gz_world} + echo "INFO [init] gazebo run disabled" fi # start gz_bridge @@ -116,6 +122,43 @@ elif [ "$PX4_SIMULATOR" = "gz" ] || [ "$(param show -q SIM_GZ_EN)" -eq "1" ]; th exit 1 fi + elif [ -n "${PX4_GZ_MODEL}" ] && [ -n "${PX4_GZ_MODEL_NAME}" ]; then + # model type and name specified, gz_bridge will spawn model with name + + if [ -n "${PX4_GZ_MODEL_POSE}" ]; then + # Clean potential input line formatting. + model_pose="$( echo "${PX4_GZ_MODEL_POSE}" | sed -e 's/^[ \t]*//; s/[ \t]*$//; s/,/ /g; s/ / /g; s/ /,/g' )" + echo "INFO [init] PX4_GZ_MODEL_POSE set, spawning at: ${model_pose}" + + else + echo "WARN [init] PX4_GZ_MODEL_POSE not set, spawning at origin." + model_pose="0,0,0,0,0,0" + fi + + # start gz bridge with pose arg. + if gz_bridge start -p "${model_pose}" -m "${PX4_GZ_MODEL}" -n "${PX4_GZ_MODEL_NAME}" -w "${PX4_GZ_WORLD}" -i "${px4_instance}"; then + if param compare -s SENS_EN_BAROSIM 1 + then + sensor_baro_sim start + fi + if param compare -s SENS_EN_GPSSIM 1 + then + sensor_gps_sim start + fi + if param compare -s SENS_EN_MAGSIM 1 + then + sensor_mag_sim start + fi + if param compare -s SENS_EN_ARSPDSIM 1 + then + sensor_airspeed_sim start + fi + + else + echo "ERROR [init] gz_bridge failed to start" + exit 1 + fi + elif [ -n "${PX4_GZ_MODEL_NAME}" ] && [ -z "${PX4_GZ_MODEL}" ]; then # model name specificed, gz_bridge will attach to existing model diff --git a/ROMFS/px4fmu_common/init.d/airframes/50005_ssrc_scout_mini_rover b/ROMFS/px4fmu_common/init.d/airframes/50005_ssrc_scout_mini_rover index f3894e439fd3..f0ebcf96f368 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50005_ssrc_scout_mini_rover +++ b/ROMFS/px4fmu_common/init.d/airframes/50005_ssrc_scout_mini_rover @@ -15,8 +15,7 @@ # Rover interface param set-default RI_ROVER_TYPE 0 -param set-default RI_MAN_THR_MAX 1.0 -param set-default RI_MIS_THR_MAX 1.0 +param set-default RI_MAN_SPD_SC 1.0 # Battery setting param set-default BAT1_N_CELLS 7 @@ -54,9 +53,13 @@ param set-default GND_THR_MIN 0 param set-default GND_SPEED_P 0.4 param set-default GND_SPEED_I 1 param set-default GND_SPEED_D 0.001 -param set-default GND_SPEED_IMAX 1 -param set-default GND_SPEED_MAX 1 -param set-default GND_SPEED_THR_SC 1 +param set-default GND_SPEED_MAX 3.0 +param set-default GND_SPEED_TRIM 3.0 +param set-default GND_SPEED_THR_SC 1.0 +param set-default GND_VEL_CTRL 1 +param set-default GND_ANG_VEL_CTRL 1 +param set-default GND_ACC_LIMIT 10 +param set-default GND_DEC_LIMIT 50 param set-default MIS_TAKEOFF_ALT 0.01 diff --git a/ROMFS/px4fmu_common/init.d/airframes/50006_ssrc_bunker_rover b/ROMFS/px4fmu_common/init.d/airframes/50006_ssrc_bunker_rover index c1fe66c5143d..cfce96cc0ab4 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50006_ssrc_bunker_rover +++ b/ROMFS/px4fmu_common/init.d/airframes/50006_ssrc_bunker_rover @@ -2,7 +2,7 @@ # # @name SSRC BUNKER UGV # -# @url https://global.agilex.ai/products/bunker +# @url https://global.agilex.ai/chassis/4 # # @type Rover # @class Rover @@ -15,8 +15,7 @@ # Rover interface param set-default RI_ROVER_TYPE 5 -param set-default RI_MAN_THR_MAX 1.5 -param set-default RI_MIS_THR_MAX 1.0 +param set-default RI_MAN_SPD_SC 1.0 # Battery setting param set-default BAT1_N_CELLS 14 @@ -54,9 +53,13 @@ param set-default GND_THR_MIN 0 param set-default GND_SPEED_P 0.4 param set-default GND_SPEED_I 1 param set-default GND_SPEED_D 0.001 -param set-default GND_SPEED_IMAX 1 -param set-default GND_SPEED_MAX 1 -param set-default GND_SPEED_THR_SC 1 +param set-default GND_SPEED_MAX 1.5 +param set-default GND_SPEED_TRIM 1.5 +param set-default GND_SPEED_THR_SC 1.0 +param set-default GND_VEL_CTRL 1 +param set-default GND_ANG_VEL_CTRL 1 +param set-default GND_ACC_LIMIT 10 +param set-default GND_DEC_LIMIT 50 param set-default MIS_TAKEOFF_ALT 0.01 diff --git a/ROMFS/px4fmu_common/init.d/airframes/50007_ssrc_bunker_mini_rover b/ROMFS/px4fmu_common/init.d/airframes/50007_ssrc_bunker_mini_rover new file mode 100644 index 000000000000..2005a6f961a5 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/airframes/50007_ssrc_bunker_mini_rover @@ -0,0 +1,103 @@ +#!/bin/sh +# +# @name SSRC BUNKER UGV +# +# @url https://global.agilex.ai/chassis/5 +# +# @type Rover +# @class Rover +# +# @board px4_fmu-v2 exclude +# @board bitcraze_crazyflie exclude +# + +. ${R}etc/init.d/rc.rover_defaults + +# Rover interface +param set-default RI_ROVER_TYPE 6 +param set-default RI_MAN_SPD_SC 1.0 + +# Battery setting +param set-default BAT1_N_CELLS 14 +param set-default BAT1_V_EMPTY 3.3 +param set-default BAT1_V_CHARGED 4.2 + +# EKF2 +param set-default EKF2_GBIAS_INIT 0.01 +param set-default EKF2_ANGERR_INIT 0.01 +param set-default EKF2_MAG_TYPE 1 +param set-default EKF2_REQ_SACC 1.0 +param set-default EKF2_REQ_VDRIFT 0.4 +param set-default EKF2_REQ_HDRIFT 0.2 + + +param set-default FW_AIRSPD_MIN 0 +param set-default FW_AIRSPD_TRIM 1 +param set-default FW_AIRSPD_MAX 3 + +param set-default GND_SP_CTRL_MODE 1 +param set-default GND_L1_DIST 5 +param set-default GND_L1_PERIOD 3 +param set-default GND_THR_CRUISE 1 +param set-default GND_THR_MAX 1 + +# Because this is differential drive, it can make a turn with radius 0. +# This corresponds to a turn angle of pi radians. +# If a special case is made for differential-drive, this will need to change. +param set-default GND_MAX_ANG 3.142 +param set-default GND_WHEEL_BASE 0.584 + +# TODO: Set to -1.0, to allow reversing. This will require many changes in the codebase +# to support negative throttle. +param set-default GND_THR_MIN 0 +param set-default GND_SPEED_P 0.4 +param set-default GND_SPEED_I 1 +param set-default GND_SPEED_D 0.001 +param set-default GND_SPEED_MAX 1.5 +param set-default GND_SPEED_TRIM 1.5 +param set-default GND_SPEED_THR_SC 1.0 +param set-default GND_VEL_CTRL 1 +param set-default GND_ANG_VEL_CTRL 1 +param set-default GND_ACC_LIMIT 10 +param set-default GND_DEC_LIMIT 50 + +param set-default MIS_TAKEOFF_ALT 0.01 + +param set-default NAV_ACC_RAD 0.5 # reached when within 0.5m of waypoint + +# Enable Airspeed check circuit breaker because Rovers will have no airspeed sensor +param set-default CBRK_AIRSPD_CHK 162128 + +# Set geometry & output configration. This is just the place holder for rover type. We dont actually use control allocation for scout mini. +param set-default CA_AIRFRAME 6 + +# Disable UAVCAN since rover use rover_interface module instead +param set UAVCAN_ENABLE 0 + + +###### ROVER/DRONE COMMON PARAMS ###### +# Disable internal magnetometer +param set-default CAL_MAG0_PRIO 0 + +# LEDs on TELEMETRY 1 +param set-default SER_TEL1_BAUD 57600 +param set-default MAV_1_CONFIG 101 +param set-default MAV_1_MODE 7 +param set-default MAV_1_RATE 1000 + +# Disable MAV_0 and MAV_2 +param set-default MAV_0_CONFIG 0 +param set-default MAV_2_CONFIG 0 + +# Enable safety switch +param set-default CBRK_IO_SAFETY 0 + +# Enable satellite info by default +param set-default GPS_SAT_INFO 1 + +# Set sticks movement not to switch to RC, we use mode switch for this +param set-default COM_RC_OVERRIDE 0 + +# Set default logfile encryption key indecies +param set-default SDLOG_EXCH_KEY 2 +param set-default SDLOG_KEY 3 diff --git a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt index 524709d081d9..11425887ba24 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt @@ -125,6 +125,7 @@ px4_add_romfs_files( 50003_aion_robotics_r1_rover 50005_ssrc_scout_mini_rover 50006_ssrc_bunker_rover + 50007_ssrc_bunker_mini_rover # [60000, 61000] (Unmanned) Underwater Robots 60000_uuv_generic diff --git a/packaging/Dockerfile.sitl_gzsim b/packaging/Dockerfile.sitl_gzsim new file mode 100644 index 000000000000..f0944e534919 --- /dev/null +++ b/packaging/Dockerfile.sitl_gzsim @@ -0,0 +1,76 @@ +FROM docker.io/ros:humble-ros-base as builder + +# Install git for pulling the base repository +RUN apt update +RUN apt install -y \ + git \ + curl \ + lsb-release \ + gnupg + +RUN curl http://packages.osrfoundation.org/gazebo.key | apt-key add - +RUN sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list' + +# Install build dependencies +RUN apt update +RUN DEBIAN_FRONTEND=noninteractive TZ=Etc/UTC apt install -y \ + libgz-transport12 \ + libgz-transport12-dev \ + astyle \ + build-essential \ + cmake \ + cppcheck \ + file \ + g++ \ + gcc \ + gdb \ + git \ + lcov \ + libfuse2 \ + libxml2-dev \ + libxml2-utils \ + make \ + ninja-build \ + python3 \ + python3-dev \ + python3-pip \ + python3-setuptools \ + python3-wheel \ + rsync \ + shellcheck \ + unzip \ + ros-humble-fastrtps \ + ros-humble-rmw-fastrtps-cpp \ + fastddsgen + +# Checkout the px4 version and build it +RUN git clone https://github.com/tiiuae/px4-firmware +RUN python3 -m pip install -r px4-firmware/Tools/setup/requirements.txt +COPY build_px4_sitl_gzsim.sh ./build.sh +RUN ./build.sh + +# ▲ runtime ──┐ +# └── build ▼ + +FROM docker.io/ros:humble-ros-base + +RUN apt update +RUN apt install -y \ + curl \ + lsb-release \ + gnupg \ + ros-humble-fastrtps \ + ros-humble-rmw-fastrtps-cpp + +RUN curl http://packages.osrfoundation.org/gazebo.key | apt-key add - +RUN sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list' + +RUN apt update +RUN DEBIAN_FRONTEND=noninteractive TZ=Etc/UTC apt install -y libgz-transport12 dnsutils + +WORKDIR /px4_sitl + +COPY --from=builder /px4-firmware/build/px4_sitl_default /px4_sitl +COPY ./entrypoint_sitl_gzsim.sh /entrypoint.sh + +CMD ["/entrypoint.sh"] diff --git a/packaging/build_px4_sitl_gzsim.sh b/packaging/build_px4_sitl_gzsim.sh new file mode 100755 index 000000000000..5ee8050ace18 --- /dev/null +++ b/packaging/build_px4_sitl_gzsim.sh @@ -0,0 +1,7 @@ +#!/bin/bash + +source /opt/ros/humble/setup.sh + +pushd px4-firmware + make px4_sitl_default +popd diff --git a/packaging/entrypoint_sitl_gzsim.sh b/packaging/entrypoint_sitl_gzsim.sh new file mode 100755 index 000000000000..c42bdafe05b1 --- /dev/null +++ b/packaging/entrypoint_sitl_gzsim.sh @@ -0,0 +1,37 @@ +#!/bin/bash +# + +export PATH=/px4_sitl/bin:$PATH + +case $PX4_VEHICLE_TYPE in + mc) + export PX4_SYS_AUTOSTART=4401 + export PX4_GZ_MODEL=holybro-x500 + ;; + rover) + export PX4_SYS_AUTOSTART=50005 + export PX4_GZ_MODEL=scout_mini + ;; + vtol) + export PX4_SYS_AUTOSTART=4004 + export PX4_GZ_MODEL=standard_vtol + ;; + fw) + export PX4_SYS_AUTOSTART=4003 + export PX4_GZ_MODEL=rc_cessna + ;; + *) + echo "ERROR: unknown vehicle type: $PX4_VEHICLE_TYPE" + exit 1 + ;; +esac + +export PX4_GZ_MODEL_NAME=$DRONE_DEVICE_ID +export PX4_GZ_WORLD=${PX4_GZ_WORLD:-default} +export GZ_PARTITION=sim +export GZ_RELAY=$(dig +short gazebo-server) +export GZ_IP=$(hostname -i) + +source /opt/ros/humble/setup.sh + +/px4_sitl/bin/px4 -d -s /px4_sitl/etc/init.d-posix/rcS -w /px4_sitl diff --git a/src/drivers/rover_interface/RoverInterface.cpp b/src/drivers/rover_interface/RoverInterface.cpp index 8d65ea989abd..bfa8d128db09 100644 --- a/src/drivers/rover_interface/RoverInterface.cpp +++ b/src/drivers/rover_interface/RoverInterface.cpp @@ -6,14 +6,12 @@ RoverInterface *RoverInterface::_instance; // CAN interface | default is can0 const char *const RoverInterface::CAN_IFACE = "can0"; -RoverInterface::RoverInterface(uint8_t rover_type, uint32_t bitrate, float manual_throttle_max, - float mission_throttle_max) +RoverInterface::RoverInterface(uint8_t rover_type, uint32_t bitrate, float vehicle_speed_max) : ModuleParams(nullptr), ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::rover_interface), _rover_type(rover_type), _bitrate(bitrate), - _manual_throttle_max(manual_throttle_max), - _mission_throttle_max(mission_throttle_max) + _vehicle_speed_max(vehicle_speed_max) { pthread_mutex_init(&_node_mutex, nullptr); } @@ -45,14 +43,14 @@ RoverInterface::~RoverInterface() } -int RoverInterface::start(uint8_t rover_type, uint32_t bitrate, float manual_throttle_max, float mission_throttle_max) +int RoverInterface::start(uint8_t rover_type, uint32_t bitrate, float vehicle_speed_max) { if (_instance != nullptr) { PX4_ERR("Already started"); return -1; } - _instance = new RoverInterface(rover_type, bitrate, manual_throttle_max, mission_throttle_max); + _instance = new RoverInterface(rover_type, bitrate, vehicle_speed_max); if (_instance == nullptr) { PX4_ERR("Failed to allocate RoverInterface object"); @@ -155,6 +153,20 @@ void RoverInterface::Init() } +void RoverInterface::parameters_update(bool force) +{ + // check for parameter updates + if (_parameter_update_sub.updated() || force) { + // clear update + parameter_update_s pupdate; + _parameter_update_sub.copy(&pupdate); + + // update parameters from storage + updateParams(); + } +} + + void RoverInterface::Run() { pthread_mutex_lock(&_node_mutex); @@ -192,6 +204,8 @@ void RoverInterface::Run() perf_begin(_cycle_perf); perf_count(_interval_perf); + // Update parameters + parameters_update(); // Check for actuator armed command to rover ActuatorArmedUpdate(); @@ -244,7 +258,7 @@ void RoverInterface::VehicleTorqueAndThrustUpdate() } if (do_update) { - auto throttle = (_is_manual_mode ? _manual_throttle_max : _mission_throttle_max) * _throttle_control; + auto throttle = (_is_manual_mode ? _param_man_speed_scale.get() : _vehicle_speed_max) * _throttle_control; auto steering = _yaw_control; _scout->SetMotionCommand(throttle, steering); } @@ -400,21 +414,16 @@ extern "C" __EXPORT int rover_interface_main(int argc, char *argv[]) int32_t can_bitrate = 0; param_get(param_find("RI_CAN_BITRATE"), &can_bitrate); - // Manual control mode max throttle (1m/s to 3m/s) - float manual_throttle_max = 1.0; - param_get(param_find("RI_MAN_THR_MAX"), &manual_throttle_max); - - // Mission control mode max throttle (1m/s to 3m/s) - float mission_throttle_max = 1.0; - param_get(param_find("RI_MIS_THR_MAX"), &mission_throttle_max); + // Vehicle speed max | depending on rover type + float vehicle_speed_max = 0.0f; + param_get(param_find("GND_SPEED_MAX"), &vehicle_speed_max); // Start PX4_INFO("Start Rover Interface to rover type %d at CAN iface %s with bitrate %d bit/s", rover_type, RoverInterface::CAN_IFACE, can_bitrate); return RoverInterface::start(static_cast(rover_type), can_bitrate, - manual_throttle_max, - mission_throttle_max + vehicle_speed_max ); } diff --git a/src/drivers/rover_interface/RoverInterface.hpp b/src/drivers/rover_interface/RoverInterface.hpp index c55a6d4695f1..888b06bba5cb 100644 --- a/src/drivers/rover_interface/RoverInterface.hpp +++ b/src/drivers/rover_interface/RoverInterface.hpp @@ -11,6 +11,8 @@ #include #include #include +#include + #include #include #include @@ -28,7 +30,7 @@ class RoverInterface : public ModuleParams, public px4::ScheduledWorkItem * Base interval, has to be compliant with the rate of the actuator_controls * topic subscription and CAN bus update rate */ - static constexpr uint64_t ScheduleIntervalMs{100_us}; + static constexpr uint64_t ScheduleIntervalMs{10_ms}; static constexpr uint64_t RoverStatusPublishIntervalMs{1000_ms}; @@ -39,10 +41,10 @@ class RoverInterface : public ModuleParams, public px4::ScheduledWorkItem public: static const char *const CAN_IFACE; - RoverInterface(uint8_t rover_type, uint32_t bitrate, float manual_throttle_max, float mission_throttle_max); + RoverInterface(uint8_t rover_type, uint32_t bitrate, float vehicle_speed_max); ~RoverInterface() override; - static int start(uint8_t rover_type, uint32_t bitrate, float manual_throttle_max, float mission_throttle_max); + static int start(uint8_t rover_type, uint32_t bitrate, float vehicle_speed_max); void print_status(); @@ -79,9 +81,7 @@ class RoverInterface : public ModuleParams, public px4::ScheduledWorkItem uint32_t _bitrate; - float _manual_throttle_max; - - float _mission_throttle_max; + float _vehicle_speed_max; float _throttle_control; @@ -94,6 +94,7 @@ class RoverInterface : public ModuleParams, public px4::ScheduledWorkItem scoutsdk::ScoutRobot *_scout{nullptr}; // Subscription + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; uORB::SubscriptionInterval _vehicle_thrust_setpoint_sub{ORB_ID(vehicle_thrust_setpoint), ControlSubIntervalMs}; uORB::SubscriptionInterval _vehicle_torque_setpoint_sub{ORB_ID(vehicle_torque_setpoint), ControlSubIntervalMs}; uORB::Subscription _actuator_armed_sub{ORB_ID(actuator_armed)}; @@ -108,4 +109,13 @@ class RoverInterface : public ModuleParams, public px4::ScheduledWorkItem // Performance counters perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle time")}; perf_counter_t _interval_perf{perf_alloc(PC_INTERVAL, MODULE_NAME": cycle interval")}; + + DEFINE_PARAMETERS( + (ParamFloat) _param_man_speed_scale + ) + + /** + * Update our local parameter cache. + */ + void parameters_update(bool force = false); }; diff --git a/src/drivers/rover_interface/rover_interface_params.c b/src/drivers/rover_interface/rover_interface_params.c index b17b1fa8504f..b8b4f629ef20 100644 --- a/src/drivers/rover_interface/rover_interface_params.c +++ b/src/drivers/rover_interface/rover_interface_params.c @@ -59,24 +59,11 @@ PARAM_DEFINE_INT32(RI_CAN_BITRATE, 500000); /** - * Rover interface manual control throttle max. + * Rover interface manual control speed scale. * - * @unit m/s + * @unit %m/s * @min 1.0 * @max 3.0 - * @reboot_required true - * @group Rover Interface - */ -PARAM_DEFINE_FLOAT(RI_MAN_THR_MAX, 1.0); - - -/** - * Rover interface mission control throttle max. - * - * @unit m/s - * @min 1.0 - * @max 3.0 - * @reboot_required true * @group Rover Interface */ -PARAM_DEFINE_FLOAT(RI_MIS_THR_MAX, 1.0); +PARAM_DEFINE_FLOAT(RI_MAN_SPD_SC, 1.0); diff --git a/src/modules/rover_pos_control/RoverPositionControl.cpp b/src/modules/rover_pos_control/RoverPositionControl.cpp index 24909280e99c..6b0406716aed 100644 --- a/src/modules/rover_pos_control/RoverPositionControl.cpp +++ b/src/modules/rover_pos_control/RoverPositionControl.cpp @@ -204,7 +204,10 @@ RoverPositionControl::control_position(const matrix::Vector2d ¤t_position, bool setpoint = true; if ((_control_mode.flag_control_auto_enabled || - _control_mode.flag_control_offboard_enabled) && pos_sp_triplet.current.valid) { + _control_mode.flag_control_offboard_enabled) && + pos_sp_triplet.current.valid && + PX4_ISFINITE(pos_sp_triplet.current.lat) && + PX4_ISFINITE(pos_sp_triplet.current.lon)) { /* AUTONOMOUS FLIGHT */ _control_mode_current = UGV_POSCTRL_MODE_AUTO; @@ -307,6 +310,9 @@ RoverPositionControl::control_position(const matrix::Vector2d ¤t_position, _prev_wp = curr_wp; } else { + // Other position control mode is not supported. Stop the rover. + _yaw_control = 0.0f; + _throttle_control = 0.0f; _control_mode_current = UGV_POSCTRL_MODE_OTHER; setpoint = false; } @@ -320,20 +326,46 @@ RoverPositionControl::control_velocity(const matrix::Vector3f ¤t_velocity) const Vector3f desired_velocity{_trajectory_setpoint.velocity}; float dt = 0.01; // Using non zero value to a avoid division by zero + if (_control_velocity_last_called > 0) { + dt = hrt_elapsed_time(&_control_velocity_last_called) * 1e-6f; + } + + _control_velocity_last_called = hrt_absolute_time(); + const float mission_throttle = _param_throttle_cruise.get(); const float desired_speed = desired_velocity.norm(); + float desired_angular_vel = PX4_ISFINITE(_trajectory_setpoint.yawspeed) ? _trajectory_setpoint.yawspeed : + desired_velocity(1); - if (desired_speed > 0.01f) { + if (desired_speed > 0.01f || desired_angular_vel > 0.01f) { const Dcmf R_to_body(Quatf(_vehicle_att.q).inversed()); const Vector3f vel = R_to_body * Vector3f(current_velocity(0), current_velocity(1), current_velocity(2)); const float x_vel = vel(0); const float x_acc = _vehicle_acceleration_sub.get().xyz[0]; + float control_throttle = 0.0f; + float speed_error = desired_speed - x_vel; + + if (_param_speed_control_mode.get() == 0) { + // Use PID control + control_throttle = pid_calculate(&_speed_ctrl, desired_speed, x_vel, x_acc, dt); + _throttle_control = math::constrain(control_throttle, 0.0f, mission_throttle); - const float control_throttle = pid_calculate(&_speed_ctrl, desired_speed, x_vel, x_acc, dt); + } else if (_param_speed_control_mode.get() == 1) { + if (_param_ang_vel_control_mode.get() == 1) { + speed_error = desired_velocity(0) - x_vel; + } - //Constrain maximum throttle to mission throttle - _throttle_control = math::constrain(control_throttle, 0.0f, mission_throttle); + // Use acc limited direct control + float max_delta_speed = (speed_error > 0 ? _param_speed_acc_limit.get() : _param_speed_dec_limit.get()) * dt; + // Compute the velocity with delta speed and constrain it to GND_SPEED_TRIM + float command_velocity = math::constrain(x_vel + math::constrain(speed_error, -max_delta_speed, max_delta_speed), + -_param_gndspeed_trim.get(), _param_gndspeed_trim.get()); + // Compute the desired velocity and divide it by max speed to get the throttle control + control_throttle = command_velocity / _param_gndspeed_max.get(); + // Still multiplying it with scaler to have the support for simulation. Real hw has 1.0 scaler as default + _throttle_control = control_throttle; + } Vector3f desired_body_velocity; @@ -345,14 +377,21 @@ RoverPositionControl::control_velocity(const matrix::Vector3f ¤t_velocity) desired_body_velocity = R_to_body * desired_velocity; } - const float desired_theta = atan2f(desired_body_velocity(1), desired_body_velocity(0)); - float control_effort = desired_theta / _param_max_turn_angle.get(); - control_effort = math::constrain(control_effort, -1.0f, 1.0f); - - _yaw_control = control_effort; + if (_param_ang_vel_control_mode.get() == 0) { + // Determine yaw from XY vector + const float desired_theta = atan2f(desired_body_velocity(1), desired_body_velocity(0)); + float control_effort = desired_theta / _param_max_turn_angle.get(); + control_effort = math::constrain(control_effort, -1.0f, 1.0f); + _yaw_control = control_effort; + + } else if (_param_ang_vel_control_mode.get() == 1) { + // Use direct yaw input from velocity setpoint + // Limit it to max anguler velocity + _yaw_control = math::constrain(desired_angular_vel, -_param_max_angular_velocity.get(), + _param_max_angular_velocity.get()); + } } else { - _throttle_control = 0.0f; _yaw_control = 0.0f; } @@ -414,14 +453,16 @@ RoverPositionControl::Run() // Convert Local setpoints to global setpoints if (_control_mode.flag_control_offboard_enabled) { - _trajectory_setpoint_sub.update(&_trajectory_setpoint); - - // local -> global - _global_local_proj_ref.reproject( - _trajectory_setpoint.position[0], _trajectory_setpoint.position[1], - _pos_sp_triplet.current.lat, _pos_sp_triplet.current.lon); - - _pos_sp_triplet.current.valid = true; + //_trajectory_setpoint_sub.update(&_trajectory_setpoint); + if (_trajectory_setpoint_sub.update(&_trajectory_setpoint) && + matrix::Vector3f(_trajectory_setpoint.position).isAllFinite()) { + // local -> global + _global_local_proj_ref.reproject( + _trajectory_setpoint.position[0], _trajectory_setpoint.position[1], + _pos_sp_triplet.current.lat, _pos_sp_triplet.current.lon); + + _pos_sp_triplet.current.valid = true; + } } // update the reset counters in any case diff --git a/src/modules/rover_pos_control/RoverPositionControl.hpp b/src/modules/rover_pos_control/RoverPositionControl.hpp index ee1c65efa03d..ace06ae9d8ba 100644 --- a/src/modules/rover_pos_control/RoverPositionControl.hpp +++ b/src/modules/rover_pos_control/RoverPositionControl.hpp @@ -133,6 +133,7 @@ class RoverPositionControl final : public ModuleBase, publ perf_counter_t _loop_perf; /**< loop performance counter */ hrt_abstime _control_position_last_called{0}; /**, publ (ParamFloat) _param_gndspeed_max, (ParamInt) _param_speed_control_mode, + (ParamInt) _param_vel_control_mode, + (ParamInt) _param_ang_vel_control_mode, (ParamFloat) _param_speed_p, (ParamFloat) _param_speed_i, (ParamFloat) _param_speed_d, @@ -190,7 +193,10 @@ class RoverPositionControl final : public ModuleBase, publ (ParamFloat) _param_throttle_cruise, (ParamFloat) _param_wheel_base, + (ParamFloat) _param_speed_acc_limit, + (ParamFloat) _param_speed_dec_limit, (ParamFloat) _param_max_turn_angle, + (ParamFloat) _param_max_angular_velocity, (ParamFloat) _param_gnd_man_y_max, (ParamFloat) _param_nav_loiter_rad /**< loiter radius for Rover */ ) diff --git a/src/modules/rover_pos_control/rover_pos_control_params.c b/src/modules/rover_pos_control/rover_pos_control_params.c index 6458fb1fea65..7106cc46b09c 100644 --- a/src/modules/rover_pos_control/rover_pos_control_params.c +++ b/src/modules/rover_pos_control/rover_pos_control_params.c @@ -164,6 +164,32 @@ PARAM_DEFINE_FLOAT(GND_THR_MIN, 0.0f); */ PARAM_DEFINE_INT32(GND_SP_CTRL_MODE, 1); +/** + * Control mode for speed + * + * This allows the user to choose between PID control or direct throttle control to work with + * rover_interface + * @min 0 + * @max 1 + * @value 0 PID control + * @value 1 Direct control + * @group Rover Position Control + */ +PARAM_DEFINE_INT32(GND_VEL_CTRL, 0); + +/** + * Control mode for angular velocity + * + * Whether the angular velocity will be done with XY vel command difference, or the angular + * velocity commands are given directly either in yawspeed or _trajectory_setpoint.velocity(1) + * @min 0 + * @max 1 + * @value 0 Difference in XY vel commands + * @value 1 Raw input from controller + * @group Rover Position Control + */ +PARAM_DEFINE_INT32(GND_ANG_VEL_CTRL, 0); + /** * Speed proportional gain * @@ -260,6 +286,42 @@ PARAM_DEFINE_FLOAT(GND_SPEED_TRIM, 3.0f); */ PARAM_DEFINE_FLOAT(GND_SPEED_MAX, 10.0f); +/** + * Velocity control acceleration limit + * + * @unit m/s^2 + * @min 0.01 + * @max 100.0 + * @decimal 2 + * @increment 0.05 + * @group Rover Position Control + */ +PARAM_DEFINE_FLOAT(GND_ACC_LIMIT, 1.0f); + +/** + * Velocity control deceleration limit + * + * @unit m/s^2 + * @min 0.005 + * @max 100.0 + * @decimal 2 + * @increment 0.05 + * @group Rover Position Control + */ +PARAM_DEFINE_FLOAT(GND_DEC_LIMIT, 1.0f); + +/** + * Limit the given angular velocity + * + * @unit rad/s + * @min 0.0 + * @max 3.14159 + * @decimal 3 + * @increment 0.01 + * @group Rover Position Control + */ +PARAM_DEFINE_FLOAT(GND_MAX_ANG_VEL, 0.4f); + /** * Maximum turn angle for Ackerman steering. * diff --git a/src/modules/simulation/gz_bridge/GZBridge.cpp b/src/modules/simulation/gz_bridge/GZBridge.cpp index 5f57ad09f45f..6bfbee43dcdc 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.cpp +++ b/src/modules/simulation/gz_bridge/GZBridge.cpp @@ -45,19 +45,25 @@ #include #include -GZBridge::GZBridge(const char *world, const char *name, const char *model, - const char *type, const char *pose_str) : +GZBridge::GZBridge(const char *world, const char *name, const char *model, const char *pose_str) : ModuleParams(nullptr), ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl), _world_name(world), _model_name(name), _model_sim(model), - _vehicle_type(type), _model_pose(pose_str) { pthread_mutex_init(&_node_mutex, nullptr); updateParams(); + + // get current simulated vehicle airframe type + param_get(param_find("CA_AIRFRAME"), &_airframe); + + // get rover max speed + if (_airframe == 6) { + param_get(param_find("GND_SPEED_MAX"), &_rover_max_speed); + } } GZBridge::~GZBridge() @@ -163,18 +169,6 @@ int GZBridge::init() return PX4_ERROR; } - // output (rover vehicle type) eg /model/$MODEL_NAME/cmd_vel - if (_vehicle_type == "rover") { - std::string cmd_vel_topic = "/model/" + _model_name + "/cmd_vel"; - _cmd_vel_pub = _node.Advertise(cmd_vel_topic); - - if (!_cmd_vel_pub.Valid()) { - PX4_ERR("failed to advertise %s", cmd_vel_topic.c_str()); - return PX4_ERROR; - } - - } - #if 0 // Airspeed: /world/$WORLD/model/$MODEL/link/airspeed_link/sensor/air_speed/air_speed std::string airpressure_topic = "/world/" + _world_name + "/model/" + _model_name + @@ -205,6 +199,17 @@ int GZBridge::init() return PX4_ERROR; } + // output (rover airframe type) eg /model/$MODEL_NAME/cmd_vel + if (_airframe == 6) { + std::string cmd_vel_topic = "/model/" + _model_name + "/cmd_vel"; + _cmd_vel_pub = _node.Advertise(cmd_vel_topic); + + if (!_cmd_vel_pub.Valid()) { + PX4_ERR("failed to advertise %s", cmd_vel_topic.c_str()); + return PX4_ERROR; + } + } + ScheduleNow(); return OK; } @@ -215,7 +220,6 @@ int GZBridge::task_spawn(int argc, char *argv[]) const char *model_name = nullptr; const char *model_pose = nullptr; const char *model_sim = nullptr; - const char *vehicle_type = nullptr; const char *px4_instance = nullptr; std::string model_name_std; @@ -252,11 +256,6 @@ int GZBridge::task_spawn(int argc, char *argv[]) px4_instance = myoptarg; break; - case 'v': - // vehicle type - vehicle_type = myoptarg; - break; - case '?': error_flag = true; break; @@ -280,10 +279,6 @@ int GZBridge::task_spawn(int argc, char *argv[]) model_sim = ""; } - if (!vehicle_type) { - vehicle_type = "mc"; - } - if (!px4_instance) { if (!model_name) { model_name = model_sim; @@ -294,10 +289,9 @@ int GZBridge::task_spawn(int argc, char *argv[]) model_name = model_name_std.c_str(); } - PX4_INFO("world: %s, model name: %s, simulation model: %s, vehicle type: %s", world_name, model_name, model_sim, - vehicle_type); + PX4_INFO("world: %s, model name: %s, simulation model: %s", world_name, model_name, model_sim); - GZBridge *instance = new GZBridge(world_name, model_name, model_sim, vehicle_type, model_pose); + GZBridge *instance = new GZBridge(world_name, model_name, model_sim, model_pose); if (instance) { _object.store(instance); @@ -692,13 +686,15 @@ void GZBridge::odometryCallback(const gz::msgs::OdometryWithCovariance &odometry void GZBridge::updateCmdVel() { bool do_update = false; + float rover_throttle_control = 0.0f; + float rover_yaw_control = 0.0f; // Check torque setppoint update if (_vehicle_torque_setpoint_sub.updated()) { vehicle_torque_setpoint_s vehicle_torque_setpoint_msg; if (_vehicle_torque_setpoint_sub.copy(&vehicle_torque_setpoint_msg)) { - _rover_yaw_control = vehicle_torque_setpoint_msg.xyz[2]; + rover_yaw_control = vehicle_torque_setpoint_msg.xyz[2]; do_update = true; } } @@ -708,19 +704,21 @@ void GZBridge::updateCmdVel() vehicle_thrust_setpoint_s vehicle_thrust_setpoint_msg; if (_vehicle_thrust_setpoint_sub.copy(&vehicle_thrust_setpoint_msg)) { - _rover_throttle_control = vehicle_thrust_setpoint_msg.xyz[0]; + /** + * On physical rover the max speed scale back is only for mission mode + * But here, we simplify the logic and apply the scale back for both + * manual and mission mode + */ + rover_throttle_control = vehicle_thrust_setpoint_msg.xyz[0] * _rover_max_speed; do_update = true; } } if (do_update) { - auto throttle = 1.0f * _rover_throttle_control; - auto steering = _rover_yaw_control; - // publish cmd_vel gz::msgs::Twist cmd_vel_message; - cmd_vel_message.mutable_linear()->set_x(throttle); - cmd_vel_message.mutable_angular()->set_z(steering); + cmd_vel_message.mutable_linear()->set_x(rover_throttle_control); + cmd_vel_message.mutable_angular()->set_z(rover_yaw_control); if (_cmd_vel_pub.Valid()) { _cmd_vel_pub.Publish(cmd_vel_message); @@ -728,7 +726,6 @@ void GZBridge::updateCmdVel() } } - void GZBridge::rotateQuaternion(gz::math::Quaterniond &q_FRD_to_NED, const gz::math::Quaterniond q_FLU_to_ENU) { // FLU (ROS) to FRD (PX4) static rotation @@ -771,8 +768,8 @@ void GZBridge::Run() _mixing_interface_servo.updateParams(); } - // In case of rover vehicle type, publish gz cmd_vel - if (_vehicle_type == "rover") { updateCmdVel(); } + // In case of differential drive rover airframe type, publish gz cmd_vel + if (_airframe == 6) { updateCmdVel(); } ScheduleDelayed(10_ms); diff --git a/src/modules/simulation/gz_bridge/GZBridge.hpp b/src/modules/simulation/gz_bridge/GZBridge.hpp index fad051dc8853..0ed1ca3e4f9c 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.hpp +++ b/src/modules/simulation/gz_bridge/GZBridge.hpp @@ -72,7 +72,7 @@ using namespace time_literals; class GZBridge : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem { public: - GZBridge(const char *world, const char *name, const char *model, const char *type, const char *pose_str); + GZBridge(const char *world, const char *name, const char *model, const char *pose_str); ~GZBridge() override; /** @see ModuleBase */ @@ -97,6 +97,12 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S bool updateClock(const uint64_t tv_sec, const uint64_t tv_nsec); + /** + * In case of rover: listen to vehicle thrust and torque setpoint and + * publish to simulated rover cmd_vel + */ + void updateCmdVel(); + void clockCallback(const gz::msgs::Clock &clock); // void airspeedCallback(const gz::msgs::AirSpeedSensor &air_pressure); @@ -104,7 +110,6 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S void imuCallback(const gz::msgs::IMU &imu); void poseInfoCallback(const gz::msgs::Pose_V &pose); void odometryCallback(const gz::msgs::OdometryWithCovariance &odometry); - void updateCmdVel(); /** * @@ -150,18 +155,18 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S const std::string _world_name; const std::string _model_name; const std::string _model_sim; - const std::string _vehicle_type; const std::string _model_pose; - float _temperature{288.15}; // 15 degrees + int32_t _airframe; - float _rover_throttle_control{0.0f}; + float _rover_max_speed{0.0}; - float _rover_yaw_control{0.0f}; + float _temperature{288.15}; // 15 degrees - gz::transport::Node _node; gz::transport::Node::Publisher _cmd_vel_pub; + gz::transport::Node _node; + DEFINE_PARAMETERS( (ParamFloat) _param_sim_home_lat, (ParamFloat) _param_sim_home_lon, diff --git a/src/modules/simulation/gz_bridge/parameters.c b/src/modules/simulation/gz_bridge/parameters.c index 513c67436cef..8f4a81eec170 100644 --- a/src/modules/simulation/gz_bridge/parameters.c +++ b/src/modules/simulation/gz_bridge/parameters.c @@ -36,10 +36,19 @@ * * @boolean * @reboot_required true - * @group UAVCAN + * @group Simulator */ PARAM_DEFINE_INT32(SIM_GZ_EN, 0); +/** + * Simulator Gazebo run enable + * + * @boolean + * @reboot_required true + * @group Simulator + */ +PARAM_DEFINE_INT32(SIM_GZ_RUN_GZSIM, 1); + /** * simulator origin latitude * diff --git a/src/modules/simulation/sensor_gps_sim/SensorGpsSim.cpp b/src/modules/simulation/sensor_gps_sim/SensorGpsSim.cpp index 1e1b5be22c06..283e171ec37f 100644 --- a/src/modules/simulation/sensor_gps_sim/SensorGpsSim.cpp +++ b/src/modules/simulation/sensor_gps_sim/SensorGpsSim.cpp @@ -114,9 +114,9 @@ void SensorGpsSim::Run() vehicle_global_position_s gpos{}; _vehicle_global_position_sub.copy(&gpos); - double latitude = gpos.lat + math::degrees((double)generate_wgn() * 0.2 / CONSTANTS_RADIUS_OF_EARTH); - double longitude = gpos.lon + math::degrees((double)generate_wgn() * 0.2 / CONSTANTS_RADIUS_OF_EARTH); - float altitude = gpos.alt + (generate_wgn() * 0.5f); + double latitude = gpos.lat + math::degrees((double)generate_wgn() * 0.1 / CONSTANTS_RADIUS_OF_EARTH); + double longitude = gpos.lon + math::degrees((double)generate_wgn() * 0.1 / CONSTANTS_RADIUS_OF_EARTH); + float altitude = gpos.alt + (generate_wgn() * 0.1f); Vector3f gps_vel = Vector3f{lpos.vx, lpos.vy, lpos.vz} + noiseGauss3f(0.06f, 0.077f, 0.158f);