mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 03:49:12 +08:00
Rover: Rewrote gnd_pos_control and removed gnd_att_control (#12239)
This commit is contained in:
committed by
Daniel Agar
parent
3743e6d8fb
commit
2ed00c9cb6
@@ -19,10 +19,6 @@ then
|
|||||||
param set GND_THR_IDLE 0
|
param set GND_THR_IDLE 0
|
||||||
param set GND_THR_MAX 0.5
|
param set GND_THR_MAX 0.5
|
||||||
param set GND_THR_MIN 0
|
param set GND_THR_MIN 0
|
||||||
param set GND_WR_D 1.2
|
|
||||||
param set GND_WR_I 0.9674
|
|
||||||
param set GND_WR_IMAX 0.1
|
|
||||||
param set GND_WR_P 2
|
|
||||||
|
|
||||||
param set MIS_LTRMIN_ALT 0.01
|
param set MIS_LTRMIN_ALT 0.01
|
||||||
param set MIS_TAKEOFF_ALT 0.01
|
param set MIS_TAKEOFF_ALT 0.01
|
||||||
@@ -30,6 +26,10 @@ then
|
|||||||
param set NAV_LOITER_RAD 2
|
param set NAV_LOITER_RAD 2
|
||||||
|
|
||||||
param set CBRK_AIRSPD_CHK 162128
|
param set CBRK_AIRSPD_CHK 162128
|
||||||
|
|
||||||
|
param set GND_MAX_ANG 0.6
|
||||||
|
param set GND_WHEEL_BASE 2.0
|
||||||
|
|
||||||
fi
|
fi
|
||||||
|
|
||||||
set MAV_TYPE 10
|
set MAV_TYPE 10
|
||||||
|
|||||||
@@ -15,7 +15,7 @@
|
|||||||
# @board px4_fmu-v2 exclude
|
# @board px4_fmu-v2 exclude
|
||||||
#
|
#
|
||||||
|
|
||||||
sh /etc/init.d/rc.ugv_defaults
|
sh /etc/init.d/rc.rover_defaults
|
||||||
|
|
||||||
if [ $AUTOCNF = yes ]
|
if [ $AUTOCNF = yes ]
|
||||||
then
|
then
|
||||||
@@ -29,15 +29,19 @@ then
|
|||||||
param set FW_AIRSPD_TRIM 1
|
param set FW_AIRSPD_TRIM 1
|
||||||
param set FW_AIRSPD_MAX 3
|
param set FW_AIRSPD_MAX 3
|
||||||
|
|
||||||
param set GND_WR_P 1
|
|
||||||
param set GND_WR_I 0.9674
|
|
||||||
param set GND_WR_IMAX 0.1
|
|
||||||
param set GND_WR_D 0.1
|
|
||||||
param set GND_SP_CTRL_MODE 1
|
param set GND_SP_CTRL_MODE 1
|
||||||
param set GND_L1_DIST 10
|
param set GND_L1_DIST 5.0
|
||||||
|
param set GND_L1_PERIOD 3.0
|
||||||
param set GND_THR_IDLE 0
|
param set GND_THR_IDLE 0
|
||||||
param set GND_THR_CRUISE 0
|
param set GND_THR_CRUISE 0.7
|
||||||
param set GND_THR_MAX 0.5
|
param set GND_THR_MAX 0.5
|
||||||
|
|
||||||
|
# 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 GND_MAX_ANG 3.142
|
||||||
|
param set GND_WHEEL_BASE 0.3
|
||||||
|
|
||||||
# TODO: Set to -1.0, to allow reversing. This will require many changes in the codebase
|
# TODO: Set to -1.0, to allow reversing. This will require many changes in the codebase
|
||||||
# to support negative throttle.
|
# to support negative throttle.
|
||||||
param set GND_THR_MIN 0.0
|
param set GND_THR_MIN 0.0
|
||||||
@@ -64,7 +68,7 @@ then
|
|||||||
param set CBRK_AIRSPD_CHK 162128
|
param set CBRK_AIRSPD_CHK 162128
|
||||||
fi
|
fi
|
||||||
|
|
||||||
# Configure this as ugv
|
# Configure this as rover
|
||||||
set MAV_TYPE 10
|
set MAV_TYPE 10
|
||||||
|
|
||||||
# Set mixer
|
# Set mixer
|
||||||
|
|||||||
@@ -16,8 +16,7 @@ ekf2 start
|
|||||||
#
|
#
|
||||||
# Start attitude controllers.
|
# Start attitude controllers.
|
||||||
#
|
#
|
||||||
gnd_att_control start
|
rover_pos_control start
|
||||||
gnd_pos_control start
|
|
||||||
|
|
||||||
|
|
||||||
#
|
#
|
||||||
|
|||||||
@@ -37,8 +37,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -58,8 +58,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -72,8 +72,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -66,8 +66,7 @@ px4_add_board(
|
|||||||
ekf2
|
ekf2
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
local_position_estimator
|
local_position_estimator
|
||||||
|
|||||||
@@ -72,8 +72,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -66,8 +66,7 @@ px4_add_board(
|
|||||||
ekf2
|
ekf2
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
local_position_estimator
|
local_position_estimator
|
||||||
|
|||||||
@@ -64,8 +64,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -65,8 +65,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -36,8 +36,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -34,8 +34,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -25,8 +25,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
#fw_att_control
|
#fw_att_control
|
||||||
#fw_pos_control_l1
|
#fw_pos_control_l1
|
||||||
#gnd_att_control
|
#rover_pos_control
|
||||||
#gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -40,8 +40,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -38,8 +38,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -41,8 +41,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
#fw_att_control
|
#fw_att_control
|
||||||
#fw_pos_control_l1
|
#fw_pos_control_l1
|
||||||
#gnd_att_control
|
#rover_pos_control
|
||||||
#gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -44,8 +44,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
#fw_att_control
|
#fw_att_control
|
||||||
#fw_pos_control_l1
|
#fw_pos_control_l1
|
||||||
#gnd_att_control
|
#rover_pos_control
|
||||||
#gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -60,8 +60,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -53,8 +53,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
#fw_att_control
|
#fw_att_control
|
||||||
#fw_pos_control_l1
|
#fw_pos_control_l1
|
||||||
#gnd_att_control
|
#rover_pos_control
|
||||||
#gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -28,8 +28,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
#fw_att_control
|
#fw_att_control
|
||||||
#fw_pos_control_l1
|
#fw_pos_control_l1
|
||||||
#gnd_att_control
|
#rover_pos_control
|
||||||
#gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -73,8 +73,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
#gnd_att_control
|
#rover_pos_control
|
||||||
#gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
#landing_target_estimator
|
#landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -69,8 +69,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
#fw_att_control
|
#fw_att_control
|
||||||
#fw_pos_control_l1
|
#fw_pos_control_l1
|
||||||
#gnd_att_control
|
#rover_pos_control
|
||||||
#gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -42,8 +42,7 @@ px4_add_board(
|
|||||||
dataman
|
dataman
|
||||||
ekf2
|
ekf2
|
||||||
events
|
events
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
load_mon
|
load_mon
|
||||||
logger
|
logger
|
||||||
|
|||||||
@@ -69,8 +69,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
#fw_att_control
|
#fw_att_control
|
||||||
#fw_pos_control_l1
|
#fw_pos_control_l1
|
||||||
#gnd_att_control
|
#rover_pos_control
|
||||||
#gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -72,8 +72,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -71,8 +71,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -71,8 +71,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -56,8 +56,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -58,8 +58,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -56,8 +56,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -70,8 +70,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -69,8 +69,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -70,8 +70,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -53,8 +53,7 @@ px4_add_board(
|
|||||||
dataman
|
dataman
|
||||||
ekf2
|
ekf2
|
||||||
events
|
events
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
load_mon
|
load_mon
|
||||||
logger
|
logger
|
||||||
|
|||||||
@@ -68,8 +68,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -68,8 +68,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -70,8 +70,6 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
@@ -81,6 +79,7 @@ px4_add_board(
|
|||||||
mc_att_control
|
mc_att_control
|
||||||
mc_pos_control
|
mc_pos_control
|
||||||
navigator
|
navigator
|
||||||
|
rover_pos_control
|
||||||
sensors
|
sensors
|
||||||
sih
|
sih
|
||||||
vmount
|
vmount
|
||||||
|
|||||||
@@ -63,13 +63,12 @@ px4_add_board(
|
|||||||
dataman
|
dataman
|
||||||
ekf2
|
ekf2
|
||||||
events
|
events
|
||||||
gnd_att_control
|
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
load_mon
|
load_mon
|
||||||
logger
|
logger
|
||||||
mavlink
|
mavlink
|
||||||
navigator
|
navigator
|
||||||
|
rover_pos_control
|
||||||
sensors
|
sensors
|
||||||
vmount
|
vmount
|
||||||
|
|
||||||
|
|||||||
@@ -70,8 +70,6 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
@@ -82,6 +80,7 @@ px4_add_board(
|
|||||||
mc_pos_control
|
mc_pos_control
|
||||||
micrortps_bridge
|
micrortps_bridge
|
||||||
navigator
|
navigator
|
||||||
|
rover_pos_control
|
||||||
sensors
|
sensors
|
||||||
sih
|
sih
|
||||||
vmount
|
vmount
|
||||||
|
|||||||
@@ -70,8 +70,6 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
@@ -81,6 +79,7 @@ px4_add_board(
|
|||||||
mc_att_control
|
mc_att_control
|
||||||
mc_pos_control
|
mc_pos_control
|
||||||
navigator
|
navigator
|
||||||
|
rover_pos_control
|
||||||
sensors
|
sensors
|
||||||
sih
|
sih
|
||||||
vmount
|
vmount
|
||||||
|
|||||||
@@ -33,8 +33,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -31,8 +31,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -30,8 +30,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -30,8 +30,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -30,8 +30,7 @@ px4_add_board(
|
|||||||
events
|
events
|
||||||
fw_att_control
|
fw_att_control
|
||||||
fw_pos_control_l1
|
fw_pos_control_l1
|
||||||
gnd_att_control
|
rover_pos_control
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
land_detector
|
||||||
landing_target_estimator
|
landing_target_estimator
|
||||||
load_mon
|
load_mon
|
||||||
|
|||||||
@@ -1,40 +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__gnd_att_control
|
|
||||||
MAIN gnd_att_control
|
|
||||||
STACK_MAIN 1200
|
|
||||||
COMPILE_FLAGS
|
|
||||||
SRCS
|
|
||||||
GroundRoverAttitudeControl.cpp
|
|
||||||
)
|
|
||||||
@@ -1,439 +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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/**
|
|
||||||
*
|
|
||||||
* 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 <mzorzi@student.ethz.ch>
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include "GroundRoverAttitudeControl.hpp"
|
|
||||||
|
|
||||||
/**
|
|
||||||
* GroundRover attitude control app start / stop handling function
|
|
||||||
*
|
|
||||||
* @ingroup apps
|
|
||||||
*/
|
|
||||||
extern "C" __EXPORT int gnd_att_control_main(int argc, char *argv[]);
|
|
||||||
|
|
||||||
namespace att_gnd_control
|
|
||||||
{
|
|
||||||
GroundRoverAttitudeControl *g_control = nullptr;
|
|
||||||
}
|
|
||||||
|
|
||||||
GroundRoverAttitudeControl::GroundRoverAttitudeControl() :
|
|
||||||
/* performance counters */
|
|
||||||
_loop_perf(perf_alloc(PC_ELAPSED, "gnda_dt")),
|
|
||||||
|
|
||||||
_nonfinite_input_perf(perf_alloc(PC_COUNT, "gnda_nani")),
|
|
||||||
_nonfinite_output_perf(perf_alloc(PC_COUNT, "gnda_nano"))
|
|
||||||
{
|
|
||||||
_parameter_handles.w_p = param_find("GND_WR_P");
|
|
||||||
_parameter_handles.w_i = param_find("GND_WR_I");
|
|
||||||
_parameter_handles.w_d = param_find("GND_WR_D");
|
|
||||||
_parameter_handles.w_imax = param_find("GND_WR_IMAX");
|
|
||||||
|
|
||||||
_parameter_handles.trim_yaw = param_find("TRIM_YAW");
|
|
||||||
|
|
||||||
_parameter_handles.man_yaw_scale = param_find("GND_MAN_Y_SC");
|
|
||||||
|
|
||||||
_parameter_handles.bat_scale_en = param_find("GND_BAT_SCALE_EN");
|
|
||||||
|
|
||||||
/* fetch initial parameter values */
|
|
||||||
parameters_update();
|
|
||||||
}
|
|
||||||
|
|
||||||
GroundRoverAttitudeControl::~GroundRoverAttitudeControl()
|
|
||||||
{
|
|
||||||
if (_control_task != -1) {
|
|
||||||
|
|
||||||
/* task wakes up every 100ms or so at the longest */
|
|
||||||
_task_should_exit = true;
|
|
||||||
|
|
||||||
/* wait for a second for the task to quit at our request */
|
|
||||||
unsigned i = 0;
|
|
||||||
|
|
||||||
do {
|
|
||||||
/* wait 20ms */
|
|
||||||
px4_usleep(20000);
|
|
||||||
|
|
||||||
/* if we have given up, kill it */
|
|
||||||
if (++i > 50) {
|
|
||||||
px4_task_delete(_control_task);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
} while (_control_task != -1);
|
|
||||||
}
|
|
||||||
|
|
||||||
perf_free(_loop_perf);
|
|
||||||
perf_free(_nonfinite_input_perf);
|
|
||||||
perf_free(_nonfinite_output_perf);
|
|
||||||
|
|
||||||
att_gnd_control::g_control = nullptr;
|
|
||||||
}
|
|
||||||
|
|
||||||
void
|
|
||||||
GroundRoverAttitudeControl::parameters_update()
|
|
||||||
{
|
|
||||||
param_get(_parameter_handles.w_p, &(_parameters.w_p));
|
|
||||||
param_get(_parameter_handles.w_i, &(_parameters.w_i));
|
|
||||||
param_get(_parameter_handles.w_d, &(_parameters.w_d));
|
|
||||||
param_get(_parameter_handles.w_imax, &(_parameters.w_imax));
|
|
||||||
|
|
||||||
param_get(_parameter_handles.trim_yaw, &(_parameters.trim_yaw));
|
|
||||||
param_get(_parameter_handles.man_yaw_scale, &(_parameters.man_yaw_scale));
|
|
||||||
|
|
||||||
param_get(_parameter_handles.bat_scale_en, &_parameters.bat_scale_en);
|
|
||||||
|
|
||||||
/* Steering pid parameters*/
|
|
||||||
pid_init(&_steering_ctrl, PID_MODE_DERIVATIV_SET, 0.01f);
|
|
||||||
pid_set_parameters(&_steering_ctrl,
|
|
||||||
_parameters.w_p,
|
|
||||||
_parameters.w_i,
|
|
||||||
_parameters.w_d,
|
|
||||||
_parameters.w_imax,
|
|
||||||
1.0f);
|
|
||||||
}
|
|
||||||
|
|
||||||
void
|
|
||||||
GroundRoverAttitudeControl::vehicle_control_mode_poll()
|
|
||||||
{
|
|
||||||
bool updated = false;
|
|
||||||
orb_check(_vcontrol_mode_sub, &updated);
|
|
||||||
|
|
||||||
if (updated) {
|
|
||||||
orb_copy(ORB_ID(vehicle_control_mode), _vcontrol_mode_sub, &_vcontrol_mode);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void
|
|
||||||
GroundRoverAttitudeControl::manual_control_setpoint_poll()
|
|
||||||
{
|
|
||||||
bool updated = false;
|
|
||||||
orb_check(_manual_sub, &updated);
|
|
||||||
|
|
||||||
if (updated) {
|
|
||||||
orb_copy(ORB_ID(manual_control_setpoint), _manual_sub, &_manual);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void
|
|
||||||
GroundRoverAttitudeControl::vehicle_attitude_setpoint_poll()
|
|
||||||
{
|
|
||||||
bool updated = false;
|
|
||||||
orb_check(_att_sp_sub, &updated);
|
|
||||||
|
|
||||||
if (updated) {
|
|
||||||
orb_copy(ORB_ID(vehicle_attitude_setpoint), _att_sp_sub, &_att_sp);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void
|
|
||||||
GroundRoverAttitudeControl::battery_status_poll()
|
|
||||||
{
|
|
||||||
/* check if there is a new message */
|
|
||||||
bool updated;
|
|
||||||
orb_check(_battery_status_sub, &updated);
|
|
||||||
|
|
||||||
if (updated) {
|
|
||||||
orb_copy(ORB_ID(battery_status), _battery_status_sub, &_battery_status);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
int
|
|
||||||
GroundRoverAttitudeControl::task_main_trampoline(int argc, char *argv[])
|
|
||||||
{
|
|
||||||
att_gnd_control::g_control->task_main();
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
void
|
|
||||||
GroundRoverAttitudeControl::task_main()
|
|
||||||
{
|
|
||||||
_att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
|
|
||||||
_att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
|
|
||||||
_vcontrol_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
|
|
||||||
_params_sub = orb_subscribe(ORB_ID(parameter_update));
|
|
||||||
_manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
|
|
||||||
_battery_status_sub = orb_subscribe(ORB_ID(battery_status));
|
|
||||||
|
|
||||||
parameters_update();
|
|
||||||
|
|
||||||
/* get an initial update for all sensor and status data */
|
|
||||||
vehicle_attitude_setpoint_poll();
|
|
||||||
vehicle_control_mode_poll();
|
|
||||||
manual_control_setpoint_poll();
|
|
||||||
battery_status_poll();
|
|
||||||
|
|
||||||
/* wakeup source */
|
|
||||||
px4_pollfd_struct_t fds[2];
|
|
||||||
|
|
||||||
/* Setup of loop */
|
|
||||||
fds[0].fd = _params_sub;
|
|
||||||
fds[0].events = POLLIN;
|
|
||||||
fds[1].fd = _att_sub;
|
|
||||||
fds[1].events = POLLIN;
|
|
||||||
|
|
||||||
_task_running = true;
|
|
||||||
|
|
||||||
while (!_task_should_exit) {
|
|
||||||
static int loop_counter = 0;
|
|
||||||
|
|
||||||
/* wait for up to 500ms for data */
|
|
||||||
int pret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
|
|
||||||
|
|
||||||
/* timed out - periodic check for _task_should_exit, etc. */
|
|
||||||
if (pret == 0) {
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* this is undesirable but not much we can do - might want to flag unhappy status */
|
|
||||||
if (pret < 0) {
|
|
||||||
PX4_ERR("poll error %d, %d", pret, errno);
|
|
||||||
continue;
|
|
||||||
}
|
|
||||||
|
|
||||||
perf_begin(_loop_perf);
|
|
||||||
|
|
||||||
/* only update parameters if they changed */
|
|
||||||
if (fds[0].revents & POLLIN) {
|
|
||||||
/* read from param to clear updated flag */
|
|
||||||
struct parameter_update_s update;
|
|
||||||
orb_copy(ORB_ID(parameter_update), _params_sub, &update);
|
|
||||||
|
|
||||||
/* update parameters from storage */
|
|
||||||
parameters_update();
|
|
||||||
}
|
|
||||||
|
|
||||||
/* only run controller if attitude changed */
|
|
||||||
if (fds[1].revents & POLLIN) {
|
|
||||||
static uint64_t last_run = 0;
|
|
||||||
float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
|
|
||||||
last_run = hrt_absolute_time();
|
|
||||||
|
|
||||||
/* guard against too large deltaT's */
|
|
||||||
if (deltaT > 1.0f ||
|
|
||||||
fabsf(deltaT) < 0.00001f ||
|
|
||||||
!PX4_ISFINITE(deltaT)) {
|
|
||||||
deltaT = 0.01f;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* load local copies */
|
|
||||||
orb_copy(ORB_ID(vehicle_attitude), _att_sub, &_att);
|
|
||||||
|
|
||||||
vehicle_attitude_setpoint_poll();
|
|
||||||
vehicle_control_mode_poll();
|
|
||||||
manual_control_setpoint_poll();
|
|
||||||
battery_status_poll();
|
|
||||||
|
|
||||||
/* decide if in stabilized or full manual control */
|
|
||||||
if (_vcontrol_mode.flag_control_rates_enabled) {
|
|
||||||
/* Run attitude controllers */
|
|
||||||
if (_vcontrol_mode.flag_control_attitude_enabled) {
|
|
||||||
|
|
||||||
Eulerf euler_angles(matrix::Quatf(_att.q));
|
|
||||||
|
|
||||||
/* Calculate the control output for the steering as yaw */
|
|
||||||
float yaw_u = pid_calculate(&_steering_ctrl, _att_sp.yaw_body, euler_angles.psi(), _att.yawspeed, deltaT);
|
|
||||||
|
|
||||||
float angle_diff = 0.0f;
|
|
||||||
|
|
||||||
if (_att_sp.yaw_body * euler_angles.psi() < 0.0f) {
|
|
||||||
if (_att_sp.yaw_body < 0.0f) {
|
|
||||||
angle_diff = euler_angles.psi() - _att_sp.yaw_body ;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
angle_diff = _att_sp.yaw_body - euler_angles.psi();
|
|
||||||
}
|
|
||||||
|
|
||||||
// a switch might have happened
|
|
||||||
if ((double)angle_diff > M_PI) {
|
|
||||||
yaw_u = -yaw_u;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
math::constrain(yaw_u, -1.0f, 1.0f);
|
|
||||||
|
|
||||||
if (PX4_ISFINITE(yaw_u)) {
|
|
||||||
_actuators.control[actuator_controls_s::INDEX_YAW] = yaw_u + _parameters.trim_yaw;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
_actuators.control[actuator_controls_s::INDEX_YAW] = _parameters.trim_yaw;
|
|
||||||
|
|
||||||
perf_count(_nonfinite_output_perf);
|
|
||||||
|
|
||||||
if (_debug && loop_counter % 10 == 0) {
|
|
||||||
PX4_INFO("yaw_u %.4f", (double)yaw_u);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/* throttle passed through if it is finite and if no engine failure was detected */
|
|
||||||
_actuators.control[actuator_controls_s::INDEX_THROTTLE] = _att_sp.thrust_body[0];
|
|
||||||
|
|
||||||
/* scale effort by battery status */
|
|
||||||
if (_parameters.bat_scale_en && _battery_status.scale > 0.0f &&
|
|
||||||
_actuators.control[actuator_controls_s::INDEX_THROTTLE] > 0.1f) {
|
|
||||||
|
|
||||||
_actuators.control[actuator_controls_s::INDEX_THROTTLE] *= _battery_status.scale;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
} else {
|
|
||||||
/* manual/direct control */
|
|
||||||
_actuators.control[actuator_controls_s::INDEX_ROLL] = _manual.y;
|
|
||||||
_actuators.control[actuator_controls_s::INDEX_PITCH] = -_manual.x;
|
|
||||||
_actuators.control[actuator_controls_s::INDEX_YAW] = _manual.r * _parameters.man_yaw_scale + _parameters.trim_yaw;
|
|
||||||
_actuators.control[actuator_controls_s::INDEX_THROTTLE] = _manual.z;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* lazily publish the setpoint only once available */
|
|
||||||
_actuators.timestamp = hrt_absolute_time();
|
|
||||||
_actuators.timestamp_sample = _att.timestamp;
|
|
||||||
|
|
||||||
/* Only publish if any of the proper modes are enabled */
|
|
||||||
if (_vcontrol_mode.flag_control_attitude_enabled ||
|
|
||||||
_vcontrol_mode.flag_control_manual_enabled) {
|
|
||||||
|
|
||||||
/* publish the actuator controls */
|
|
||||||
if (_actuators_0_pub != nullptr) {
|
|
||||||
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, _actuators_0_pub, &_actuators);
|
|
||||||
|
|
||||||
} else {
|
|
||||||
_actuators_0_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &_actuators);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
loop_counter++;
|
|
||||||
perf_end(_loop_perf);
|
|
||||||
}
|
|
||||||
|
|
||||||
PX4_INFO("exiting.");
|
|
||||||
|
|
||||||
_control_task = -1;
|
|
||||||
_task_running = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
int
|
|
||||||
GroundRoverAttitudeControl::start()
|
|
||||||
{
|
|
||||||
/* start the task */
|
|
||||||
_control_task = px4_task_spawn_cmd("gnd_att_control",
|
|
||||||
SCHED_DEFAULT,
|
|
||||||
SCHED_PRIORITY_MAX - 5,
|
|
||||||
1500,
|
|
||||||
(px4_main_t)&GroundRoverAttitudeControl::task_main_trampoline,
|
|
||||||
nullptr);
|
|
||||||
|
|
||||||
if (_control_task < 0) {
|
|
||||||
PX4_ERR("task start failed");
|
|
||||||
return -errno;
|
|
||||||
}
|
|
||||||
|
|
||||||
return PX4_OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
int gnd_att_control_main(int argc, char *argv[])
|
|
||||||
{
|
|
||||||
if (argc < 2) {
|
|
||||||
PX4_INFO("usage: gnd_att_control {start|stop|status}");
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "start")) {
|
|
||||||
|
|
||||||
if (att_gnd_control::g_control != nullptr) {
|
|
||||||
PX4_WARN("already running");
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
att_gnd_control::g_control = new GroundRoverAttitudeControl;
|
|
||||||
|
|
||||||
if (att_gnd_control::g_control == nullptr) {
|
|
||||||
PX4_ERR("alloc failed");
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (PX4_OK != att_gnd_control::g_control->start()) {
|
|
||||||
delete att_gnd_control::g_control;
|
|
||||||
att_gnd_control::g_control = nullptr;
|
|
||||||
PX4_ERR("start failed");
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* check if the waiting is necessary at all */
|
|
||||||
if (att_gnd_control::g_control == nullptr || !att_gnd_control::g_control->task_running()) {
|
|
||||||
|
|
||||||
/* avoid memory fragmentation by not exiting start handler until the task has fully started */
|
|
||||||
while (att_gnd_control::g_control == nullptr || !att_gnd_control::g_control->task_running()) {
|
|
||||||
px4_usleep(50000);
|
|
||||||
printf(".");
|
|
||||||
fflush(stdout);
|
|
||||||
}
|
|
||||||
|
|
||||||
printf("\n");
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "stop")) {
|
|
||||||
if (att_gnd_control::g_control == nullptr) {
|
|
||||||
PX4_WARN("not running");
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
delete att_gnd_control::g_control;
|
|
||||||
att_gnd_control::g_control = nullptr;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!strcmp(argv[1], "status")) {
|
|
||||||
if (att_gnd_control::g_control) {
|
|
||||||
PX4_INFO("running");
|
|
||||||
return 0;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
PX4_INFO("not running");
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
PX4_WARN("unrecognized command");
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
@@ -1,143 +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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/**
|
|
||||||
*
|
|
||||||
* 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 <mzorzi@student.ethz.ch>
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <px4_config.h>
|
|
||||||
#include <px4_defines.h>
|
|
||||||
#include <px4_tasks.h>
|
|
||||||
#include <px4_posix.h>
|
|
||||||
|
|
||||||
#include <drivers/drv_hrt.h>
|
|
||||||
#include <mathlib/mathlib.h>
|
|
||||||
#include <matrix/math.hpp>
|
|
||||||
#include <parameters/param.h>
|
|
||||||
#include <pid/pid.h>
|
|
||||||
#include <perf/perf_counter.h>
|
|
||||||
#include <uORB/topics/actuator_controls.h>
|
|
||||||
#include <uORB/topics/battery_status.h>
|
|
||||||
#include <uORB/topics/manual_control_setpoint.h>
|
|
||||||
#include <uORB/topics/parameter_update.h>
|
|
||||||
#include <uORB/topics/vehicle_attitude.h>
|
|
||||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
|
||||||
#include <uORB/topics/vehicle_control_mode.h>
|
|
||||||
#include <uORB/topics/vehicle_rates_setpoint.h>
|
|
||||||
#include <uORB/uORB.h>
|
|
||||||
|
|
||||||
using matrix::Eulerf;
|
|
||||||
using matrix::Quatf;
|
|
||||||
|
|
||||||
class GroundRoverAttitudeControl
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
GroundRoverAttitudeControl();
|
|
||||||
~GroundRoverAttitudeControl();
|
|
||||||
|
|
||||||
int start();
|
|
||||||
bool task_running() { return _task_running; }
|
|
||||||
|
|
||||||
private:
|
|
||||||
|
|
||||||
bool _task_should_exit{false}; /**< if true, attitude control task should exit */
|
|
||||||
bool _task_running{false}; /**< if true, task is running in its mainloop */
|
|
||||||
int _control_task{-1}; /**< task handle */
|
|
||||||
|
|
||||||
int _att_sp_sub{-1}; /**< vehicle attitude setpoint */
|
|
||||||
int _battery_status_sub{-1}; /**< battery status subscription */
|
|
||||||
int _att_sub{-1}; /**< control state subscription */
|
|
||||||
int _manual_sub{-1}; /**< notification of manual control updates */
|
|
||||||
int _params_sub{-1}; /**< notification of parameter updates */
|
|
||||||
int _vcontrol_mode_sub{-1}; /**< vehicle status subscription */
|
|
||||||
|
|
||||||
orb_advert_t _actuators_0_pub{nullptr}; /**< actuator control group 0 setpoint */
|
|
||||||
|
|
||||||
actuator_controls_s _actuators {}; /**< actuator control inputs */
|
|
||||||
battery_status_s _battery_status {}; /**< battery status */
|
|
||||||
manual_control_setpoint_s _manual {}; /**< r/c channel data */
|
|
||||||
vehicle_attitude_s _att {}; /**< control state */
|
|
||||||
vehicle_attitude_setpoint_s _att_sp {}; /**< vehicle attitude setpoint */
|
|
||||||
vehicle_control_mode_s _vcontrol_mode {}; /**< vehicle control mode */
|
|
||||||
|
|
||||||
perf_counter_t _loop_perf; /**< loop performance counter */
|
|
||||||
perf_counter_t _nonfinite_input_perf; /**< performance counter for non finite input */
|
|
||||||
perf_counter_t _nonfinite_output_perf; /**< performance counter for non finite output */
|
|
||||||
|
|
||||||
bool _debug{false}; /**< if set to true, print debug output */
|
|
||||||
|
|
||||||
struct {
|
|
||||||
float w_p; /**< Proportional gain of the steering controller */
|
|
||||||
float w_i; /**< Integral gain of the steering controller */
|
|
||||||
float w_d; /**< Derivative of the steering controller */
|
|
||||||
float w_imax; /**< maximum integrator level of the steering controller */
|
|
||||||
|
|
||||||
float trim_yaw;
|
|
||||||
float man_yaw_scale; /**< scale factor applied to yaw actuator control in pure manual mode */
|
|
||||||
|
|
||||||
int32_t bat_scale_en; /**< Battery scaling enabled */
|
|
||||||
|
|
||||||
} _parameters{}; /**< local copies of interesting parameters */
|
|
||||||
|
|
||||||
struct {
|
|
||||||
param_t w_p;
|
|
||||||
param_t w_i;
|
|
||||||
param_t w_d;
|
|
||||||
param_t w_imax;
|
|
||||||
|
|
||||||
param_t trim_yaw;
|
|
||||||
param_t man_yaw_scale;
|
|
||||||
|
|
||||||
param_t bat_scale_en;
|
|
||||||
|
|
||||||
} _parameter_handles{}; /**< handles for interesting parameters */
|
|
||||||
|
|
||||||
PID_t _steering_ctrl{};
|
|
||||||
|
|
||||||
void parameters_update();
|
|
||||||
|
|
||||||
void vehicle_control_mode_poll();
|
|
||||||
void manual_control_setpoint_poll();
|
|
||||||
void vehicle_attitude_setpoint_poll();
|
|
||||||
void battery_status_poll();
|
|
||||||
|
|
||||||
static int task_main_trampoline(int argc, char *argv[]);
|
|
||||||
void task_main();
|
|
||||||
|
|
||||||
};
|
|
||||||
@@ -1,195 +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 gnd_att_control_params.c
|
|
||||||
*
|
|
||||||
* Parameters defined by the attitude 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 <mzorzi@student.ethz.ch>
|
|
||||||
*/
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Controller parameters, accessible via MAVLink
|
|
||||||
*
|
|
||||||
*/
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Attitude Wheel Time Constant
|
|
||||||
*
|
|
||||||
* This defines the latency between a steering step input and the achieved setpoint
|
|
||||||
* (inverse to a P gain). Half a second is a good start value and fits for
|
|
||||||
* most average systems. Smaller systems may require smaller values, but as
|
|
||||||
* this will wear out servos faster, the value should only be decreased as
|
|
||||||
* needed.
|
|
||||||
*
|
|
||||||
* @unit s
|
|
||||||
* @min 0.4
|
|
||||||
* @max 1.0
|
|
||||||
* @decimal 2
|
|
||||||
* @increment 0.05
|
|
||||||
* @group GND Attitude Control
|
|
||||||
*/
|
|
||||||
PARAM_DEFINE_FLOAT(GND_WR_TC, 0.4f);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Wheel steering rate proportional gain
|
|
||||||
*
|
|
||||||
* This defines how much the wheel steering input will be commanded depending on the
|
|
||||||
* current body angular rate error.
|
|
||||||
*
|
|
||||||
* @unit %/rad/s
|
|
||||||
* @min 0.005
|
|
||||||
* @max 1.0
|
|
||||||
* @decimal 3
|
|
||||||
* @increment 0.005
|
|
||||||
* @group GND Attitude Control
|
|
||||||
*/
|
|
||||||
PARAM_DEFINE_FLOAT(GND_WR_P, 1.0f);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Wheel steering rate integrator gain
|
|
||||||
*
|
|
||||||
* This gain defines how much control response will result out of a steady
|
|
||||||
* state error. It trims any constant error.
|
|
||||||
*
|
|
||||||
* @unit %/rad
|
|
||||||
* @min 0.00
|
|
||||||
* @max 0.5
|
|
||||||
* @decimal 3
|
|
||||||
* @increment 0.005
|
|
||||||
* @group GND Attitude Control
|
|
||||||
*/
|
|
||||||
PARAM_DEFINE_FLOAT(GND_WR_I, 0.00f);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Wheel steering rate integrator gain
|
|
||||||
*
|
|
||||||
*
|
|
||||||
* @unit %/rad
|
|
||||||
* @min 0.00
|
|
||||||
* @max 30
|
|
||||||
* @decimal 3
|
|
||||||
* @increment 0.005
|
|
||||||
* @group GND Attitude Control
|
|
||||||
*/
|
|
||||||
PARAM_DEFINE_FLOAT(GND_WR_D, 0.00f);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Wheel steering rate integrator limit
|
|
||||||
*
|
|
||||||
* The portion of the integrator part in the control surface deflection is
|
|
||||||
* limited to this value
|
|
||||||
*
|
|
||||||
* @min 0.0
|
|
||||||
* @max 1.0
|
|
||||||
* @decimal 2
|
|
||||||
* @increment 0.05
|
|
||||||
* @group GND Attitude Control
|
|
||||||
*/
|
|
||||||
PARAM_DEFINE_FLOAT(GND_WR_IMAX, 0.0f);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Maximum wheel steering rate
|
|
||||||
*
|
|
||||||
* This limits the maximum wheel steering rate the controller will output (in degrees per
|
|
||||||
* second). Setting a value of zero disables the limit.
|
|
||||||
*
|
|
||||||
* @unit deg/s
|
|
||||||
* @min 0.0
|
|
||||||
* @max 90.0
|
|
||||||
* @decimal 1
|
|
||||||
* @increment 0.5
|
|
||||||
* @group GND Attitude Control
|
|
||||||
*/
|
|
||||||
PARAM_DEFINE_FLOAT(GND_W_RMAX, 90.0f);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Wheel steering rate feed forward
|
|
||||||
*
|
|
||||||
* Direct feed forward from rate setpoint to control surface output
|
|
||||||
*
|
|
||||||
* @unit %/rad/s
|
|
||||||
* @min 0.0
|
|
||||||
* @max 10.0
|
|
||||||
* @decimal 2
|
|
||||||
* @increment 0.05
|
|
||||||
* @group GND Attitude Control
|
|
||||||
*/
|
|
||||||
PARAM_DEFINE_FLOAT(GND_WR_FF, 0.0f);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Manual yaw scale
|
|
||||||
*
|
|
||||||
* Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows
|
|
||||||
* to adjust the throws of the control surfaces.
|
|
||||||
*
|
|
||||||
* @unit norm
|
|
||||||
* @min 0.0
|
|
||||||
* @decimal 2
|
|
||||||
* @increment 0.01
|
|
||||||
* @group GND Attitude Control
|
|
||||||
*/
|
|
||||||
PARAM_DEFINE_FLOAT(GND_MAN_Y_SC, 1.0f);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Groundspeed speed trim
|
|
||||||
*
|
|
||||||
* This allows to scale the turning radius depending on the speed.
|
|
||||||
*
|
|
||||||
* @unit norm
|
|
||||||
* @min 0.0
|
|
||||||
* @decimal 2
|
|
||||||
* @increment 0.1
|
|
||||||
* @group GND Attitude Control
|
|
||||||
*/
|
|
||||||
PARAM_DEFINE_FLOAT(GND_GSPD_SP_TRIM, 1.0f);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Whether to scale throttle by battery power level
|
|
||||||
*
|
|
||||||
* This compensates for voltage drop of the battery over time by attempting to
|
|
||||||
* normalize performance across the operating range of the battery. The fixed wing
|
|
||||||
* should constantly behave as if it was fully charged with reduced max thrust
|
|
||||||
* at lower battery percentages. i.e. if cruise speed is at 0.5 throttle at 100% battery,
|
|
||||||
* it will still be 0.5 at 60% battery.
|
|
||||||
*
|
|
||||||
* @boolean
|
|
||||||
* @group GND Attitude Control
|
|
||||||
*/
|
|
||||||
PARAM_DEFINE_INT32(GND_BAT_SCALE_EN, 0);
|
|
||||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user