Skip to content

Commit 5f1fd99

Browse files
christophfroehlichmergify[bot]
authored andcommitted
Fix steering controllers library kinematics (#1150)
(cherry picked from commit df04492)
1 parent 5d8a1f5 commit 5f1fd99

File tree

7 files changed

+197
-50
lines changed

7 files changed

+197
-50
lines changed

ackermann_steering_controller/test/test_ackermann_steering_controller.cpp

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -173,6 +173,7 @@ TEST_F(AckermannSteeringControllerTest, test_update_logic)
173173
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
174174
controller_interface::return_type::OK);
175175

176+
// we test with open_loop=false, but steering angle was not updated (is zero) -> same commands
176177
EXPECT_NEAR(
177178
controller_->command_interfaces_[CMD_TRACTION_RIGHT_WHEEL].get_value(), 0.22222222222222224,
178179
COMMON_THRESHOLD);
@@ -211,8 +212,9 @@ TEST_F(AckermannSteeringControllerTest, test_update_logic_chained)
211212
ASSERT_EQ(
212213
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
213214
controller_interface::return_type::OK);
214-
EXPECT_NEAR(
215215

216+
// we test with open_loop=false, but steering angle was not updated (is zero) -> same commands
217+
EXPECT_NEAR(
216218
controller_->command_interfaces_[STATE_TRACTION_RIGHT_WHEEL].get_value(), 0.22222222222222224,
217219
COMMON_THRESHOLD);
218220
EXPECT_NEAR(
@@ -261,6 +263,7 @@ TEST_F(AckermannSteeringControllerTest, receive_message_and_publish_updated_stat
261263
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
262264
controller_interface::return_type::OK);
263265

266+
// we test with open_loop=false, but steering angle was not updated (is zero) -> same commands
264267
EXPECT_NEAR(
265268
controller_->command_interfaces_[CMD_TRACTION_RIGHT_WHEEL].get_value(), 0.22222222222222224,
266269
COMMON_THRESHOLD);
@@ -276,6 +279,7 @@ TEST_F(AckermannSteeringControllerTest, receive_message_and_publish_updated_stat
276279

277280
subscribe_and_get_messages(msg);
278281

282+
// we test with open_loop=false, but steering angle was not updated (is zero) -> same commands
279283
EXPECT_NEAR(
280284
msg.linear_velocity_command[CMD_TRACTION_RIGHT_WHEEL], 0.22222222222222224, COMMON_THRESHOLD);
281285
EXPECT_NEAR(

bicycle_steering_controller/test/test_bicycle_steering_controller.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -158,7 +158,7 @@ TEST_F(BicycleSteeringControllerTest, test_update_logic)
158158
controller_interface::return_type::OK);
159159

160160
EXPECT_NEAR(
161-
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_value(), 0.253221, COMMON_THRESHOLD);
161+
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_value(), 0.1 / 0.45, COMMON_THRESHOLD);
162162
EXPECT_NEAR(
163163
controller_->command_interfaces_[CMD_STEER_WHEEL].get_value(), 1.4179821977774734,
164164
COMMON_THRESHOLD);
@@ -190,7 +190,7 @@ TEST_F(BicycleSteeringControllerTest, test_update_logic_chained)
190190
controller_interface::return_type::OK);
191191

192192
EXPECT_NEAR(
193-
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_value(), 0.253221, COMMON_THRESHOLD);
193+
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_value(), 0.1 / 0.45, COMMON_THRESHOLD);
194194
EXPECT_NEAR(
195195
controller_->command_interfaces_[CMD_STEER_WHEEL].get_value(), 1.4179821977774734,
196196
COMMON_THRESHOLD);
@@ -237,22 +237,22 @@ TEST_F(BicycleSteeringControllerTest, receive_message_and_publish_updated_status
237237
EXPECT_EQ(msg.linear_velocity_command[0], 1.1);
238238
EXPECT_EQ(msg.steering_angle_command[0], 2.2);
239239

240-
publish_commands();
240+
publish_commands(0.1, 0.2);
241241
ASSERT_TRUE(controller_->wait_for_commands(executor));
242242

243243
ASSERT_EQ(
244244
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
245245
controller_interface::return_type::OK);
246246

247247
EXPECT_NEAR(
248-
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_value(), 0.253221, COMMON_THRESHOLD);
248+
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_value(), 0.1 / 0.45, COMMON_THRESHOLD);
249249
EXPECT_NEAR(
250250
controller_->command_interfaces_[CMD_STEER_WHEEL].get_value(), 1.4179821977774734,
251251
COMMON_THRESHOLD);
252252

