diff --git a/.github/workflows/mavros_mission_tests.yml b/.github/workflows/mavros_mission_tests.yml index 85b4da0d57..c5d50109b6 100644 --- a/.github/workflows/mavros_mission_tests.yml +++ b/.github/workflows/mavros_mission_tests.yml @@ -24,7 +24,6 @@ jobs: matrix: config: - {vehicle: "iris", mission: "MC_mission_box"} - - {vehicle: "rover", mission: "rover_mission_1"} steps: - uses: actions/checkout@v4 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1060_gazebo-classic_rover b/ROMFS/px4fmu_common/init.d-posix/airframes/1060_gazebo-classic_rover deleted file mode 100644 index 920d022f21..0000000000 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1060_gazebo-classic_rover +++ /dev/null @@ -1,33 +0,0 @@ -#!/bin/sh -# -# @name Rover -# - -. ${R}etc/init.d/rc.rover_defaults - -param set-default GND_L1_DIST 5 -param set-default GND_L1_PERIOD 10 -param set-default GND_SP_CTRL_MODE 1 -param set-default GND_SPEED_D 0.001 -param set-default GND_SPEED_I 3 -param set-default GND_SPEED_IMAX 0.125 -param set-default GND_SPEED_P 0.25 -param set-default GND_SPEED_THR_SC 1 -param set-default GND_SPEED_TRIM 4 -param set-default GND_THR_CRUISE 0.3 -param set-default GND_THR_MAX 0.5 -param set-default GND_THR_MIN 0 - -param set-default NAV_ACC_RAD 0.5 -param set-default NAV_LOITER_RAD 2 - -param set-default GND_MAX_ANG 0.6 -param set-default GND_WHEEL_BASE 2 - -param set-default CA_AIRFRAME 5 - -param set-default CA_R_REV 1 -param set-default PWM_MAIN_FUNC1 201 -param set-default PWM_MAIN_FUNC2 201 -param set-default PWM_MAIN_FUNC6 101 -param set-default PWM_MAIN_FUNC7 101 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1061_gazebo-classic_r1_rover b/ROMFS/px4fmu_common/init.d-posix/airframes/1061_gazebo-classic_r1_rover deleted file mode 100644 index 54905d502b..0000000000 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1061_gazebo-classic_r1_rover +++ /dev/null @@ -1,12 +0,0 @@ -#!/bin/sh -# -# @name Aion Robotics R1 Rover -# @type Rover -# @class Rover - -. ${R}etc/init.d/rc.rover_differential_defaults - -param set-default PWM_MAIN_FUNC1 101 -param set-default PWM_MAIN_FUNC2 101 -param set-default PWM_MAIN_FUNC6 102 -param set-default PWM_MAIN_FUNC7 102 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index b5739f711d..e33c888a19 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt @@ -62,8 +62,6 @@ px4_add_romfs_files( 1043_gazebo-classic_standard_vtol_drop 1044_gazebo-classic_plane_lidar 1045_gazebo-classic_quadtailsitter - 1060_gazebo-classic_rover - 1061_gazebo-classic_r1_rover 1062_flightgear_tf-r1 1070_gazebo-classic_boat diff --git a/ROMFS/px4fmu_common/init.d/CMakeLists.txt b/ROMFS/px4fmu_common/init.d/CMakeLists.txt index 7c6f8f4369..88c6be83a9 100644 --- a/ROMFS/px4fmu_common/init.d/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d/CMakeLists.txt @@ -69,15 +69,6 @@ if(CONFIG_MODULES_MC_RATE_CONTROL) ) endif() -if(CONFIG_MODULES_ROVER_POS_CONTROL) - px4_add_romfs_files( - rc.rover_apps - rc.rover_defaults - - rc.boat_defaults # hack - ) -endif() - if(CONFIG_MODULES_ROVER_DIFFERENTIAL) px4_add_romfs_files( rc.rover_differential_apps diff --git a/ROMFS/px4fmu_common/init.d/airframes/59000_generic_ground_vehicle b/ROMFS/px4fmu_common/init.d/airframes/59000_generic_ground_vehicle deleted file mode 100644 index 078ea7859d..0000000000 --- a/ROMFS/px4fmu_common/init.d/airframes/59000_generic_ground_vehicle +++ /dev/null @@ -1,49 +0,0 @@ -#!/bin/sh -# -# @name Generic Ground Vehicle (Deprecated) -# -# @type Rover -# @class Rover -# -# @output Motor1 throttle -# @output Servo1 steering -# -# @maintainer -# -# @board bitcraze_crazyflie exclude -# - -. ${R}etc/init.d/rc.rover_defaults - -param set-default BAT1_N_CELLS 2 - -param set-default EKF2_ANGERR_INIT 0.01 -param set-default EKF2_GBIAS_INIT 0.01 -param set-default EKF2_MAG_TYPE 1 - -param set-default FW_AIRSPD_MAX 3 -param set-default FW_AIRSPD_MIN 0 -param set-default FW_AIRSPD_TRIM 1 - -# Settings for a typical wheelbase 0f 0.3m -param set-default GND_L1_DIST 1 -param set-default GND_L1_PERIOD 5 -param set-default GND_SP_CTRL_MODE 1 -param set-default GND_SPEED_P 0.25 -param set-default GND_SPEED_I 3 -param set-default GND_SPEED_D 0.001 -param set-default GND_SPEED_IMAX 0.125 -param set-default GND_SPEED_THR_SC 1 -param set-default GND_THR_CRUISE 0.3 -param set-default GND_THR_MAX 0.5 -param set-default GND_THR_MIN 0 - -param set-default NAV_ACC_RAD 0.5 - -param set-default CA_AIRFRAME 5 - -param set-default CA_R_REV 1 -param set-default PWM_MAIN_FUNC1 201 -param set-default PWM_MAIN_FUNC2 201 -param set-default PWM_MAIN_FUNC6 101 -param set-default PWM_MAIN_FUNC7 101 diff --git a/ROMFS/px4fmu_common/init.d/airframes/59001_nxpcup_car_dfrobot_gpx b/ROMFS/px4fmu_common/init.d/airframes/59001_nxpcup_car_dfrobot_gpx deleted file mode 100644 index 9f08553d97..0000000000 --- a/ROMFS/px4fmu_common/init.d/airframes/59001_nxpcup_car_dfrobot_gpx +++ /dev/null @@ -1,64 +0,0 @@ -#!/bin/sh -# -# @name NXP Cup car: DF Robot GPX (Deprecated) - -# -# @type Rover -# @class Rover -# -# @board px4_fmu-v2 exclude -# -# @output Motor1 Speed of left wheels -# @output Servo1 Steering servo -# -# @maintainer Katrin Moritz -# -# @board px4_fmu-v2 exclude -# @board bitcraze_crazyflie exclude -# - -. ${R}etc/init.d/rc.rover_defaults - -param set-default BAT1_N_CELLS 2 - -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 FW_AIRSPD_MIN 0 -param set-default FW_AIRSPD_TRIM 1 -param set-default FW_AIRSPD_MAX 3 - -param set-default GND_THR_CRUISE 0.3 -param set-default GND_THR_MAX 0.5 - -# Differential drive acts like ackermann steering with a maximum turn angle of 60 degrees, or pi/3 radians -param set-default GND_MAX_ANG 1.042 -param set-default GND_WHEEL_BASE 0.17 - -# TODO: Set to -1, 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.25 -param set-default GND_SPEED_I 3 -param set-default GND_SPEED_D 0.001 -param set-default GND_SPEED_IMAX 0.125 -param set-default GND_SPEED_THR_SC 1 - -param set-default NAV_ACC_RAD 0.5 - -param set-default CA_AIRFRAME 5 - -param set-default CA_R_REV 1 -param set-default PWM_MAIN_FUNC2 201 -param set-default PWM_MAIN_FUNC3 101 -param set-default PWM_MAIN_FUNC4 101 - -# Provide ESC a constant 1500 us pulse to idle -param set-default PWM_MAIN_DIS2 1500 -param set-default PWM_MAIN_DIS3 1485 -param set-default PWM_MAIN_DIS4 1485 -param set-default PWM_MAIN_FAIL3 1485 -param set-default PWM_MAIN_FAIL4 1485 -param set-default PWM_MAIN_MIN3 970 -param set-default PWM_MAIN_MIN4 970 diff --git a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt index d9142ec1c5..236e3c6209 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt @@ -158,14 +158,6 @@ if(CONFIG_MODULES_ROVER_MECANUM) ) endif() -if(CONFIG_MODULES_ROVER_POS_CONTROL) - px4_add_romfs_files( - # [59000, 59999] Rover position control (deprecated) - 59000_generic_ground_vehicle - 59001_nxpcup_car_dfrobot_gpx - ) -endif() - if(CONFIG_MODULES_UUV_ATT_CONTROL) px4_add_romfs_files( # [60000, 61000] (Unmanned) Underwater Robots diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_apps b/ROMFS/px4fmu_common/init.d/rc.rover_apps deleted file mode 100644 index 2decfbb5ed..0000000000 --- a/ROMFS/px4fmu_common/init.d/rc.rover_apps +++ /dev/null @@ -1,21 +0,0 @@ -#!/bin/sh -# -# Standard apps for unmanned ground vehicles (UGV). -# -# NOTE: Script variables are declared/initialized/unset in the rcS script. -# - -# -# Start Control Allocator -# -control_allocator start - -# -# Start attitude controllers. -# -rover_pos_control start - -# -# Start Land Detector. -# -land_detector start rover diff --git a/ROMFS/px4fmu_common/init.d/rc.rover_defaults b/ROMFS/px4fmu_common/init.d/rc.rover_defaults deleted file mode 100644 index 2e03de6597..0000000000 --- a/ROMFS/px4fmu_common/init.d/rc.rover_defaults +++ /dev/null @@ -1,19 +0,0 @@ -#!/bin/sh -# -# UGV default parameters. -# -# NOTE: Script variables are declared/initialized/unset in the rcS script. -# - -set VEHICLE_TYPE rover - -# MAV_TYPE_GROUND_ROVER 10 -param set-default MAV_TYPE 10 - -param set-default MIS_TAKEOFF_ALT 0.01 - -param set-default NAV_ACC_RAD 2 -param set-default NAV_LOITER_RAD 2 - -# Temporary. -param set-default NAV_FW_ALT_RAD 1000 diff --git a/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board b/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board index bbb20fd252..7b0f4b75d0 100644 --- a/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board +++ b/boards/3dr/ctrl-zero-h7-oem-revg/default.px4board @@ -62,7 +62,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/airmind/mindpx-v2/default.px4board b/boards/airmind/mindpx-v2/default.px4board index 67c4a57dd4..50c6679426 100644 --- a/boards/airmind/mindpx-v2/default.px4board +++ b/boards/airmind/mindpx-v2/default.px4board @@ -67,7 +67,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index 348b531a2b..0a94ac60fb 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -79,7 +79,6 @@ CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y CONFIG_MODULES_VTOL_ATT_CONTROL=y diff --git a/boards/av/x-v1/default.px4board b/boards/av/x-v1/default.px4board index 1ad68a8f71..5777261431 100644 --- a/boards/av/x-v1/default.px4board +++ b/boards/av/x-v1/default.px4board @@ -63,7 +63,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/beaglebone/blue/default.px4board b/boards/beaglebone/blue/default.px4board index 1e7db4fae5..155e2fb7d1 100644 --- a/boards/beaglebone/blue/default.px4board +++ b/boards/beaglebone/blue/default.px4board @@ -51,7 +51,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_BATTERY_SIMULATOR=y CONFIG_MODULES_SIMULATION_SIMULATOR_MAVLINK=y diff --git a/boards/bluerobotics/navigator/default.px4board b/boards/bluerobotics/navigator/default.px4board index 8812f00366..5942504bfd 100644 --- a/boards/bluerobotics/navigator/default.px4board +++ b/boards/bluerobotics/navigator/default.px4board @@ -57,7 +57,6 @@ CONFIG_MODULES_MC_ATT_CONTROL=y CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_VTOL_ATT_CONTROL=y CONFIG_SYSTEMCMDS_BSONDUMP=y CONFIG_SYSTEMCMDS_DYN=y diff --git a/boards/cubepilot/cubeyellow/default.px4board b/boards/cubepilot/cubeyellow/default.px4board index 8d0dc3eee3..28e3bc6f86 100644 --- a/boards/cubepilot/cubeyellow/default.px4board +++ b/boards/cubepilot/cubeyellow/default.px4board @@ -67,7 +67,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/emlid/navio2/default.px4board b/boards/emlid/navio2/default.px4board index 6498bf7820..584ef65634 100644 --- a/boards/emlid/navio2/default.px4board +++ b/boards/emlid/navio2/default.px4board @@ -53,7 +53,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_BATTERY_SIMULATOR=y CONFIG_MODULES_SIMULATION_SIMULATOR_MAVLINK=y diff --git a/boards/hkust/nxt-dual/default.px4board b/boards/hkust/nxt-dual/default.px4board index 97b19358e5..242c36bea0 100644 --- a/boards/hkust/nxt-dual/default.px4board +++ b/boards/hkust/nxt-dual/default.px4board @@ -60,7 +60,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y diff --git a/boards/hkust/nxt-v1/default.px4board b/boards/hkust/nxt-v1/default.px4board index 0690280eea..90ff7f0e1b 100644 --- a/boards/hkust/nxt-v1/default.px4board +++ b/boards/hkust/nxt-v1/default.px4board @@ -62,7 +62,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y diff --git a/boards/holybro/durandal-v1/default.px4board b/boards/holybro/durandal-v1/default.px4board index 627917d186..1e27fa6da8 100644 --- a/boards/holybro/durandal-v1/default.px4board +++ b/boards/holybro/durandal-v1/default.px4board @@ -63,7 +63,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/holybro/kakuteh7/default.px4board b/boards/holybro/kakuteh7/default.px4board index fed11068e6..a7ee05d56d 100644 --- a/boards/holybro/kakuteh7/default.px4board +++ b/boards/holybro/kakuteh7/default.px4board @@ -66,7 +66,6 @@ CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/holybro/kakuteh7mini/default.px4board b/boards/holybro/kakuteh7mini/default.px4board index 06bc5ffe7e..c24c605342 100644 --- a/boards/holybro/kakuteh7mini/default.px4board +++ b/boards/holybro/kakuteh7mini/default.px4board @@ -66,7 +66,6 @@ CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_PWM_OUT_SIM=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/holybro/kakuteh7v2/default.px4board b/boards/holybro/kakuteh7v2/default.px4board index 8821361a69..3135103cb6 100644 --- a/boards/holybro/kakuteh7v2/default.px4board +++ b/boards/holybro/kakuteh7v2/default.px4board @@ -66,7 +66,6 @@ CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/holybro/pix32v5/default.px4board b/boards/holybro/pix32v5/default.px4board index 01c28a922c..566d4dea3a 100644 --- a/boards/holybro/pix32v5/default.px4board +++ b/boards/holybro/pix32v5/default.px4board @@ -71,7 +71,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/modalai/fc-v1/default.px4board b/boards/modalai/fc-v1/default.px4board index 12623c2c87..0f386cc2b3 100644 --- a/boards/modalai/fc-v1/default.px4board +++ b/boards/modalai/fc-v1/default.px4board @@ -70,7 +70,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/modalai/fc-v2/default.px4board b/boards/modalai/fc-v2/default.px4board index 38a9641d33..fb698d437a 100644 --- a/boards/modalai/fc-v2/default.px4board +++ b/boards/modalai/fc-v2/default.px4board @@ -61,7 +61,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y diff --git a/boards/mro/ctrl-zero-classic/default.px4board b/boards/mro/ctrl-zero-classic/default.px4board index 16cac64d3f..a9dc98219a 100644 --- a/boards/mro/ctrl-zero-classic/default.px4board +++ b/boards/mro/ctrl-zero-classic/default.px4board @@ -66,7 +66,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/mro/ctrl-zero-f7-oem/default.px4board b/boards/mro/ctrl-zero-f7-oem/default.px4board index 5d35d0b04f..7dfdd1e8b0 100644 --- a/boards/mro/ctrl-zero-f7-oem/default.px4board +++ b/boards/mro/ctrl-zero-f7-oem/default.px4board @@ -65,7 +65,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/mro/ctrl-zero-f7/default.px4board b/boards/mro/ctrl-zero-f7/default.px4board index 8e33ae6bb9..ee46ef85c8 100644 --- a/boards/mro/ctrl-zero-f7/default.px4board +++ b/boards/mro/ctrl-zero-f7/default.px4board @@ -65,7 +65,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/mro/ctrl-zero-h7-oem/default.px4board b/boards/mro/ctrl-zero-h7-oem/default.px4board index bbb20fd252..7b0f4b75d0 100644 --- a/boards/mro/ctrl-zero-h7-oem/default.px4board +++ b/boards/mro/ctrl-zero-h7-oem/default.px4board @@ -62,7 +62,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/mro/ctrl-zero-h7/default.px4board b/boards/mro/ctrl-zero-h7/default.px4board index d858efba21..9bf253c18a 100644 --- a/boards/mro/ctrl-zero-h7/default.px4board +++ b/boards/mro/ctrl-zero-h7/default.px4board @@ -63,7 +63,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/mro/pixracerpro/default.px4board b/boards/mro/pixracerpro/default.px4board index 77c80f8de4..7dd0b238fe 100644 --- a/boards/mro/pixracerpro/default.px4board +++ b/boards/mro/pixracerpro/default.px4board @@ -63,7 +63,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/mro/x21-777/default.px4board b/boards/mro/x21-777/default.px4board index 8512dd375e..322d80227e 100644 --- a/boards/mro/x21-777/default.px4board +++ b/boards/mro/x21-777/default.px4board @@ -66,7 +66,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y CONFIG_MODULES_UUV_ATT_CONTROL=y diff --git a/boards/mro/x21/default.px4board b/boards/mro/x21/default.px4board index 749c36e211..00d2c84743 100644 --- a/boards/mro/x21/default.px4board +++ b/boards/mro/x21/default.px4board @@ -67,7 +67,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/nxp/fmuk66-e/default.px4board b/boards/nxp/fmuk66-e/default.px4board index 70f4c16968..3adae50a71 100644 --- a/boards/nxp/fmuk66-e/default.px4board +++ b/boards/nxp/fmuk66-e/default.px4board @@ -68,7 +68,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/nxp/fmuk66-v3/default.px4board b/boards/nxp/fmuk66-v3/default.px4board index a8edef6f01..f9143c1b5e 100644 --- a/boards/nxp/fmuk66-v3/default.px4board +++ b/boards/nxp/fmuk66-v3/default.px4board @@ -69,7 +69,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/nxp/mr-canhubk3/fmu.px4board b/boards/nxp/mr-canhubk3/fmu.px4board index a1a3d9ddd1..366fac4e09 100644 --- a/boards/nxp/mr-canhubk3/fmu.px4board +++ b/boards/nxp/mr-canhubk3/fmu.px4board @@ -52,7 +52,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y CONFIG_MODULES_VTOL_ATT_CONTROL=y diff --git a/boards/nxp/mr-canhubk3/sysview.px4board b/boards/nxp/mr-canhubk3/sysview.px4board index a101423cf9..a8f2de4fa2 100644 --- a/boards/nxp/mr-canhubk3/sysview.px4board +++ b/boards/nxp/mr-canhubk3/sysview.px4board @@ -39,7 +39,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y CONFIG_MODULES_VTOL_ATT_CONTROL=y CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y diff --git a/boards/nxp/mr-canhubk3/zenoh.px4board b/boards/nxp/mr-canhubk3/zenoh.px4board index 9bc71357c4..e54b06000d 100644 --- a/boards/nxp/mr-canhubk3/zenoh.px4board +++ b/boards/nxp/mr-canhubk3/zenoh.px4board @@ -43,7 +43,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y CONFIG_MODULES_VTOL_ATT_CONTROL=y CONFIG_MODULES_ZENOH=y diff --git a/boards/nxp/tropic-community/default.px4board b/boards/nxp/tropic-community/default.px4board index f36d388a49..b29d7f4c37 100644 --- a/boards/nxp/tropic-community/default.px4board +++ b/boards/nxp/tropic-community/default.px4board @@ -72,7 +72,6 @@ CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y diff --git a/boards/px4/fmu-v3/default.px4board b/boards/px4/fmu-v3/default.px4board index 386b363aa6..03b74027d2 100644 --- a/boards/px4/fmu-v3/default.px4board +++ b/boards/px4/fmu-v3/default.px4board @@ -71,7 +71,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/px4/fmu-v4/default.px4board b/boards/px4/fmu-v4/default.px4board index 48ecf1b2c2..046a0b5fc4 100644 --- a/boards/px4/fmu-v4/default.px4board +++ b/boards/px4/fmu-v4/default.px4board @@ -72,7 +72,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/px4/fmu-v4pro/default.px4board b/boards/px4/fmu-v4pro/default.px4board index a30e386ea9..bea7aceac8 100644 --- a/boards/px4/fmu-v4pro/default.px4board +++ b/boards/px4/fmu-v4pro/default.px4board @@ -68,7 +68,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/px4/fmu-v5/debug.px4board b/boards/px4/fmu-v5/debug.px4board index 557590ea18..c8d7d1993a 100644 --- a/boards/px4/fmu-v5/debug.px4board +++ b/boards/px4/fmu-v5/debug.px4board @@ -22,7 +22,6 @@ CONFIG_MODULES_ESC_BATTERY=n CONFIG_MODULES_GIMBAL=n CONFIG_MODULES_GYRO_CALIBRATION=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n -CONFIG_MODULES_ROVER_POS_CONTROL=n CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n CONFIG_MODULES_TEMPERATURE_COMPENSATION=n CONFIG_MODULES_UUV_ATT_CONTROL=n diff --git a/boards/px4/fmu-v5/default.px4board b/boards/px4/fmu-v5/default.px4board index e5da7855a7..9a36ff1fe7 100644 --- a/boards/px4/fmu-v5/default.px4board +++ b/boards/px4/fmu-v5/default.px4board @@ -74,7 +74,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/px4/fmu-v5/protected.px4board b/boards/px4/fmu-v5/protected.px4board index 9f8eb32888..481547eddc 100644 --- a/boards/px4/fmu-v5/protected.px4board +++ b/boards/px4/fmu-v5/protected.px4board @@ -19,7 +19,6 @@ CONFIG_MODULES_FW_ATT_CONTROL=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_FW_MODE_MANAGER=n CONFIG_MODULES_FW_LATERAL_LONGITUDINAL_CONTROL=n -CONFIG_MODULES_ROVER_POS_CONTROL=n CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n CONFIG_MODULES_TEMPERATURE_COMPENSATION=n CONFIG_MODULES_UUV_ATT_CONTROL=n diff --git a/boards/px4/fmu-v5/stackcheck.px4board b/boards/px4/fmu-v5/stackcheck.px4board index 8e96a2ff79..eec679f623 100644 --- a/boards/px4/fmu-v5/stackcheck.px4board +++ b/boards/px4/fmu-v5/stackcheck.px4board @@ -36,7 +36,6 @@ CONFIG_MODULES_GIMBAL=n CONFIG_MODULES_GYRO_CALIBRATION=n CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n CONFIG_MODULES_MAG_BIAS_ESTIMATOR=n -CONFIG_MODULES_ROVER_POS_CONTROL=n CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n CONFIG_MODULES_TEMPERATURE_COMPENSATION=n CONFIG_MODULES_UUV_ATT_CONTROL=n diff --git a/boards/px4/fmu-v5/test.px4board b/boards/px4/fmu-v5/test.px4board index ea3fa6bf0b..f6b826cd51 100644 --- a/boards/px4/fmu-v5/test.px4board +++ b/boards/px4/fmu-v5/test.px4board @@ -11,7 +11,6 @@ CONFIG_DRIVERS_PCA9685_PWM_OUT=n CONFIG_DRIVERS_UAVCAN=n CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_ROVER_POS_CONTROL=n CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n CONFIG_BOARD_TESTING=y CONFIG_DRIVERS_TEST_PPM=y diff --git a/boards/px4/fmu-v5/uavcanv0periph.px4board b/boards/px4/fmu-v5/uavcanv0periph.px4board index 7b89c5f0c9..a2b3413545 100644 --- a/boards/px4/fmu-v5/uavcanv0periph.px4board +++ b/boards/px4/fmu-v5/uavcanv0periph.px4board @@ -17,7 +17,6 @@ CONFIG_MODULES_CAMERA_FEEDBACK=n CONFIG_MODULES_ESC_BATTERY=n CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n -CONFIG_MODULES_ROVER_POS_CONTROL=n CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n CONFIG_MODULES_TEMPERATURE_COMPENSATION=n CONFIG_MODULES_UUV_ATT_CONTROL=n diff --git a/boards/px4/fmu-v6c/default.px4board b/boards/px4/fmu-v6c/default.px4board index e3aa477534..c1adacd987 100644 --- a/boards/px4/fmu-v6c/default.px4board +++ b/boards/px4/fmu-v6c/default.px4board @@ -67,7 +67,6 @@ CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/px4/fmu-v6u/default.px4board b/boards/px4/fmu-v6u/default.px4board index e72a584fd8..7402fbd25e 100644 --- a/boards/px4/fmu-v6u/default.px4board +++ b/boards/px4/fmu-v6u/default.px4board @@ -68,7 +68,6 @@ CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y diff --git a/boards/px4/fmu-v6xrt/default.px4board b/boards/px4/fmu-v6xrt/default.px4board index 96cbb0f716..557339844e 100644 --- a/boards/px4/fmu-v6xrt/default.px4board +++ b/boards/px4/fmu-v6xrt/default.px4board @@ -81,7 +81,6 @@ CONFIG_MODULES_NAVIGATOR=y CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000 CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y CONFIG_MODULES_UXRCE_DDS_CLIENT=y diff --git a/boards/px4/raspberrypi/default.px4board b/boards/px4/raspberrypi/default.px4board index 484a66beff..fe61c826e9 100644 --- a/boards/px4/raspberrypi/default.px4board +++ b/boards/px4/raspberrypi/default.px4board @@ -51,7 +51,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_BATTERY_SIMULATOR=y CONFIG_MODULES_SIMULATION_SIMULATOR_MAVLINK=y diff --git a/boards/px4/sitl/default.px4board b/boards/px4/sitl/default.px4board index 28c16f931f..84d22144b4 100644 --- a/boards/px4/sitl/default.px4board +++ b/boards/px4/sitl/default.px4board @@ -49,7 +49,6 @@ CONFIG_MODULES_REPLAY=y CONFIG_MODULES_ROVER_ACKERMANN=y CONFIG_MODULES_ROVER_DIFFERENTIAL=y CONFIG_MODULES_ROVER_MECANUM=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_COMMON_SIMULATION=y CONFIG_MODULES_SIMULATION_GZ_MSGS=y diff --git a/boards/scumaker/pilotpi/default.px4board b/boards/scumaker/pilotpi/default.px4board index d9d35ab25d..7bb44aa427 100644 --- a/boards/scumaker/pilotpi/default.px4board +++ b/boards/scumaker/pilotpi/default.px4board @@ -53,7 +53,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/siyi/n7/default.px4board b/boards/siyi/n7/default.px4board index 3dafcc85a1..0fda7adec4 100644 --- a/boards/siyi/n7/default.px4board +++ b/boards/siyi/n7/default.px4board @@ -57,7 +57,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/sky-drones/smartap-airlink/default.px4board b/boards/sky-drones/smartap-airlink/default.px4board index b2cd40a7ba..8c8afa6080 100644 --- a/boards/sky-drones/smartap-airlink/default.px4board +++ b/boards/sky-drones/smartap-airlink/default.px4board @@ -65,7 +65,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/thepeach/k1/default.px4board b/boards/thepeach/k1/default.px4board index cc519b968d..d542a2c1b0 100644 --- a/boards/thepeach/k1/default.px4board +++ b/boards/thepeach/k1/default.px4board @@ -65,7 +65,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/thepeach/r1/default.px4board b/boards/thepeach/r1/default.px4board index cc519b968d..d542a2c1b0 100644 --- a/boards/thepeach/r1/default.px4board +++ b/boards/thepeach/r1/default.px4board @@ -65,7 +65,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y diff --git a/boards/x-mav/ap-h743v2/default.px4board b/boards/x-mav/ap-h743v2/default.px4board index 33f81262d3..adc930268c 100644 --- a/boards/x-mav/ap-h743v2/default.px4board +++ b/boards/x-mav/ap-h743v2/default.px4board @@ -61,7 +61,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y CONFIG_MODULES_VTOL_ATT_CONTROL=y diff --git a/integrationtests/python_src/px4_it/mavros/missions/rover_mission_1.plan b/integrationtests/python_src/px4_it/mavros/missions/rover_mission_1.plan deleted file mode 100644 index e7c76347fc..0000000000 --- a/integrationtests/python_src/px4_it/mavros/missions/rover_mission_1.plan +++ /dev/null @@ -1,88 +0,0 @@ -{ - "fileType": "Plan", - "geoFence": { - "circles": [ - ], - "polygons": [ - ], - "version": 2 - }, - "groundStation": "QGroundControl", - "mission": { - "cruiseSpeed": 15, - "firmwareType": 12, - "hoverSpeed": 5, - "items": [ - { - "AMSLAltAboveTerrain": 0, - "Altitude": 0, - "AltitudeMode": 1, - "autoContinue": true, - "command": 16, - "doJumpId": 1, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.39773780490375, - 8.54604903179387, - 0 - ], - "type": "SimpleItem" - }, - { - "AMSLAltAboveTerrain": 0, - "Altitude": 0, - "AltitudeMode": 1, - "autoContinue": true, - "command": 16, - "doJumpId": 2, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.397488802748335, - 8.54604396073961, - 0 - ], - "type": "SimpleItem" - }, - { - "AMSLAltAboveTerrain": 0, - "Altitude": 0, - "AltitudeMode": 1, - "autoContinue": true, - "command": 16, - "doJumpId": 3, - "frame": 3, - "params": [ - 0, - 0, - 0, - null, - 47.397475935201946, - 8.545597816497462, - 0 - ], - "type": "SimpleItem" - } - ], - "plannedHomePosition": [ - 47.3977419, - 8.5455944, - 489 - ], - "vehicleType": 10, - "version": 2 - }, - "rallyPoints": { - "points": [ - ], - "version": 2 - }, - "version": 1 -} diff --git a/src/modules/rover_pos_control/CMakeLists.txt b/src/modules/rover_pos_control/CMakeLists.txt deleted file mode 100644 index ee85e3cc39..0000000000 --- a/src/modules/rover_pos_control/CMakeLists.txt +++ /dev/null @@ -1,42 +0,0 @@ -############################################################################ -# -# Copyright (c) 2017 PX4 Development Team. All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions -# are met: -# -# 1. Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# 2. Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in -# the documentation and/or other materials provided with the -# distribution. -# 3. Neither the name PX4 nor the names of its contributors may be -# used to endorse or promote products derived from this software -# without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. -# -############################################################################ -px4_add_module( - MODULE modules__rover_pos_control - MAIN rover_pos_control - SRCS - RoverPositionControl.cpp - RoverPositionControl.hpp - DEPENDS - l1 - PID - ) diff --git a/src/modules/rover_pos_control/Kconfig b/src/modules/rover_pos_control/Kconfig deleted file mode 100644 index 4fc6a11426..0000000000 --- a/src/modules/rover_pos_control/Kconfig +++ /dev/null @@ -1,12 +0,0 @@ -menuconfig MODULES_ROVER_POS_CONTROL - bool "rover_pos_control" - default n - ---help--- - Enable support for rover_pos_control - -menuconfig USER_ROVER_POS_CONTROL - bool "rover_pos_control running as userspace module" - default y - depends on BOARD_PROTECTED && MODULES_ROVER_POS_CONTROL - ---help--- - Put rover_pos_control in userspace memory diff --git a/src/modules/rover_pos_control/RoverPositionControl.cpp b/src/modules/rover_pos_control/RoverPositionControl.cpp deleted file mode 100644 index 119c8c18e8..0000000000 --- a/src/modules/rover_pos_control/RoverPositionControl.cpp +++ /dev/null @@ -1,553 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * - * This module is a modification of the fixed wing module and it is designed for ground rovers. - * It has been developed starting from the fw module, simplified and improved with dedicated items. - * - * All the acknowledgments and credits for the fw wing app are reported in those files. - * - * @author Marco Zorzi - */ - - -#include "RoverPositionControl.hpp" -#include - -using namespace matrix; - -/** - * L1 control app start / stop handling function - * - * @ingroup apps - */ -extern "C" __EXPORT int rover_pos_control_main(int argc, char *argv[]); - -RoverPositionControl::RoverPositionControl() : - ModuleParams(nullptr), - WorkItem(MODULE_NAME, px4::wq_configurations::nav_and_controllers), - /* performance counters */ - _loop_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")) // TODO : do we even need these perf counters -{ -} - -RoverPositionControl::~RoverPositionControl() -{ - perf_free(_loop_perf); -} - -bool -RoverPositionControl::init() -{ - if (!_vehicle_angular_velocity_sub.registerCallback()) { - PX4_ERR("callback registration failed"); - return false; - } - - return true; -} - -void RoverPositionControl::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(); - - _gnd_control.set_l1_damping(_param_l1_damping.get()); - _gnd_control.set_l1_period(_param_l1_period.get()); - - _speed_ctrl.setGains(_param_speed_p.get(), _param_speed_i.get(), _param_speed_d.get()); - _speed_ctrl.setIntegralLimit(_param_speed_imax.get()); - _speed_ctrl.setOutputLimit(_param_gndspeed_max.get()); - } -} - -void -RoverPositionControl::vehicle_control_mode_poll() -{ - if (_control_mode_sub.updated()) { - _control_mode_sub.copy(&_control_mode); - } -} - -void -RoverPositionControl::manual_control_setpoint_poll() -{ - if (_control_mode.flag_control_manual_enabled) { - if (_manual_control_setpoint_sub.copy(&_manual_control_setpoint)) { - float dt = math::constrain(hrt_elapsed_time(&_manual_setpoint_last_called) * 1e-6f, 0.0002f, 0.04f); - - if (!_control_mode.flag_control_climb_rate_enabled && - !_control_mode.flag_control_offboard_enabled) { - - if (_control_mode.flag_control_attitude_enabled) { - // STABILIZED mode generate the attitude setpoint from manual user inputs - float roll_body = 0.0; - float pitch_body = 0.0; - - /* reset yaw setpoint to current position if needed */ - if (_reset_yaw_sp) { - const float vehicle_yaw = Eulerf(Quatf(_vehicle_att.q)).psi(); - _manual_yaw_sp = vehicle_yaw; - _reset_yaw_sp = false; - - } else { - const float yaw_rate = math::radians(_param_gnd_man_y_max.get()); - _att_sp.yaw_sp_move_rate = _manual_control_setpoint.roll * yaw_rate; - _manual_yaw_sp = wrap_pi(_manual_yaw_sp + _att_sp.yaw_sp_move_rate * dt); - } - - float yaw_body = _manual_yaw_sp; - _att_sp.thrust_body[0] = _manual_control_setpoint.throttle; - - const Quatf q(Eulerf(roll_body, pitch_body, yaw_body)); - q.copyTo(_att_sp.q_d); - - _att_sp.timestamp = hrt_absolute_time(); - - - _attitude_sp_pub.publish(_att_sp); - - } else { - // Set heading from the manual roll input channel - _yaw_control = _manual_control_setpoint.roll; // Nominally yaw: _manual_control_setpoint.yaw; - // Set throttle from the manual throttle channel - _throttle_control = _manual_control_setpoint.throttle; - _reset_yaw_sp = true; - } - - } else { - _reset_yaw_sp = true; - } - - _manual_setpoint_last_called = hrt_absolute_time(); - } - } -} - -void -RoverPositionControl::position_setpoint_triplet_poll() -{ - if (_pos_sp_triplet_sub.updated()) { - _pos_sp_triplet_sub.copy(&_pos_sp_triplet); - } -} - -void -RoverPositionControl::attitude_setpoint_poll() -{ - if (_att_sp_sub.updated()) { - _att_sp_sub.copy(&_att_sp); - } -} - -void -RoverPositionControl::vehicle_attitude_poll() -{ - if (_att_sub.updated()) { - _att_sub.copy(&_vehicle_att); - } -} - -bool -RoverPositionControl::control_position(const matrix::Vector2d ¤t_position, - const matrix::Vector3f &ground_speed, const position_setpoint_triplet_s &pos_sp_triplet) -{ - float dt = 0.01; // Using non zero value to a avoid division by zero - - if (_control_position_last_called > 0) { - dt = hrt_elapsed_time(&_control_position_last_called) * 1e-6f; - } - - _control_position_last_called = hrt_absolute_time(); - - bool setpoint = true; - - if ((_control_mode.flag_control_auto_enabled || - _control_mode.flag_control_offboard_enabled) && pos_sp_triplet.current.valid) { - /* AUTONOMOUS FLIGHT */ - - _control_mode_current = UGV_POSCTRL_MODE_AUTO; - - /* current waypoint (the one currently heading for) */ - matrix::Vector2d curr_wp(pos_sp_triplet.current.lat, pos_sp_triplet.current.lon); - - /* previous waypoint */ - matrix::Vector2d prev_wp = curr_wp; - - if (pos_sp_triplet.previous.valid) { - prev_wp(0) = pos_sp_triplet.previous.lat; - prev_wp(1) = pos_sp_triplet.previous.lon; - } - - matrix::Vector2f ground_speed_2d(ground_speed); - - float mission_throttle = _param_throttle_cruise.get(); - - /* Just control the throttle */ - if (_param_speed_control_mode.get() == 1) { - /* control the speed in closed loop */ - - float mission_target_speed = _param_gndspeed_trim.get(); - - if (PX4_ISFINITE(_pos_sp_triplet.current.cruising_speed) && - _pos_sp_triplet.current.cruising_speed > 0.1f) { - mission_target_speed = _pos_sp_triplet.current.cruising_speed; - } - - // Velocity in body frame - const Dcmf R_to_body(Quatf(_vehicle_att.q).inversed()); - const Vector3f vel = R_to_body * Vector3f(ground_speed(0), ground_speed(1), ground_speed(2)); - - // Compute airspeed control out and just scale it as a constant - _speed_ctrl.setSetpoint(mission_target_speed); - mission_throttle = _param_throttle_speed_scaler.get() * _speed_ctrl.update(vel(0), dt); - - // Constrain throttle between min and max - mission_throttle = math::constrain(mission_throttle, _param_throttle_min.get(), _param_throttle_max.get()); - - } else { - /* Just control throttle in open loop */ - if (PX4_ISFINITE(_pos_sp_triplet.current.cruising_throttle) && - _pos_sp_triplet.current.cruising_throttle > 0.01f) { - - mission_throttle = _pos_sp_triplet.current.cruising_throttle; - } - } - - float dist_target = get_distance_to_next_waypoint(_global_pos.lat, _global_pos.lon, - (double)curr_wp(0), (double)curr_wp(1)); // pos_sp_triplet.current.lat, pos_sp_triplet.current.lon); - - switch (_pos_ctrl_state) { - case GOTO_WAYPOINT: { - if (dist_target < _param_nav_loiter_rad.get()) { - _pos_ctrl_state = STOPPING; // We are closer than loiter radius to waypoint, stop. - - } else { - Vector2f curr_pos_local{_local_pos.x, _local_pos.y}; - Vector2f curr_wp_local = _global_local_proj_ref.project(curr_wp(0), curr_wp(1)); - Vector2f prev_wp_local = _global_local_proj_ref.project(prev_wp(0), - prev_wp(1)); - _gnd_control.navigate_waypoints(prev_wp_local, curr_wp_local, curr_pos_local, ground_speed_2d); - - _throttle_control = mission_throttle; - - float desired_r = ground_speed_2d.norm_squared() / math::abs_t(_gnd_control.nav_lateral_acceleration_demand()); - float desired_theta = (0.5f * M_PI_F) - atan2f(desired_r, _param_wheel_base.get()); - float control_effort = (desired_theta / _param_max_turn_angle.get()) * sign( - _gnd_control.nav_lateral_acceleration_demand()); - control_effort = math::constrain(control_effort, -1.0f, 1.0f); - _yaw_control = control_effort; - } - } - break; - - case STOPPING: { - _yaw_control = 0.0f; - _throttle_control = 0.0f; - // Note _prev_wp is different to the local prev_wp which is related to a mission waypoint. - float dist_between_waypoints = get_distance_to_next_waypoint((double)_prev_wp(0), (double)_prev_wp(1), - (double)curr_wp(0), (double)curr_wp(1)); - - if (dist_between_waypoints > 0) { - _pos_ctrl_state = GOTO_WAYPOINT; // A new waypoint has arrived go to it - } - } - break; - - default: - PX4_ERR("Unknown Rover State"); - _pos_ctrl_state = STOPPING; - break; - } - - _prev_wp = curr_wp; - - } else { - _control_mode_current = UGV_POSCTRL_MODE_OTHER; - setpoint = false; - } - - return setpoint; -} - -void -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 - - const float mission_throttle = _param_throttle_cruise.get(); - const float desired_speed = desired_velocity.norm(); - - if (desired_speed > 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)); - - _speed_ctrl.setSetpoint(desired_speed); - const float control_throttle = _speed_ctrl.update(vel(0), dt); - - //Constrain maximum throttle to mission throttle - _throttle_control = math::constrain(control_throttle, 0.0f, mission_throttle); - - Vector3f desired_body_velocity; - - if (_velocity_frame == VelocityFrame::NED) { - desired_body_velocity = desired_velocity; - - } else { - // If the frame of the velocity setpoint is unknown, assume it is in local frame - 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; - - } else { - - _throttle_control = 0.0f; - _yaw_control = 0.0f; - } -} - -void -RoverPositionControl::control_attitude(const vehicle_attitude_s &att, const vehicle_attitude_setpoint_s &att_sp) -{ - // quaternion attitude control law, qe is rotation from q to qd - const Quatf qe = Quatf(att.q).inversed() * Quatf(att_sp.q_d); - const Eulerf euler_sp = qe; - - float control_effort = euler_sp(2) / _param_max_turn_angle.get(); - control_effort = math::constrain(control_effort, -1.0f, 1.0f); - - _yaw_control = control_effort; - - const float control_throttle = att_sp.thrust_body[0]; - - _throttle_control = math::constrain(control_throttle, 0.0f, 1.0f); - -} - -void -RoverPositionControl::Run() -{ - parameters_update(true); - - /* run controller on gyro changes */ - vehicle_angular_velocity_s angular_velocity; - - if (_vehicle_angular_velocity_sub.update(&angular_velocity)) { - - /* check vehicle control mode for changes to publication state */ - vehicle_control_mode_poll(); - attitude_setpoint_poll(); - vehicle_attitude_poll(); - manual_control_setpoint_poll(); - - /* update parameters from storage */ - parameters_update(); - - /* only run controller if position changed */ - if (_local_pos_sub.update(&_local_pos)) { - - /* load local copies */ - _global_pos_sub.update(&_global_pos); - - position_setpoint_triplet_poll(); - - if (!_global_local_proj_ref.isInitialized() - || (_global_local_proj_ref.getProjectionReferenceTimestamp() != _local_pos.ref_timestamp)) { - - _global_local_proj_ref.initReference(_local_pos.ref_lat, _local_pos.ref_lon, - _local_pos.ref_timestamp); - } - - // 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; - } - - // update the reset counters in any case - _pos_reset_counter = _global_pos.lat_lon_reset_counter; - - matrix::Vector3f ground_speed(_local_pos.vx, _local_pos.vy, _local_pos.vz); - matrix::Vector2d current_position(_global_pos.lat, _global_pos.lon); - matrix::Vector3f current_velocity(_local_pos.vx, _local_pos.vy, _local_pos.vz); - - if (!_control_mode.flag_control_manual_enabled && _control_mode.flag_control_position_enabled) { - - if (control_position(current_position, ground_speed, _pos_sp_triplet)) { - - //TODO: check if radius makes sense here - float turn_distance = _param_l1_distance.get(); - - // publish status - position_controller_status_s pos_ctrl_status{}; - - pos_ctrl_status.nav_roll = 0.0f; - pos_ctrl_status.nav_pitch = 0.0f; - pos_ctrl_status.nav_bearing = _gnd_control.nav_bearing(); - - pos_ctrl_status.target_bearing = _gnd_control.target_bearing(); - pos_ctrl_status.xtrack_error = _gnd_control.crosstrack_error(); - - pos_ctrl_status.wp_dist = get_distance_to_next_waypoint(_global_pos.lat, _global_pos.lon, - _pos_sp_triplet.current.lat, _pos_sp_triplet.current.lon); - - pos_ctrl_status.acceptance_radius = turn_distance; - - pos_ctrl_status.timestamp = hrt_absolute_time(); - - _pos_ctrl_status_pub.publish(pos_ctrl_status); - } - - } else if (!_control_mode.flag_control_manual_enabled && _control_mode.flag_control_velocity_enabled) { - _trajectory_setpoint_sub.update(&_trajectory_setpoint); - control_velocity(current_velocity); - } - } - - // Respond to an attitude update and run the attitude controller if enabled - if (_control_mode.flag_control_attitude_enabled - && !_control_mode.flag_control_position_enabled - && !_control_mode.flag_control_velocity_enabled) { - control_attitude(_vehicle_att, _att_sp); - - } - - /* Only publish if any of the proper modes are enabled */ - if (_control_mode.flag_control_velocity_enabled || - _control_mode.flag_control_attitude_enabled || - _control_mode.flag_control_position_enabled || - _control_mode.flag_control_manual_enabled) { - - vehicle_thrust_setpoint_s v_thrust_sp{}; - v_thrust_sp.timestamp = hrt_absolute_time(); - v_thrust_sp.xyz[0] = _throttle_control; - v_thrust_sp.xyz[1] = 0.0f; - v_thrust_sp.xyz[2] = 0.0f; - _vehicle_thrust_setpoint_pub.publish(v_thrust_sp); - - vehicle_torque_setpoint_s v_torque_sp{}; - v_torque_sp.timestamp = hrt_absolute_time(); - v_torque_sp.xyz[0] = 0.f; - v_torque_sp.xyz[1] = 0.f; - v_torque_sp.xyz[2] = _yaw_control; - _vehicle_torque_setpoint_pub.publish(v_torque_sp); - } - } -} - -int RoverPositionControl::task_spawn(int argc, char *argv[]) -{ - RoverPositionControl *instance = new RoverPositionControl(); - - if (instance) { - _object.store(instance); - _task_id = task_id_is_work_queue; - - if (instance->init()) { - return PX4_OK; - } - - } else { - PX4_ERR("alloc failed"); - } - - delete instance; - _object.store(nullptr); - _task_id = -1; - - return PX4_ERROR; -} - -int RoverPositionControl::custom_command(int argc, char *argv[]) -{ - return print_usage("unknown command"); -} - -int RoverPositionControl::print_usage(const char *reason) -{ - if (reason) { - PX4_WARN("%s\n", reason); - } - - PRINT_MODULE_DESCRIPTION( - R"DESCR_STR( -### Description -Controls the position of a ground rover using an L1 controller. - -Publishes `vehicle_thrust_setpoint (only in x) and vehicle_torque_setpoint (only yaw)` messages at IMU_GYRO_RATEMAX. - -### Implementation -Currently, this implementation supports only a few modes: - - * Full manual: Throttle and yaw controls are passed directly through to the actuators - * Auto mission: The rover runs missions - * Loiter: The rover will navigate to within the loiter radius, then stop the motors - -### Examples -CLI usage example: -$ rover_pos_control start -$ rover_pos_control status -$ rover_pos_control stop - -)DESCR_STR"); - - PRINT_MODULE_USAGE_NAME("rover_pos_control", "controller"); - PRINT_MODULE_USAGE_COMMAND("start") - PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); - - return 0; -} - -int rover_pos_control_main(int argc, char *argv[]) -{ - return RoverPositionControl::main(argc, argv); -} diff --git a/src/modules/rover_pos_control/RoverPositionControl.hpp b/src/modules/rover_pos_control/RoverPositionControl.hpp deleted file mode 100644 index d3a26438e2..0000000000 --- a/src/modules/rover_pos_control/RoverPositionControl.hpp +++ /dev/null @@ -1,215 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2017-2021 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * - * This module is a modification of the fixed wing module and it is designed for ground rovers. - * It has been developed starting from the fw module, simplified and improved with dedicated items. - * - * All the ackowledgments and credits for the fw wing app are reported in those files. - * - * @author Marco Zorzi - */ - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -using matrix::Dcmf; - -using namespace time_literals; - -class RoverPositionControl final : public ModuleBase, public ModuleParams, public px4::WorkItem -{ -public: - RoverPositionControl(); - ~RoverPositionControl(); - RoverPositionControl(const RoverPositionControl &) = delete; - RoverPositionControl operator=(const RoverPositionControl &other) = delete; - - /** @see ModuleBase */ - static int task_spawn(int argc, char *argv[]); - - /** @see ModuleBase */ - static int custom_command(int argc, char *argv[]); - - /** @see ModuleBase */ - static int print_usage(const char *reason = nullptr); - - bool init(); - -private: - void Run() override; - - uORB::SubscriptionCallbackWorkItem _vehicle_angular_velocity_sub{this, ORB_ID(vehicle_angular_velocity)}; - - uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; - - uORB::Publication _attitude_sp_pub{ORB_ID(vehicle_attitude_setpoint)}; - uORB::Publication _pos_ctrl_status_pub{ORB_ID(position_controller_status)}; /**< navigation capabilities publication */ - - uORB::Subscription _control_mode_sub{ORB_ID(vehicle_control_mode)}; /**< control mode subscription */ - uORB::Subscription _global_pos_sub{ORB_ID(vehicle_global_position)}; - uORB::Subscription _local_pos_sub{ORB_ID(vehicle_local_position)}; - uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; /**< notification of manual control updates */ - uORB::Subscription _pos_sp_triplet_sub{ORB_ID(position_setpoint_triplet)}; - uORB::Subscription _att_sub{ORB_ID(vehicle_attitude)}; - uORB::Subscription _att_sp_sub{ORB_ID(vehicle_attitude_setpoint)}; - uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; - - manual_control_setpoint_s _manual_control_setpoint{}; /**< r/c channel data */ - position_setpoint_triplet_s _pos_sp_triplet{}; /**< triplet of mission items */ - vehicle_attitude_setpoint_s _att_sp{}; /**< attitude setpoint > */ - vehicle_control_mode_s _control_mode{}; /**< control mode */ - vehicle_global_position_s _global_pos{}; /**< global vehicle position */ - vehicle_local_position_s _local_pos{}; /**< global vehicle position */ - vehicle_attitude_s _vehicle_att{}; - trajectory_setpoint_s _trajectory_setpoint{}; - uORB::Publication _vehicle_thrust_setpoint_pub{ORB_ID(vehicle_thrust_setpoint)}; - uORB::Publication _vehicle_torque_setpoint_pub{ORB_ID(vehicle_torque_setpoint)}; - - perf_counter_t _loop_perf; /**< loop performance counter */ - - hrt_abstime _control_position_last_called{0}; /**) _param_l1_period, - (ParamFloat) _param_l1_damping, - (ParamFloat) _param_l1_distance, - - (ParamFloat) _param_gndspeed_trim, - (ParamFloat) _param_gndspeed_max, - - (ParamInt) _param_speed_control_mode, - (ParamFloat) _param_speed_p, - (ParamFloat) _param_speed_i, - (ParamFloat) _param_speed_d, - (ParamFloat) _param_speed_imax, - (ParamFloat) _param_throttle_speed_scaler, - - (ParamFloat) _param_throttle_min, - (ParamFloat) _param_throttle_max, - (ParamFloat) _param_throttle_cruise, - - (ParamFloat) _param_wheel_base, - (ParamFloat) _param_max_turn_angle, - (ParamFloat) _param_gnd_man_y_max, - (ParamFloat) _param_nav_loiter_rad /**< loiter radius for Rover */ - ) - - /** - * Update our local parameter cache. - */ - void parameters_update(bool force = false); - - void position_setpoint_triplet_poll(); - void attitude_setpoint_poll(); - void vehicle_control_mode_poll(); - void vehicle_attitude_poll(); - void manual_control_setpoint_poll(); - - /** - * Control position. - */ - bool control_position(const matrix::Vector2d &global_pos, const matrix::Vector3f &ground_speed, - const position_setpoint_triplet_s &_pos_sp_triplet); - void control_velocity(const matrix::Vector3f ¤t_velocity); - void control_attitude(const vehicle_attitude_s &att, const vehicle_attitude_setpoint_s &att_sp); - -}; diff --git a/src/modules/rover_pos_control/rover_pos_control_params.c b/src/modules/rover_pos_control/rover_pos_control_params.c deleted file mode 100644 index 020cb43231..0000000000 --- a/src/modules/rover_pos_control/rover_pos_control_params.c +++ /dev/null @@ -1,287 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013-2017 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file rover_pos_control_params.c - * - * Parameters defined by the position control task for ground rovers - * - * This is a modification of the fixed wing params and it is designed for ground rovers. - * It has been developed starting from the fw module, simplified and improved with dedicated items. - * - * All the ackowledgments and credits for the fw wing app are reported in those files. - * - * @author Marco Zorzi - */ - -/* - * Controller parameters, accessible via MAVLink - */ - -/** - * Distance from front axle to rear axle - * - * A value of 0.31 is typical for 1/10 RC cars. - * - * @unit m - * @min 0.0 - * @decimal 3 - * @increment 0.01 - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_FLOAT(GND_WHEEL_BASE, 0.31f); - -/** - * L1 distance - * - * This is the distance at which the next waypoint is activated. This should be set - * to about 2-4x of GND_WHEEL_BASE and not smaller than one meter (due to GPS accuracy). - * - * - * @unit m - * @min 1.0 - * @max 50.0 - * @decimal 1 - * @increment 0.1 - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_FLOAT(GND_L1_DIST, 1.0f); - -/** - * L1 period - * - * This is the L1 distance and defines the tracking - * point ahead of the rover it's following. - * Use values around 2-5m for a 0.3m wheel base. Tuning instructions: Shorten - * slowly during tuning until response is sharp without oscillation. - * - * @unit m - * @min 0.5 - * @max 50.0 - * @decimal 1 - * @increment 0.5 - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_FLOAT(GND_L1_PERIOD, 5.0f); - -/** - * L1 damping - * - * Damping factor for L1 control. - * - * @min 0.6 - * @max 0.9 - * @decimal 2 - * @increment 0.05 - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_FLOAT(GND_L1_DAMPING, 0.75f); - -/** - * Cruise throttle - * - * This is the throttle setting required to achieve the desired cruise speed. - * 10% is ok for a traxxas stampede vxl with ESC set to training mode - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_FLOAT(GND_THR_CRUISE, 0.1f); - -/** - * Throttle limit max - * - * This is the maximum throttle % that can be used by the controller. - * For a Traxxas stampede vxl with the ESC set to training, 30 % is enough - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_FLOAT(GND_THR_MAX, 0.3f); - -/** - * Throttle limit min - * - * This is the minimum throttle % that can be used by the controller. - * Set to 0 for rover - * - * @unit norm - * @min 0.0 - * @max 1.0 - * @decimal 2 - * @increment 0.01 - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_FLOAT(GND_THR_MIN, 0.0f); - -/** - * Control mode for speed - * - * This allows the user to choose between closed loop gps speed or open loop cruise throttle speed - * @min 0 - * @max 1 - * @value 0 open loop control - * @value 1 close the loop with gps speed - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_INT32(GND_SP_CTRL_MODE, 1); - -/** - * Speed proportional gain - * - * This is the proportional gain for the speed closed loop controller - * - * @unit %m/s - * @min 0.005 - * @max 50.0 - * @decimal 3 - * @increment 0.005 - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_FLOAT(GND_SPEED_P, 2.0f); - -/** - * Speed Integral gain - * - * This is the integral gain for the speed closed loop controller - * - * @unit %m/s - * @min 0.00 - * @max 50.0 - * @decimal 3 - * @increment 0.005 - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_FLOAT(GND_SPEED_I, 3.0f); - -/** - * Speed proportional gain - * - * This is the derivative gain for the speed closed loop controller - * - * @unit %m/s - * @min 0.00 - * @max 50.0 - * @decimal 3 - * @increment 0.005 - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_FLOAT(GND_SPEED_D, 0.001f); - -/** - * Speed integral maximum value - * - * This is the maxim value the integral can reach to prevent wind-up. - * - * @unit %m/s - * @min 0.005 - * @max 50.0 - * @decimal 3 - * @increment 0.005 - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_FLOAT(GND_SPEED_IMAX, 1.0f); - -/** - * Speed to throttle scaler - * - * This is a gain to map the speed control output to the throttle linearly. - * - * @unit %m/s - * @min 0.005 - * @max 50.0 - * @decimal 3 - * @increment 0.005 - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_FLOAT(GND_SPEED_THR_SC, 1.0f); - -/** - * Trim ground speed - * - * - * @unit m/s - * @min 0.0 - * @max 40 - * @decimal 1 - * @increment 0.5 - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_FLOAT(GND_SPEED_TRIM, 3.0f); - -/** - * Maximum ground speed - * - * - * @unit m/s - * @min 0.0 - * @max 40 - * @decimal 1 - * @increment 0.5 - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_FLOAT(GND_SPEED_MAX, 10.0f); - -/** - * Maximum turn angle for Ackerman steering. - * - * At a control output of 0, the steering wheels are at 0 radians. - * At a control output of 1, the steering wheels are at GND_MAX_ANG radians. - * - * @unit rad - * @min 0.0 - * @max 3.14159 - * @decimal 3 - * @increment 0.01 - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_FLOAT(GND_MAX_ANG, 0.7854f); - -/** - * Max manual yaw rate - * - * @unit deg/s - * @min 0.0 - * @max 400 - * @decimal 1 - * @group Rover Position Control (Deprecated) - */ -PARAM_DEFINE_FLOAT(GND_MAN_Y_MAX, 150.0f); diff --git a/src/modules/simulation/simulator_mavlink/sitl_targets_gazebo-classic.cmake b/src/modules/simulation/simulator_mavlink/sitl_targets_gazebo-classic.cmake index 258e18d8b2..649f0f99c8 100644 --- a/src/modules/simulation/simulator_mavlink/sitl_targets_gazebo-classic.cmake +++ b/src/modules/simulation/simulator_mavlink/sitl_targets_gazebo-classic.cmake @@ -93,8 +93,6 @@ if(gazebo_FOUND) plane_lidar px4vision quadtailsitter - r1_rover - rover standard_vtol standard_vtol_drop tailsitter