Skip to content

Commit b245155

Browse files
christophfroehlichsaikishorqinqon
authored
Fix steering controllers library code documentation and naming (#1149)
* Update documentation and consolidate variable names * Simplify private methods and further update docs * Rename methods * Rename method and variables * Rename convert method * Rename variables and improve doc * Rename local variables * Use std::isfinite instead of !isnan Co-authored-by: Sai Kishor Kothakota <sai.kishor@pal-robotics.com> * Use a lowercase theta for heading Co-authored-by: Sai Kishor Kothakota <sai.kishor@pal-robotics.com> * Make some temporary variables const * Let update_from_position call update_from_velocity * Explicitly set variables with 0 in constructor * Fix docstring * Apply consistent variable naming Co-authored-by: Quique Llorente <ellorent@redhat.com> --------- Co-authored-by: Sai Kishor Kothakota <sai.kishor@pal-robotics.com> Co-authored-by: Quique Llorente <ellorent@redhat.com>
1 parent 64adf67 commit b245155

File tree

5 files changed

+139
-150
lines changed

5 files changed

+139
-150
lines changed

ackermann_steering_controller/src/ackermann_steering_controller.cpp

+12-11
Original file line numberDiff line numberDiff line change
@@ -62,28 +62,29 @@ bool AckermannSteeringController::update_odometry(const rclcpp::Duration & perio
6262
}
6363
else
6464
{
65-
const double rear_right_wheel_value = state_interfaces_[STATE_TRACTION_RIGHT_WHEEL].get_value();
66-
const double rear_left_wheel_value = state_interfaces_[STATE_TRACTION_LEFT_WHEEL].get_value();
67-
const double front_right_steer_position =
68-
state_interfaces_[STATE_STEER_RIGHT_WHEEL].get_value();
69-
const double front_left_steer_position = state_interfaces_[STATE_STEER_LEFT_WHEEL].get_value();
65+
const double traction_right_wheel_value =
66+
state_interfaces_[STATE_TRACTION_RIGHT_WHEEL].get_value();
67+
const double traction_left_wheel_value =
68+
state_interfaces_[STATE_TRACTION_LEFT_WHEEL].get_value();
69+
const double steering_right_position = state_interfaces_[STATE_STEER_RIGHT_WHEEL].get_value();
70+
const double steering_left_position = state_interfaces_[STATE_STEER_LEFT_WHEEL].get_value();
7071
if (
71-
!std::isnan(rear_right_wheel_value) && !std::isnan(rear_left_wheel_value) &&
72-
!std::isnan(front_right_steer_position) && !std::isnan(front_left_steer_position))
72+
std::isfinite(traction_right_wheel_value) && std::isfinite(traction_left_wheel_value) &&
73+
std::isfinite(steering_right_position) && std::isfinite(steering_left_position))
7374
{
7475
if (params_.position_feedback)
7576
{
7677
// Estimate linear and angular velocity using joint information
7778
odometry_.update_from_position(
78-
rear_right_wheel_value, rear_left_wheel_value, front_right_steer_position,
79-
front_left_steer_position, period.seconds());
79+
traction_right_wheel_value, traction_left_wheel_value, steering_right_position,
80+
steering_left_position, period.seconds());
8081
}
8182
else
8283
{
8384
// Estimate linear and angular velocity using joint information
8485
odometry_.update_from_velocity(
85-
rear_right_wheel_value, rear_left_wheel_value, front_right_steer_position,
86-
front_left_steer_position, period.seconds());
86+
traction_right_wheel_value, traction_left_wheel_value, steering_right_position,
87+
steering_left_position, period.seconds());
8788
}
8889
}
8990
}