253253
subscribe_and_get_messages(msg);
254254

255-
EXPECT_NEAR(msg.linear_velocity_command[0], 0.253221, COMMON_THRESHOLD);
255+
EXPECT_NEAR(msg.linear_velocity_command[0], 0.1 / 0.45, COMMON_THRESHOLD);
256256
EXPECT_NEAR(msg.steering_angle_command[0], 1.4179821977774734, COMMON_THRESHOLD);
257257
}
258258

steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp

Lines changed: 16 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#ifndef STEERING_CONTROLLERS_LIBRARY__STEERING_ODOMETRY_HPP_
1919
#define STEERING_CONTROLLERS_LIBRARY__STEERING_ODOMETRY_HPP_
2020

21+
#include <cmath>
2122
#include <tuple>
2223
#include <vector>
2324

@@ -31,6 +32,9 @@ namespace steering_odometry
3132
const unsigned int BICYCLE_CONFIG = 0;
3233
const unsigned int TRICYCLE_CONFIG = 1;
3334
const unsigned int ACKERMANN_CONFIG = 2;
35+
36+
inline bool is_close_to_zero(double val) { return std::fabs(val) < 1e-6; }
37+
3438
/**
3539
* \brief The Odometry class handles odometry readings
3640
* (2D pose and velocity with related timestamp)
@@ -183,10 +187,11 @@ class SteeringOdometry
183187
* \brief Calculates inverse kinematics for the desired linear and angular velocities
184188
* \param v_bx Desired linear velocity of the robot in x_b-axis direction
185189
* \param omega_bz Desired angular velocity of the robot around x_z-axis
190+
* \param open_loop If false, the IK will be calculated using measured steering angle
186191
* \return Tuple of velocity commands and steering commands
187192
*/
188193
std::tuple<std::vector<double>, std::vector<double>> get_commands(
189-
const double v_bx, const double omega_bz);
194+
const double v_bx, const double omega_bz, const bool open_loop = true);
190195

191196
/**
192197
* \brief Reset poses, heading, and accumulators
@@ -225,6 +230,16 @@ class SteeringOdometry
225230
*/
226231
double convert_twist_to_steering_angle(const double v_bx, const double omega_bz);
227232

233+
/**
234+
* \brief Calculates linear velocity of a robot with double traction axle
235+
* \param right_traction_wheel_vel Right traction wheel velocity [rad/s]
236+
* \param left_traction_wheel_vel Left traction wheel velocity [rad/s]
237+
* \param steer_pos Steer wheel position [rad]
238+
*/
239+
double get_linear_velocity_double_traction_axle(
240+
const double right_traction_wheel_vel, const double left_traction_wheel_vel,
241+
const double steer_pos);
242+
228243
/**
229244
* \brief Reset linear and angular accumulators
230245
*/

steering_controllers_library/src/steering_controllers_library.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -452,7 +452,7 @@ controller_interface::return_type SteeringControllersLibrary::update_and_write_c
452452
last_angular_velocity_ = reference_interfaces_[1];
453453

