Skip to content

Commit

Permalink
Differential Rover: PR fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
MaEtUgR committed Dec 21, 2023
1 parent 667f5e1 commit 126c890
Show file tree
Hide file tree
Showing 35 changed files with 364 additions and 461 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
# @name Rover
#

. ${R}etc/init.d/rc.rover_ackermann_defaults
. ${R}etc/init.d/rc.rover_defaults

param set-default GND_L1_DIST 5
param set-default GND_L1_PERIOD 10
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,29 +6,7 @@

. ${R}etc/init.d/rc.rover_differential_defaults

param set-default GND_L1_DIST 5
param set-default GND_SP_CTRL_MODE 1
param set-default GND_SPEED_D 3
param set-default GND_SPEED_I 0.001
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.0

param set-default CA_AIRFRAME 6

param set-default CA_R_REV 3
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

41 changes: 12 additions & 29 deletions ROMFS/px4fmu_common/init.d-posix/airframes/4009_gz_r1_rover
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
#!/bin/sh
#
# @name Aion Robotics R1 Rover
# @type Rover
# @class Rover
Expand All @@ -10,39 +9,23 @@ PX4_SIMULATOR=${PX4_SIMULATOR:=gz}
PX4_GZ_WORLD=${PX4_GZ_WORLD:=default}
PX4_SIM_MODEL=${PX4_SIM_MODEL:=r1_rover}

param set-default SIM_GZ_EN 1
param set-default SIM_GZ_EN 1 # Gazebo bridge

# Simulated sensors
param set-default SENS_EN_GPSSIM 1
param set-default SENS_EN_BAROSIM 0
param set-default SENS_EN_MAGSIM 1
param set-default SENS_EN_ARSPDSIM 1

param set-default COM_PREARM_MODE 2
# Actuator mapping
param set-default SIM_GZ_WH_FUNC1 101 # right wheel
param set-default SIM_GZ_WH_MIN1 0
param set-default SIM_GZ_WH_MAX1 200
param set-default SIM_GZ_WH_DIS1 100

param set-default NAV_ACC_RAD 0.5
param set-default NAV_LOITER_RAD 2
param set-default SIM_GZ_WH_FUNC2 102 # left wheel
param set-default SIM_GZ_WH_MIN2 0
param set-default SIM_GZ_WH_MAX2 200
param set-default SIM_GZ_WH_DIS2 100

param set-default GND_MAX_ANG 0.6
param set-default GND_WHEEL_BASE 2.0

param set-default CA_R_REV 3

param set-default SIM_GZ_EC_FUNC1 101
param set-default SIM_GZ_EC_MIN1 0
param set-default SIM_GZ_EC_MAX1 200
param set-default SIM_GZ_EC_DIS1 100

param set-default SIM_GZ_EC_FUNC2 102
param set-default SIM_GZ_EC_MIN2 0
param set-default SIM_GZ_EC_MAX2 200
param set-default SIM_GZ_EC_DIS2 100

param set-default SIM_GZ_MT_FUNC1 101
param set-default SIM_GZ_MT_MIN1 0
param set-default SIM_GZ_MT_MAX1 200
param set-default SIM_GZ_MT_DIS1 100