bicycle_steering_controller/src/bicycle_steering_controller.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -60,19 +60,19 @@ bool BicycleSteeringController::update_odometry(const rclcpp::Duration & period)
6060
}
6161
else
6262
{
63-
const double rear_wheel_value = state_interfaces_[STATE_TRACTION_WHEEL].get_value();
64-
const double steer_position = state_interfaces_[STATE_STEER_AXIS].get_value();
65-
if (!std::isnan(rear_wheel_value) && !std::isnan(steer_position))
63+
const double traction_wheel_value = state_interfaces_[STATE_TRACTION_WHEEL].get_value();
64+
const double steering_position = state_interfaces_[STATE_STEER_AXIS].get_value();
65+
if (std::isfinite(traction_wheel_value) && std::isfinite(steering_position))
6666
{
6767
if (params_.position_feedback)
6868
{
6969
// Estimate linear and angular velocity using joint information
70-
odometry_.update_from_position(rear_wheel_value, steer_position, period.seconds());
70+
odometry_.update_from_position(traction_wheel_value, steering_position, period.seconds());
7171
}
7272
else
7373
{
7474
// Estimate linear and angular velocity using joint information
75-
odometry_.update_from_velocity(rear_wheel_value, steer_position, period.seconds());
75+
odometry_.update_from_velocity(traction_wheel_value, steering_position, period.seconds());
7676
}
7777
}
7878
}

steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp

+32-31
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ class SteeringOdometry
6161
/**
6262
* \brief Updates the odometry class with latest wheels position
6363
* \param traction_wheel_pos traction wheel position [rad]
64-
* \param steer_pos Front Steer position [rad]
64+
* \param steer_pos Steer wheel position [rad]
6565
* \param dt time difference to last call
6666
* \return true if the odometry is actually updated
6767
*/
@@ -72,7 +72,7 @@ class SteeringOdometry
7272
* \brief Updates the odometry class with latest wheels position
7373
* \param right_traction_wheel_pos Right traction wheel velocity [rad]
7474
* \param left_traction_wheel_pos Left traction wheel velocity [rad]
75-
* \param front_steer_pos Steer wheel position [rad]
75+
* \param steer_pos Steer wheel position [rad]
7676
* \param dt time difference to last call
7777
* \return true if the odometry is actually updated
7878
*/
@@ -96,7 +96,7 @@ class SteeringOdometry
9696
/**
9797
* \brief Updates the odometry class with latest wheels position
9898
* \param traction_wheel_vel Traction wheel velocity [rad/s]
99-
* \param front_steer_pos Steer wheel position [rad]
99+
* \param steer_pos Steer wheel position [rad]
100100
* \param dt time difference to last call
101101
* \return true if the odometry is actually updated
102102
*/
@@ -107,7 +107,7 @@ class SteeringOdometry
107107
* \brief Updates the odometry class with latest wheels position
108108
* \param right_traction_wheel_vel Right traction wheel velocity [rad/s]
109109
* \param left_traction_wheel_vel Left traction wheel velocity [rad/s]
110-
* \param front_steer_pos Steer wheel position [rad]
110+
* \param steer_pos Steer wheel position [rad]
111111
* \param dt time difference to last call
112112
* \return true if the odometry is actually updated
113113
*/
@@ -130,11 +130,11 @@ class SteeringOdometry
130130

131131
/**
132132
* \brief Updates the odometry class with latest velocity command
133-
* \param linear Linear velocity [m/s]
134-
* \param angular Angular velocity [rad/s]
135-
* \param time Current time
133+
* \param v_bx Linear velocity [m/s]
134+
* \param omega_bz Angular velocity [rad/s]
135+
* \param dt time difference to last call
136136
*/
137-
void update_open_loop(const double linear, const double angular, const double dt);
137+
void update_open_loop(const double v_bx, const double omega_bz, const double dt);
138138

139139
/**
140140
* \brief Set odometry type
@@ -175,22 +175,23 @@ class SteeringOdometry
175175
/**
176176
* \brief Sets the wheel parameters: radius, separation and wheelbase
177177
*/
178-
void set_wheel_params(double wheel_radius, double wheelbase = 0.0, double wheel_track = 0.0);
178+
void set_wheel_params(
179+
const double wheel_radius, const double wheelbase = 0.0, const double wheel_track = 0.0);
179180