454454
auto [traction_commands, steering_commands] =
455-
odometry_.get_commands(last_linear_velocity_, last_angular_velocity_);
455+
odometry_.get_commands(last_linear_velocity_, last_angular_velocity_, params_.open_loop);
456456
if (params_.front_steering)
457457
{
458458
for (size_t i = 0; i < params_.rear_wheels_names.size(); i++)

steering_controllers_library/src/steering_odometry.cpp

Lines changed: 60 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121

2222
#include <cmath>
2323
#include <iostream>
24+
#include <limits>
2425

2526
namespace steering_odometry
2627
{
@@ -128,13 +129,26 @@ bool SteeringOdometry::update_from_velocity(
128129
return update_odometry(linear_velocity, angular_velocity, dt);
129130
}
130131

132+
double SteeringOdometry::get_linear_velocity_double_traction_axle(
133+
const double right_traction_wheel_vel, const double left_traction_wheel_vel,
134+
const double steer_pos)
135+
{
136+
double turning_radius = wheelbase_ / std::tan(steer_pos);
137+
// overdetermined, we take the average
138+
double vel_r = right_traction_wheel_vel * wheel_radius_ * turning_radius /
139+
(turning_radius + wheel_track_ * 0.5);
140+
double vel_l = left_traction_wheel_vel * wheel_radius_ * turning_radius /
141+
(turning_radius - wheel_track_ * 0.5);
142+
return (vel_r + vel_l) * 0.5;
143+
}
144+
131145
bool SteeringOdometry::update_from_velocity(
132146
const double right_traction_wheel_vel, const double left_traction_wheel_vel,
133147
const double steer_pos, const double dt)
134148
{
135-
double linear_velocity =
136-
(right_traction_wheel_vel + left_traction_wheel_vel) * wheel_radius_ * 0.5;
137149
steer_pos_ = steer_pos;
150+
double linear_velocity = get_linear_velocity_double_traction_axle(
151+
right_traction_wheel_vel, left_traction_wheel_vel, steer_pos_);
138152

139153
const double angular_velocity = std::tan(steer_pos_) * linear_velocity / wheelbase_;
140154

@@ -145,10 +159,18 @@ bool SteeringOdometry::update_from_velocity(
145159
const double right_traction_wheel_vel, const double left_traction_wheel_vel,
146160
const double right_steer_pos, const double left_steer_pos, const double dt)
147161
{
148-
steer_pos_ = (right_steer_pos + left_steer_pos) * 0.5;
149-
double linear_velocity =
150-
(right_traction_wheel_vel + left_traction_wheel_vel) * wheel_radius_ * 0.5;
151-
const double angular_velocity = std::tan(steer_pos_) * linear_velocity / wheelbase_;
162+
// overdetermined, we take the average
163+
const double right_steer_pos_est = std::atan(
164+
wheelbase_ * std::tan(right_steer_pos) /
165+
(wheelbase_ - wheel_track_ / 2 * std::tan(right_steer_pos)));
166+
const double left_steer_pos_est = std::atan(
167+
wheelbase_ * std::tan(left_steer_pos) /
168+
(wheelbase_ + wheel_track_ / 2 * std::tan(left_steer_pos)));
169+
steer_pos_ = (right_steer_pos_est + left_steer_pos_est) * 0.5;
170+
171+
double linear_velocity = get_linear_velocity_double_traction_axle(
172+
right_traction_wheel_vel, left_traction_wheel_vel, steer_pos_);
173+
const double angular_velocity = steer_pos_ * linear_velocity / wheelbase_;
152174

153175
return update_odometry(linear_velocity, angular_velocity, dt);
154176
}
@@ -181,30 +203,41 @@ void SteeringOdometry::set_odometry_type(const unsigned int type) { config_type_
181203

182204
double SteeringOdometry::convert_twist_to_steering_angle(double v_bx, double omega_bz)
183205
{
184-
if (omega_bz == 0 || v_bx == 0)
206+
if (fabs(v_bx) < std::numeric_limits<float>::epsilon())
185207
{
186-
return 0;
208+
// avoid division by zero
209+
return 0.;
187210
}
188211
return std::atan(omega_bz * wheelbase_ / v_bx);
189212
}
190213

191214
std::tuple<std::vector<double>, std::vector<double>> SteeringOdometry::get_commands(
192-
const double v_bx, const double omega_bz)
215+
const double v_bx, const double omega_bz, const bool open_loop)
193216
{
194217
// desired wheel speed and steering angle of the middle of traction and steering axis
195-
double Ws, phi;
218+
double Ws, phi, phi_IK = steer_pos_;
196219

220+
#if 0
197221
if (v_bx == 0 && omega_bz != 0)
198222
{
199-
// TODO(anyone) would be only valid if traction is on the steering axis -> tricycle_controller
223+
// TODO(anyone) this would be only possible if traction is on the steering axis
200224
phi = omega_bz > 0 ? M_PI_2 : -M_PI_2;
201225
Ws = abs(omega_bz) * wheelbase_ / wheel_radius_;
202226
}
203227
else
204228
{
205-
phi = SteeringOdometry::convert_twist_to_steering_angle(v_bx, omega_bz);
206-
Ws = v_bx / (wheel_radius_ * std::cos(steer_pos_));
229+
// TODO(anyone) this would be valid only if traction is on the steering axis
230+
Ws = v_bx / (wheel_radius_ * std::cos(phi_IK)); // using the measured steering angle
231+
}
232+
#endif
233+
// steering angle
234+
phi = SteeringOdometry::convert_twist_to_steering_angle(v_bx, omega_bz);
235+
if (open_loop)
236+
{
237+
phi_IK = phi;
207238
}
239+
// wheel speed
240+
Ws = v_bx / wheel_radius_;
208241

209242
if (config_type_ == BICYCLE_CONFIG)
210243
{
@@ -216,32 +249,37 @@ std::tuple<std::vector<double>, std::vector<double>> SteeringOdometry::get_comma
216249
{
217250
std::vector<double> traction_commands;
218251
std::vector<double> steering_commands;
219-
if (fabs(steer_pos_) < 1e-6)
252+
// double-traction axle
253+
if (is_close_to_zero(phi_IK))
220254
{
255+
// avoid division by zero
221256
traction_commands = {Ws, Ws};
222257
}
223258
else
224259
{
225-
const double turning_radius = wheelbase_ / std::tan(steer_pos_);
260+
const double turning_radius = wheelbase_ / std::tan(phi_IK);
226261
const double Wr = Ws * (turning_radius + wheel_track_ * 0.5) / turning_radius;
227262
const double Wl = Ws * (turning_radius - wheel_track_ * 0.5) / turning_radius;
228263
traction_commands = {Wr, Wl};
229264
}
265+
// simple steering
230266
steering_commands = {phi};
231267
return std::make_tuple(traction_commands, steering_commands);
232268
}
233269
else if (config_type_ == ACKERMANN_CONFIG)
234270
{
235271
std::vector<double> traction_commands;
236272
std::vector<double> steering_commands;
237-
if (fabs(steer_pos_) < 1e-6)
273+
if (is_close_to_zero(phi_IK))
238274
{
275+
// avoid division by zero
239276
traction_commands = {Ws, Ws};
277+
// shortcut, no steering
240278
steering_commands = {phi, phi};
241279
}
242280
else
243281
{
244-
const double turning_radius = wheelbase_ / std::tan(steer_pos_);
282+
const double turning_radius = wheelbase_ / std::tan(phi_IK);
245283
const double Wr = Ws * (turning_radius + wheel_track_ * 0.5) / turning_radius;
246284
const double Wl = Ws * (turning_radius - wheel_track_ * 0.5) / turning_radius;
247285
traction_commands = {Wr, Wl};
@@ -279,8 +317,8 @@ void SteeringOdometry::integrate_runge_kutta_2(
279317
const double theta_mid = heading_ + omega_bz * 0.5 * dt;
280318

281319
// Use the intermediate values to update the state
282-
x_ += v_bx * cos(theta_mid) * dt;
283-
y_ += v_bx * sin(theta_mid) * dt;
320+
x_ += v_bx * std::cos(theta_mid) * dt;
321+
y_ += v_bx * std::sin(theta_mid) * dt;
284322
heading_ += omega_bz * dt;
285323
}
286324

@@ -289,7 +327,7 @@ void SteeringOdometry::integrate_fk(const double v_bx, const double omega_bz, co
289327
const double delta_x_b = v_bx * dt;
290328
const double delta_theta = omega_bz * dt;
291329

292-
if (fabs(delta_theta) < 1e-6)
330+
if (is_close_to_zero(delta_theta))
293331
{
294332
/// Runge-Kutta 2nd Order (should solve problems when omega_bz is zero):
295333
integrate_runge_kutta_2(v_bx, omega_bz, dt);
@@ -300,8 +338,8 @@ void SteeringOdometry::integrate_fk(const double v_bx, const double omega_bz, co
300338
const double heading_old = heading_;
301339
const double R = delta_x_b / delta_theta;
302340
heading_ += delta_theta;
303-
x_ += R * (sin(heading_) - sin(heading_old));
304-
y_ += -R * (cos(heading_) - cos(heading_old));
341+
x_ += R * (sin(heading_) - std::sin(heading_old));
342+
y_ += -R * (cos(heading_) - std::cos(heading_old));
305343
}
306344
}
307345

0 commit comments

Comments
 (0)