mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 11:59:17 +08:00
rover: restructure airframes (#23506)
This commit is contained in:
@@ -0,0 +1,12 @@
|
|||||||
|
#!/bin/sh
|
||||||
|
#
|
||||||
|
# @name Generic Rover Differential
|
||||||
|
#
|
||||||
|
# @type Rover
|
||||||
|
# @class Rover
|
||||||
|
#
|
||||||
|
# @board px4_fmu-v2 exclude
|
||||||
|
# @board bitcraze_crazyflie exclude
|
||||||
|
#
|
||||||
|
|
||||||
|
. ${R}etc/init.d/rc.rover_differential_defaults
|
||||||
-3
@@ -15,9 +15,6 @@
|
|||||||
|
|
||||||
param set-default BAT1_N_CELLS 4
|
param set-default BAT1_N_CELLS 4
|
||||||
|
|
||||||
param set-default EKF2_GBIAS_INIT 0.01
|
|
||||||
param set-default EKF2_ANGERR_INIT 0.01
|
|
||||||
|
|
||||||
# Set geometry & output configration
|
# Set geometry & output configration
|
||||||
param set-default RBCLW_ADDRESS 128
|
param set-default RBCLW_ADDRESS 128
|
||||||
param set-default RBCLW_FUNC1 101
|
param set-default RBCLW_FUNC1 101
|
||||||
+1
-1
@@ -1,6 +1,6 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
#
|
#
|
||||||
# @name Generic ackermann rover
|
# @name Generic Rover Ackermann
|
||||||
#
|
#
|
||||||
# @type Rover
|
# @type Rover
|
||||||
# @class Rover
|
# @class Rover
|
||||||
@@ -0,0 +1,37 @@
|
|||||||
|
#!/bin/sh
|
||||||
|
#
|
||||||
|
# @name Axial SCX10 2 Trail Honcho
|
||||||
|
#
|
||||||
|
# @url https://www.axialadventure.com/product/1-10-scx10-ii-trail-honcho-4wd-rock-crawler-brushed-rtr/AXID9059.html
|
||||||
|
#
|
||||||
|
# @type Rover
|
||||||
|
# @class Rover
|
||||||
|
#
|
||||||
|
# @board px4_fmu-v2 exclude
|
||||||
|
# @board bitcraze_crazyflie exclude
|
||||||
|
#
|
||||||
|
|
||||||
|
. ${R}etc/init.d/rc.rover_ackermann_defaults
|
||||||
|
|
||||||
|
param set-default BAT1_N_CELLS 3
|
||||||
|
|
||||||
|
# Rover parameters
|
||||||
|
param set-default NAV_ACC_RAD 0.5
|
||||||
|
param set-default RA_ACC_RAD_GAIN 2
|
||||||
|
param set-default RA_ACC_RAD_MAX 3
|
||||||
|
param set-default RA_MAX_ACCEL 0.5
|
||||||
|
param set-default RA_MAX_JERK 10
|
||||||
|
param set-default RA_MAX_SPEED 2.7
|
||||||
|
param set-default RA_MAX_STR_ANG 0.5236
|
||||||
|
param set-default RA_MAX_STR_RATE 270
|
||||||
|
param set-default RA_MISS_VEL_DEF 2.7
|
||||||
|
param set-default RA_MISS_VEL_GAIN 3.5
|
||||||
|
param set-default RA_MISS_VEL_MIN 1
|
||||||
|
param set-default RA_SPEED_I 0.1
|
||||||
|
param set-default RA_SPEED_P 0.5
|
||||||
|
param set-default RA_WHEEL_BASE 0.321
|
||||||
|
|
||||||
|
# Pure pursuit parameters
|
||||||
|
param set-default PP_LOOKAHD_GAIN 1
|
||||||
|
param set-default PP_LOOKAHD_MAX 10
|
||||||
|
param set-default PP_LOOKAHD_MIN 1.5
|
||||||
+1
-1
@@ -1,6 +1,6 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
#
|
#
|
||||||
# @name Generic Ground Vehicle (Ackermann)
|
# @name Generic Ground Vehicle (Deprecated)
|
||||||
#
|
#
|
||||||
# @type Rover
|
# @type Rover
|
||||||
# @class Rover
|
# @class Rover
|
||||||
+1
-1
@@ -1,6 +1,6 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
#
|
#
|
||||||
# @name NXP Cup car: DF Robot GPX
|
# @name NXP Cup car: DF Robot GPX (Deprecated)
|
||||||
|
|
||||||
#
|
#
|
||||||
# @type Rover
|
# @type Rover
|
||||||
@@ -136,22 +136,27 @@ if(CONFIG_MODULES_VTOL_ATT_CONTROL)
|
|||||||
)
|
)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
if(CONFIG_MODULES_ROVER_POS_CONTROL)
|
|
||||||
px4_add_romfs_files(
|
|
||||||
50000_generic_ground_vehicle
|
|
||||||
50004_nxpcup_car_dfrobot_gpx
|
|
||||||
)
|
|
||||||
endif()
|
|
||||||
|
|
||||||
if(CONFIG_MODULES_ROVER_DIFFERENTIAL)
|
if(CONFIG_MODULES_ROVER_DIFFERENTIAL)
|
||||||
px4_add_romfs_files(
|
px4_add_romfs_files(
|
||||||
50003_aion_robotics_r1_rover
|
# [50000, 50999] Differential rovers
|
||||||
|
50000_generic_rover_differential
|
||||||
|
50001_aion_robotics_r1_rover
|
||||||
)
|
)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
if(CONFIG_MODULES_ROVER_ACKERMANN)
|
if(CONFIG_MODULES_ROVER_ACKERMANN)
|
||||||
px4_add_romfs_files(
|
px4_add_romfs_files(
|
||||||
50010_ackermann_rover_generic
|
# [51000, 51999] Ackermann rovers
|
||||||
|
51000_generic_rover_ackermann
|
||||||
|
51001_axial_scx10_2_trail_honcho
|
||||||
|
)
|
||||||
|
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()
|
endif()
|
||||||
|
|
||||||
|
|||||||
@@ -1,7 +1,7 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
# Standard apps for a ackermann drive rover.
|
# Standard apps for an ackermann rover.
|
||||||
|
|
||||||
# Start rover ackermann drive controller.
|
# Start rover ackermann module.
|
||||||
rover_ackermann start
|
rover_ackermann start
|
||||||
|
|
||||||
# Start Land Detector.
|
# Start Land Detector.
|
||||||
|
|||||||
@@ -5,9 +5,7 @@ set VEHICLE_TYPE rover_ackermann
|
|||||||
param set-default MAV_TYPE 10 # MAV_TYPE_GROUND_ROVER
|
param set-default MAV_TYPE 10 # MAV_TYPE_GROUND_ROVER
|
||||||
param set-default CA_AIRFRAME 5 # Rover (Ackermann)
|
param set-default CA_AIRFRAME 5 # Rover (Ackermann)
|
||||||
param set-default CA_R_REV 1 # Motor is assumed to be reversible
|
param set-default CA_R_REV 1 # Motor is assumed to be reversible
|
||||||
param set-default EKF2_MAG_TYPE 1 # make sure magnetometer is fused even when not flying
|
param set-default EKF2_MAG_TYPE 1 # Make sure magnetometer is fused even when not flying
|
||||||
|
param set-default NAV_ACC_RAD 0.5 # Waypoint acceptance radius
|
||||||
param set-default EKF2_GBIAS_INIT 0.01
|
param set-default EKF2_GBIAS_INIT 0.01
|
||||||
param set-default EKF2_ANGERR_INIT 0.01
|
param set-default EKF2_ANGERR_INIT 0.01
|
||||||
param set-default NAV_ACC_RAD 0.5 # Waypoint acceptance radius
|
|
||||||
param set-default NAV_RCL_ACT 6 # Disarm on manual control loss
|
|
||||||
param set-default COM_FAIL_ACT_T 1 # Delay before failsafe after rc loss
|
|
||||||
|
|||||||
@@ -1,7 +1,7 @@
|
|||||||
#!/bin/sh
|
#!/bin/sh
|
||||||
# Standard apps for a differential drive rover.
|
# Standard apps for a differential rover.
|
||||||
|
|
||||||
# Start rover differential drive controller.
|
# Start rover differential module.
|
||||||
rover_differential start
|
rover_differential start
|
||||||
|
|
||||||
# Start Land Detector.
|
# Start Land Detector.
|
||||||
|
|||||||
@@ -2,9 +2,10 @@
|
|||||||
# Differential rover parameters.
|
# Differential rover parameters.
|
||||||
|
|
||||||
set VEHICLE_TYPE rover_differential
|
set VEHICLE_TYPE rover_differential
|
||||||
|
|
||||||
param set-default MAV_TYPE 10 # MAV_TYPE_GROUND_ROVER
|
param set-default MAV_TYPE 10 # MAV_TYPE_GROUND_ROVER
|
||||||
param set-default CA_AIRFRAME 6 # Rover (Differential)
|
param set-default CA_AIRFRAME 6 # Rover (Differential)
|
||||||
param set-default CA_R_REV 3 # Right and left motors reversible
|
param set-default CA_R_REV 3 # Right and left motors reversible
|
||||||
param set-default NAV_ACC_RAD 0.5 # Waypoint acceptance radius
|
|
||||||
param set-default EKF2_MAG_TYPE 1 # Make sure magnetometer is fused even when not flying
|
param set-default EKF2_MAG_TYPE 1 # Make sure magnetometer is fused even when not flying
|
||||||
|
param set-default NAV_ACC_RAD 0.5 # Waypoint acceptance radius
|
||||||
|
param set-default EKF2_GBIAS_INIT 0.01
|
||||||
|
param set-default EKF2_ANGERR_INIT 0.01
|
||||||
|
|||||||
Reference in New Issue
Block a user