180181
/**
181182
* \brief Velocity rolling window size setter
182183
* \param velocity_rolling_window_size Velocity rolling window size
183184
*/
184-
void set_velocity_rolling_window_size(size_t velocity_rolling_window_size);
185+
void set_velocity_rolling_window_size(const size_t velocity_rolling_window_size);
185186

186187
/**
187188
* \brief Calculates inverse kinematics for the desired linear and angular velocities
188-
* \param Vx Desired linear velocity [m/s]
189-
* \param theta_dot Desired angular velocity [rad/s]
189+
* \param v_bx Desired linear velocity of the robot in x_b-axis direction
190+
* \param omega_bz Desired angular velocity of the robot around x_z-axis
190191
* \return Tuple of velocity commands and steering commands
191192
*/
192193
std::tuple<std::vector<double>, std::vector<double>> get_commands(
193-
const double Vx, const double theta_dot);
194+
const double v_bx, const double omega_bz);
194195

195196
/**
196197
* \brief Reset poses, heading, and accumulators
@@ -199,35 +200,35 @@ class SteeringOdometry
199200

200201
private:
201202
/**
202-
* \brief Uses precomputed linear and angular velocities to compute dometry and update
203-
* accumulators \param linear Linear velocity [m] (linear displacement, i.e. m/s * dt)
204-
* computed by previous odometry method \param angular Angular velocity [rad] (angular
205-
* displacement, i.e. m/s * dt) computed by previous odometry method
203+
* \brief Uses precomputed linear and angular velocities to compute odometry
204+
* \param v_bx Linear velocity [m/s]
205+
* \param omega_bz Angular velocity [rad/s]
206+
* \param dt time difference to last call
206207
*/
207-
bool update_odometry(const double linear_velocity, const double angular, const double dt);
208+
bool update_odometry(const double v_bx, const double omega_bz, const double dt);
208209

209210
/**
210211
* \brief Integrates the velocities (linear and angular) using 2nd order Runge-Kutta
211-
* \param linear Linear velocity [m] (linear displacement, i.e. m/s * dt) computed by
212-
* encoders \param angular Angular velocity [rad] (angular displacement, i.e. m/s * dt) computed
213-
* by encoders
212+
* \param v_bx Linear velocity [m/s]
213+
* \param omega_bz Angular velocity [rad/s]
214+
* \param dt time difference to last call
214215
*/
215-
void integrate_runge_kutta_2(double linear, double angular);
216+
void integrate_runge_kutta_2(const double v_bx, const double omega_bz, const double dt);
216217

217218
/**
218-
* \brief Integrates the velocities (linear and angular) using exact method
219-
* \param linear Linear velocity [m] (linear displacement, i.e. m/s * dt) computed by
220-
* encoders \param angular Angular velocity [rad] (angular displacement, i.e. m/s * dt) computed
221-
* by encoders
219+
* \brief Integrates the velocities (linear and angular)
220+
* \param v_bx Linear velocity [m/s]
221+
* \param omega_bz Angular velocity [rad/s]
222+
* \param dt time difference to last call
222223
*/
223-
void integrate_exact(double linear, double angular);
224+
void integrate_fk(const double v_bx, const double omega_bz, const double dt);
224225

225226
/**
226-
* \brief Calculates steering angle from the desired translational and rotational velocity
227-
* \param Vx Linear velocity [m]
228-
* \param theta_dot Angular velocity [rad]
227+
* \brief Calculates steering angle from the desired twist
228+
* \param v_bx Linear velocity of the robot in x_b-axis direction
229+
* \param omega_bz Angular velocity of the robot around x_z-axis
229230
*/
230-
double convert_trans_rot_vel_to_steering_angle(double Vx, double theta_dot);
231+
double convert_twist_to_steering_angle(const double v_bx, const double omega_bz);
231232

232233
/**
233234
* \brief Reset linear and angular accumulators

0 commit comments

Comments
 (0)