param set-default SIM_GZ_MT_FUNC2 102
param set-default SIM_GZ_MT_MIN2 0
param set-default SIM_GZ_MT_MAX2 200
param set-default SIM_GZ_MT_DIS2 100
param set-default SIM_GZ_WH_REV 1 # reverse right wheel
2 changes: 0 additions & 2 deletions ROMFS/px4fmu_common/init.d/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -53,8 +53,6 @@ px4_add_romfs_files(
rc.rover_defaults
rc.rover_differential_apps
rc.rover_differential_defaults
rc.rover_ackermann_apps
rc.rover_ackermann_defaults
rc.uuv_apps
rc.uuv_defaults
rc.vehicle_setup
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
# @board bitcraze_crazyflie exclude
#

. ${R}etc/init.d/rc.rover_ackermann_defaults
. ${R}etc/init.d/rc.rover_defaults


param set-default BAT1_N_CELLS 2
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,50 +13,13 @@

. ${R}etc/init.d/rc.rover_differential_defaults



param set-default BAT1_N_CELLS 4

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_SP_CTRL_MODE 1
param set-default GND_L1_DIST 5
param set-default GND_L1_PERIOD 3
param set-default GND_THR_CRUISE 0.7
param set-default 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-default GND_MAX_ANG 3.142
param set-default GND_WHEEL_BASE 0.3

# TODO: Set to -1.0, to allow reversing. This will require many changes in the codebase
# to support negative throttle.
param set-default GND_THR_MIN 0
param set-default GND_SPEED_P 0.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

# Differential drive acts like ackermann steering with a maximum turn angle of 180 degrees, or pi radians
param set-default GND_MAX_ANG 3.1415

# Set geometry & output configration
param set-default CA_AIRFRAME 6
param set-default CA_R_REV 3


param set-default RBCLW_ADDRESS 128
param set-default RBCLW_FUNC1 101
param set-default RBCLW_FUNC2 102
param set-default RBCLW_REV 1
param set-default RBCLW_REV 1 # reverse right wheels
28 changes: 0 additions & 28 deletions ROMFS/px4fmu_common/init.d/rc.rover_ackermann_apps

This file was deleted.

22 changes: 0 additions & 22 deletions ROMFS/px4fmu_common/init.d/rc.rover_ackermann_defaults

This file was deleted.

2 changes: 0 additions & 2 deletions ROMFS/px4fmu_common/init.d/rc.rover_apps
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,6 @@
# Start the attitude and position estimator.
#
ekf2 start &
#attitude_estimator_q start
#local_position_estimator start

#
# Start Control Allocator
Expand Down
17 changes: 2 additions & 15 deletions ROMFS/px4fmu_common/init.d/rc.rover_differential_apps
Original file line number Diff line number Diff line change
@@ -1,24 +1,11 @@
#!/bin/sh
#
# Standard apps for unmanned ground vehicles (UGV).
#
# NOTE: Script variables are declared/initialized/unset in the rcS script.
#
# Standard apps for a differential drive rover.

#
# Start the attitude and position estimator.
#
ekf2 start &
#attitude_estimator_q start
#local_position_estimator start

#
# Start manual rover differential drive controller.
#
# Start rover differential drive controller.
differential_drive_control start


#
# Start Land Detector.
#
land_detector start rover
14 changes: 7 additions & 7 deletions ROMFS/px4fmu_common/init.d/rc.rover_differential_defaults
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
#!/bin/sh
#
# UGV default parameters.
#
# NOTE: Script variables are declared/initialized/unset in the rcS script.
#
# Differential rover parameters.

set VEHICLE_TYPE rover_differential

# MAV_TYPE_GROUND_ROVER 10
param set-default MAV_TYPE 10
param set-default MAV_TYPE 10 # MAV_TYPE_GROUND_ROVER

param set-default CA_AIRFRAME 6 # Rover (Differential)
param set-default CA_R_REV 3 # Right and left motors reversible

param set-default EKF2_MAG_TYPE 1 # make sure magnetometer is fused even when not flying
23 changes: 7 additions & 16 deletions ROMFS/px4fmu_common/init.d/rc.vehicle_setup
Original file line number Diff line number Diff line change
Expand Up @@ -24,30 +24,21 @@ then
fi

#
# Differential Rover setup.
#
if [ $VEHICLE_TYPE = rover_differential ]
then
# Start standard UGV apps.
. ${R}etc/init.d/rc.rover_differential_apps
fi

#
# Ackermann Rover setup.
# UGV setup.
#
if [ $VEHICLE_TYPE = rover_ackermann ]
if [ $VEHICLE_TYPE = rover ]
then
# Start standard UGV apps.
. ${R}etc/init.d/rc.rover_ackermann_apps
. ${R}etc/init.d/rc.rover_apps
fi

#
# UGV setup.
# Differential Rover setup.
#
if [ $VEHICLE_TYPE = rover ]
if [ $VEHICLE_TYPE = rover_differential ]
then
# Start standard UGV apps.
. ${R}etc/init.d/rc.rover_apps
# Start differential drive rover apps.
. ${R}etc/init.d/rc.rover_differential_apps
fi

#
Expand Down
2 changes: 1 addition & 1 deletion boards/px4/fmu-v5x/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,6 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS6"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1"
CONFIG_BOARD_SERIAL_EXT2="/dev/ttyS3"
CONFIG_MODULE_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_DRIVERS_ADC_ADS1115=y
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_BMP388=y
Expand Down Expand Up @@ -54,6 +53,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y
Expand Down
2 changes: 1 addition & 1 deletion boards/px4/sitl/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULE_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE_CONTROL=y
CONFIG_MODULES_EKF2=y
CONFIG_EKF2_AUX_GLOBAL_POSITION=y
CONFIG_MODULES_EVENTS=y
Expand Down
2 changes: 1 addition & 1 deletion platforms/common/include/px4_platform_common/module.h
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ extern pthread_mutex_t px4_modules_mutex;
* static int custom_command(int argc, char *argv[])
* {
* // support for custom commands
* // it none are supported, just do:
* // if none are supported, just do:
* return print_usage("unrecognized command");
* }
*
Expand Down
2 changes: 1 addition & 1 deletion platforms/ros2/include/px4_platform_common/module.h
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@
* static int custom_command(int argc, char *argv[])
* {
* // support for custom commands
* // it none are supported, just do:
* // if none are supported, just do:
* return print_usage("unrecognized command");
* }
*
Expand Down
3 changes: 1 addition & 2 deletions src/modules/control_allocator/ControlAllocator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,6 @@ ControlAllocator::ControlAllocator() :
_actuator_servos_pub.advertise();
_actuator_servos_trim_pub.advertise();


for (int i = 0; i < MAX_NUM_MOTORS; ++i) {
char buffer[17];
snprintf(buffer, sizeof(buffer), "CA_R%u_SLEW", i);
Expand Down Expand Up @@ -240,7 +239,7 @@ ControlAllocator::update_effectiveness_source()
break;

case EffectivenessSource::ROVER_DIFFERENTIAL:
// actuator_motors message is published directly from the differential drive controller
// differential_drive_control does allocation and publishes directly to actuator_motors topic
break;

case EffectivenessSource::FIXED_WING:
Expand Down
5 changes: 3 additions & 2 deletions src/modules/differential_drive_control/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -30,17 +30,18 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################

add_subdirectory(DifferentialDriveKinematics)

px4_add_module(
MODULE modules__differential_drive_control
MAIN differential_drive_control
COMPILE_FLAGS
#-DDEBUG_BUILD
SRCS
DifferentialDriveControl.cpp
DifferentialDriveControl.hpp
DEPENDS
DifferentialDriveKinematics
px4_work_queue
MODULE_CONFIG
module.yaml
)
Loading

0 comments on commit 126c890

Please sign in to comment.