Skip to content

Commit

Permalink
differential: refactor code architecture
Browse files Browse the repository at this point in the history
  • Loading branch information
chfriedrich98 committed Feb 11, 2025
1 parent b96b4fb commit 8d04fd8
Show file tree
Hide file tree
Showing 28 changed files with 1,707 additions and 1,356 deletions.
44 changes: 27 additions & 17 deletions ROMFS/px4fmu_common/init.d-posix/airframes/4009_gz_r1_rover
Original file line number Diff line number Diff line change
Expand Up @@ -11,29 +11,39 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=r1_rover}

param set-default SIM_GZ_EN 1 # Gazebo bridge

# Rover parameters
param set-default NAV_ACC_RAD 0.5

# Differential Parameters
param set-default RD_WHEEL_TRACK 0.3
param set-default RD_MAX_ACCEL 5
param set-default RD_MAX_DECEL 10
param set-default RD_MAX_JERK 30
param set-default RD_MAX_THR_YAW_R 1.5
param set-default RD_YAW_RATE_P 0.25
param set-default RD_YAW_RATE_I 0.01
param set-default RD_YAW_P 5
param set-default RD_YAW_I 0.1
param set-default RD_MAX_SPEED 2
param set-default RD_MAX_THR_SPD 2.15
param set-default RD_SPEED_P 0.1
param set-default RD_SPEED_I 0.01
param set-default RD_MAX_YAW_RATE 180
param set-default RD_TRANS_DRV_TRN 0.349066
param set-default RD_TRANS_TRN_DRV 0.174533
param set-default RD_MAX_YAW_ACCEL 1000

# Pure pursuit parameters
param set-default PP_LOOKAHD_MAX 30
param set-default PP_LOOKAHD_MIN 2
# Rover Control Parameters
param set-default RO_ACCEL_LIM 5
param set-default RO_DECEL_LIM 10
param set-default RO_JERK_LIM 30
param set-default RO_MAX_THR_SPEED 2.1

# Rover Rate Control Parameters
param set-default RO_YAW_RATE_I 0.01
param set-default RO_YAW_RATE_P 0.25
param set-default RO_YAW_RATE_LIM 180
param set-default RO_YAW_ACCEL_LIM 120
param set-default RO_YAW_DECEL_LIM 1000

# Rover Attitude Control Parameters
param set-default RO_YAW_P 5

# Rover Position Control Parameters
param set-default RO_SPEED_LIM 2
param set-default RO_SPEED_I 0.5
param set-default RO_SPEED_P 1

# Pure Pursuit parameters
param set-default PP_LOOKAHD_GAIN 1
param set-default PP_LOOKAHD_MAX 10
param set-default PP_LOOKAHD_MIN 1

# Simulated sensors
param set-default SENS_EN_GPSSIM 1
Expand Down
43 changes: 27 additions & 16 deletions ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover
Original file line number Diff line number Diff line change
Expand Up @@ -21,26 +21,37 @@ param set-default RBCLW_FUNC1 101
param set-default RBCLW_FUNC2 102
param set-default RBCLW_REV 1 # reverse right wheels

# Rover parameters

param set-default NAV_ACC_RAD 0.5

# Differential Parameters
param set-default RD_WHEEL_TRACK 0.3
param set-default RD_MAX_ACCEL 3
param set-default RD_MAX_DECEL 4
param set-default RD_MAX_JERK 5
param set-default RD_MAX_SPEED 1.6
param set-default RD_MAX_THR_SPD 1.9
param set-default RD_MAX_THR_YAW_R 0.7
param set-default RD_MAX_YAW_ACCEL 600
param set-default RD_MAX_YAW_RATE 250
param set-default RD_SPEED_P 0.1
param set-default RD_SPEED_I 0.01
param set-default RD_TRANS_DRV_TRN 0.785398
param set-default RD_TRANS_TRN_DRV 0.139626
param set-default RD_YAW_P 5
param set-default RD_YAW_I 0.1
param set-default RD_YAW_RATE_P 0.1
param set-default RD_YAW_RATE_I 0.01

# Pure pursuit parameters
# Rover Control Parameters
param set-default RO_ACCEL_LIM 3
param set-default RO_DECEL_LIM 4
param set-default RO_JERK_LIM 5
param set-default RO_MAX_THR_SPEED 1.9

# Rover Rate Control Parameters
param set-default RO_YAW_RATE_I 0.01
param set-default RO_YAW_RATE_P 0.1
param set-default RO_YAW_RATE_LIM 250
param set-default RO_YAW_ACCEL_LIM 600
param set-default RO_YAW_DECEL_LIM 600

# Rover Attitude Control Parameters
param set-default RO_YAW_P 5

# Rover Position Control Parameters
param set-default RO_SPEED_LIM 1.6
param set-default RO_SPEED_I 0.01
param set-default RO_SPEED_P 0.1

# Pure Pursuit parameters
param set-default PP_LOOKAHD_GAIN 1
param set-default PP_LOOKAHD_MAX 10
param set-default PP_LOOKAHD_MIN 1
param set-default PP_LOOKAHD_GAIN 1
3 changes: 0 additions & 3 deletions msg/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -178,9 +178,6 @@ set(msg_files
RoverRateStatus.msg
RoverSteeringSetpoint.msg
RoverThrottleSetpoint.msg
RoverDifferentialGuidanceStatus.msg
RoverDifferentialSetpoint.msg
RoverDifferentialStatus.msg
RoverMecanumGuidanceStatus.msg
RoverMecanumSetpoint.msg
RoverMecanumStatus.msg
Expand Down
7 changes: 0 additions & 7 deletions msg/RoverDifferentialGuidanceStatus.msg

This file was deleted.

9 changes: 0 additions & 9 deletions msg/RoverDifferentialSetpoint.msg

This file was deleted.

14 changes: 0 additions & 14 deletions msg/RoverDifferentialStatus.msg

This file was deleted.

89 changes: 72 additions & 17 deletions src/lib/rover_control/RoverControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,26 +48,24 @@ float throttleControl(SlewRate<float> &motor_setpoint, const float throttle_setp

if (accelerating && max_accel > FLT_EPSILON && max_thr_spd > FLT_EPSILON) { // Acceleration slew rate
motor_setpoint.setSlewRate(max_accel / max_thr_spd);
motor_setpoint.update(throttle_setpoint, dt);

// Reinitialize slew rate if current value is closer to setpoint than post slew rate value
if (fabsf(motor_setpoint.getState() - current_motor_setpoint) > fabsf(throttle_setpoint -
current_motor_setpoint)) {
motor_setpoint.setForcedValue(current_motor_setpoint);
motor_setpoint.setForcedValue(throttle_setpoint);
}

motor_setpoint.update(throttle_setpoint, dt);

} else if (!accelerating && max_decel > FLT_EPSILON && max_thr_spd > FLT_EPSILON) { // Deceleration slew rate
motor_setpoint.setSlewRate(max_decel / max_thr_spd);
motor_setpoint.update(throttle_setpoint, dt);

// Reinitialize slew rate if current value is closer to setpoint than post slew rate value
if (fabsf(motor_setpoint.getState() - current_motor_setpoint) > fabsf(throttle_setpoint -
current_motor_setpoint)) {
motor_setpoint.setForcedValue(current_motor_setpoint);
motor_setpoint.setForcedValue(throttle_setpoint);
}

motor_setpoint.update(throttle_setpoint, dt);

} else { // Fallthrough if slew rate parameters are not configured
motor_setpoint.setForcedValue(throttle_setpoint);
}
Expand All @@ -88,14 +86,13 @@ float attitudeControl(SlewRateYaw<float> &adjusted_yaw_setpoint, PID &pid_yaw,

if (yaw_slew_rate > FLT_EPSILON) { // Apply slew rate if configured
adjusted_yaw_setpoint.setSlewRate(yaw_slew_rate);
adjusted_yaw_setpoint.update(yaw_setpoint, dt);

// Reinitialize slew rate if current value is closer to setpoint than post slew rate value
if (fabsf(wrap_pi(adjusted_yaw_setpoint.getState() - vehicle_yaw)) > fabsf(wrap_pi(yaw_setpoint - vehicle_yaw))) {
adjusted_yaw_setpoint.setForcedValue(vehicle_yaw);
adjusted_yaw_setpoint.setForcedValue(yaw_setpoint);
}

adjusted_yaw_setpoint.update(yaw_setpoint, dt);

} else {
adjusted_yaw_setpoint.setForcedValue(yaw_setpoint);
}
Expand All @@ -118,26 +115,24 @@ float speedControl(SlewRate<float> &speed_with_rate_limit, PID &pid_speed, const
// Apply acceleration and deceleration limit
if (fabsf(speed_setpoint) >= fabsf(vehicle_speed) && max_accel > FLT_EPSILON) {
speed_with_rate_limit.setSlewRate(max_accel);
speed_with_rate_limit.update(speed_setpoint, dt);

// Reinitialize slew rate if current value is closer to setpoint than post slew rate value
if (fabsf(speed_with_rate_limit.getState() - vehicle_speed) > fabsf(
speed_setpoint - vehicle_speed)) {
speed_with_rate_limit.setForcedValue(vehicle_speed);
speed_with_rate_limit.setForcedValue(speed_setpoint);
}

speed_with_rate_limit.update(speed_setpoint, dt);

} else if (fabsf(speed_setpoint) < fabsf(vehicle_speed) && max_decel > FLT_EPSILON) {
speed_with_rate_limit.setSlewRate(max_decel);
speed_with_rate_limit.update(speed_setpoint, dt);

// Reinitialize slew rate if current value is closer to setpoint than post slew rate value
if (fabsf(speed_with_rate_limit.getState() - vehicle_speed) > fabsf(
speed_setpoint - vehicle_speed)) {
speed_with_rate_limit.setForcedValue(vehicle_speed);
speed_with_rate_limit.setForcedValue(speed_setpoint);
}

speed_with_rate_limit.update(speed_setpoint, dt);

} else { // Fallthrough if slew rate is not configured
speed_with_rate_limit.setForcedValue(speed_setpoint);
}
Expand All @@ -153,12 +148,72 @@ float speedControl(SlewRate<float> &speed_with_rate_limit, PID &pid_speed, const
}

// Feedback control
pid_speed.setSetpoint(speed_with_rate_limit.getState());
forward_speed_normalized += pid_speed.update(vehicle_speed, dt);
if (fabsf(speed_with_rate_limit.getState()) > FLT_EPSILON) {
pid_speed.setSetpoint(speed_with_rate_limit.getState());
forward_speed_normalized += pid_speed.update(vehicle_speed, dt);

} else {
pid_speed.resetIntegral();
}


return math::constrain(forward_speed_normalized, -1.f, 1.f);
}

float rateControl(SlewRate<float> &adjusted_yaw_rate_setpoint, PID &pid_yaw_rate, const float yaw_rate_setpoint,
const float vehicle_yaw_rate, const float max_thr_yaw_r, const float max_yaw_accel, const float max_yaw_decel,
const float wheel_track, const float dt)
{
// Apply acceleration and deceleration limit
if (fabsf(yaw_rate_setpoint) >= fabsf(vehicle_yaw_rate) && max_yaw_accel > FLT_EPSILON) {
adjusted_yaw_rate_setpoint.setSlewRate(max_yaw_accel);
adjusted_yaw_rate_setpoint.update(yaw_rate_setpoint, dt);

// Reinitialize slew rate if current value is closer to setpoint than post slew rate value
if (fabsf(adjusted_yaw_rate_setpoint.getState() - vehicle_yaw_rate) > fabsf(
yaw_rate_setpoint - vehicle_yaw_rate)) {
adjusted_yaw_rate_setpoint.setForcedValue(yaw_rate_setpoint);
}


} else if (fabsf(yaw_rate_setpoint) < fabsf(vehicle_yaw_rate) && max_yaw_decel > FLT_EPSILON) {
adjusted_yaw_rate_setpoint.setSlewRate(max_yaw_decel);
adjusted_yaw_rate_setpoint.update(yaw_rate_setpoint, dt);

// Reinitialize slew rate if current value is closer to setpoint than post slew rate value
if (fabsf(adjusted_yaw_rate_setpoint.getState() - vehicle_yaw_rate) > fabsf(
yaw_rate_setpoint - vehicle_yaw_rate)) {
adjusted_yaw_rate_setpoint.setForcedValue(yaw_rate_setpoint);
}


} else { // Fallthrough if slew rate is not configured
adjusted_yaw_rate_setpoint.setForcedValue(yaw_rate_setpoint);
}

// Transform yaw rate into speed difference
float speed_diff_normalized{0.f};

if (wheel_track > FLT_EPSILON && max_thr_yaw_r > FLT_EPSILON) { // Feedforward
const float speed_diff = adjusted_yaw_rate_setpoint.getState() * wheel_track /
2.f;
speed_diff_normalized = math::interpolate<float>(speed_diff, -max_thr_yaw_r,
max_thr_yaw_r, -1.f, 1.f);
}

// Feedback control
if (fabsf(adjusted_yaw_rate_setpoint.getState()) > FLT_EPSILON) {
pid_yaw_rate.setSetpoint(adjusted_yaw_rate_setpoint.getState());
speed_diff_normalized += pid_yaw_rate.update(vehicle_yaw_rate, dt);

} else {
pid_yaw_rate.resetIntegral();
}


return math::constrain(speed_diff_normalized, -1.f, 1.f);
}

void globalToLocalSetpointTriplet(Vector2f &curr_wp_ned, Vector2f &prev_wp_ned, Vector2f &next_wp_ned,
position_setpoint_triplet_s position_setpoint_triplet, Vector2f &curr_pos_ned, Vector2d &home_pos,
MapProjection &global_ned_proj_ref)
Expand Down
18 changes: 18 additions & 0 deletions src/lib/rover_control/RoverControl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,24 @@ float attitudeControl(SlewRateYaw<float> &adjusted_yaw_setpoint, PID &pid_yaw, f
float speedControl(SlewRate<float> &speed_with_rate_limit, PID &pid_speed, float speed_setpoint,
float vehicle_speed, float max_accel, float max_decel, float max_thr_speed, float dt);

/**
* Applies yaw acceleration slew rate to a yaw rate setpoint and calculates the necessary speed diff setpoint
* using a feedforward term and/or a PID controller.
* @param adjusted_yaw_rate_setpoint Yaw rate setpoint with applied slew rate [-1, 1] (Updated by this function).
* @param pid_yaw_rate Yaw rate PID (Updated by this function).
* @param yaw_rate_setpoint Yaw rate setpoint [rad/s].
* @param vehicle_yaw_rate Measured vehicle yaw rate [rad/s].
* @param max_thr_yaw_r Yaw rate turning left/right wheels at max speed in opposite directions [m/s].
* @param max_yaw_accel Maximum allowed yaw acceleration [rad/s^2].
* @param max_yaw_decel Maximum allowed yaw deceleration [rad/s^2].
* @param wheel_track Distance from the center of the right wheel to the center of the left wheel [m].
* @param dt Time since last update [s].
* @return Normalized speed difference setpoint [-1, 1].
*/
float rateControl(SlewRate<float> &adjusted_yaw_rate_setpoint, PID &pid_yaw_rate,
float yaw_rate_setpoint, float vehicle_yaw_rate, float max_thr_yaw_r, float max_yaw_accel, float max_yaw_decel,
float wheel_track, float dt);

/**
* Projects positionSetpointTriplet waypoints from global to ned frame.
* @param curr_wp_ned Current waypoint in NED frame (Updated by this function)
Expand Down
13 changes: 13 additions & 0 deletions src/lib/rover_control/module.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,19 @@ parameters:
decimal: 2
default: -1

RO_YAW_DECEL_LIM:
description:
short: Yaw deceleration limit
long: |
Set to -1 to disable.
type: float
unit: deg/s^2
min: -1
max: 10000
increment: 0.01
decimal: 2
default: -1

- group: Rover Attitude Control
definitions:
RO_YAW_P:
Expand Down
3 changes: 0 additions & 3 deletions src/modules/logger/logged_topics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,9 +109,6 @@ void LoggedTopics::add_default_topics()
add_optional_topic("rover_rate_status", 100);
add_optional_topic("rover_steering_setpoint", 100);
add_optional_topic("rover_throttle_setpoint", 100);
add_optional_topic("rover_differential_guidance_status", 100);
add_optional_topic("rover_differential_setpoint", 100);
add_optional_topic("rover_differential_status", 100);
add_optional_topic("rover_mecanum_guidance_status", 100);
add_optional_topic("rover_mecanum_setpoint", 100);
add_optional_topic("rover_mecanum_status", 100);
Expand Down
14 changes: 8 additions & 6 deletions src/modules/rover_differential/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2024 PX4 Development Team. All rights reserved.
# Copyright (c) 2025 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
Expand Down Expand Up @@ -31,8 +31,9 @@
#
############################################################################

add_subdirectory(RoverDifferentialGuidance)
add_subdirectory(RoverDifferentialControl)
add_subdirectory(DifferentialRateControl)
add_subdirectory(DifferentialAttControl)
add_subdirectory(DifferentialPosVelControl)

px4_add_module(
MODULE modules__rover_differential
Expand All @@ -41,10 +42,11 @@ px4_add_module(
RoverDifferential.cpp
RoverDifferential.hpp
DEPENDS
RoverDifferentialGuidance
RoverDifferentialControl
DifferentialRateControl
DifferentialAttControl
DifferentialPosVelControl
px4_work_queue
pure_pursuit
rover_control
MODULE_CONFIG
module.yaml
)
Loading

0 comments on commit 8d04fd8

Please sign in to comment.