Skip to content

Commit 0438a1e

Browse files
steering_controllers_library: Add reduce_wheel_speed_until_steering_reached parameter (#1314)
1 parent 337127a commit 0438a1e

File tree

6 files changed

+189
-7
lines changed

6 files changed

+189
-7
lines changed

doc/release_notes.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -66,6 +66,7 @@ steering_controllers_library
6666
* Changing default int values to double in steering controller's yaml file. The controllers should now initialize successfully without specifying these parameters (`#927 <https://github.com/ros-controls/ros2_controllers/pull/927>`_).
6767
* A fix for Ackermann steering odometry was added (`#921 <https://github.com/ros-controls/ros2_controllers/pull/921>`_).
6868
* Do not reset the steering wheels to ``0.0`` on timeout (`#1289 <https://github.com/ros-controls/ros2_controllers/pull/1289>`_).
69+
* New parameter ``reduce_wheel_speed_until_steering_reached`` was added. If set to true, then the wheel speed(s) is reduced until the steering angle has been reached. Only considered if ``open_loop = false`` (`#1314 <https://github.com/ros-controls/ros2_controllers/pull/1314>`_).
6970

7071
tricycle_controller
7172
************************

steering_controllers_library/include/steering_controllers_library/steering_odometry.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -192,10 +192,13 @@ class SteeringOdometry
192192
* \param v_bx Desired linear velocity of the robot in x_b-axis direction
193193
* \param omega_bz Desired angular velocity of the robot around x_z-axis
194194
* \param open_loop If false, the IK will be calculated using measured steering angle
195+
* \param reduce_wheel_speed_until_steering_reached Reduce wheel speed until the steering angle
196+
* has been reached
195197
* \return Tuple of velocity commands and steering commands
196198
*/
197199
std::tuple<std::vector<double>, std::vector<double>> get_commands(
198-
const double v_bx, const double omega_bz, const bool open_loop = true);
200+
const double v_bx, const double omega_bz, const bool open_loop = true,
201+
const bool reduce_wheel_speed_until_steering_reached = false);
199202

200203
/**
201204
* \brief Reset poses, heading, and accumulators

steering_controllers_library/src/steering_controllers_library.cpp

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -353,7 +353,7 @@ controller_interface::CallbackReturn SteeringControllersLibrary::on_deactivate(
353353
}
354354

355355
controller_interface::return_type SteeringControllersLibrary::update_reference_from_subscribers(
356-
const rclcpp::Time & time, const rclcpp::Duration & /*period*/)
356+
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
357357
{
358358
auto current_ref = *(input_ref_.readFromRT());
359359

@@ -386,8 +386,10 @@ controller_interface::return_type SteeringControllersLibrary::update_and_write_c
386386
const auto timeout =
387387
age_of_last_command > ref_timeout_ && ref_timeout_ != rclcpp::Duration::from_seconds(0);
388388

389-
auto [traction_commands, steering_commands] =
390-
odometry_.get_commands(last_linear_velocity_, last_angular_velocity_, params_.open_loop);
389+
auto [traction_commands, steering_commands] = odometry_.get_commands(
390+
last_linear_velocity_, last_angular_velocity_, params_.open_loop,
391+
params_.reduce_wheel_speed_until_steering_reached);
392+
391393
if (params_.front_steering)
392394
{
393395
for (size_t i = 0; i < params_.rear_wheels_names.size(); i++)

steering_controllers_library/src/steering_controllers_library.yaml

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -63,6 +63,13 @@ steering_controllers_library:
6363
read_only: false,
6464
}
6565

66+
reduce_wheel_speed_until_steering_reached: {
67+
type: bool,
68+
default_value: false,
69+
description: "Reduce wheel speed until the steering angle has been reached.",
70+
read_only: false,
71+
}
72+
6673
velocity_rolling_window_size: {
6774
type: int,
6875
default_value: 10,

steering_controllers_library/src/steering_odometry.cpp

Lines changed: 25 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -217,7 +217,8 @@ double SteeringOdometry::convert_twist_to_steering_angle(double v_bx, double ome
217217
}
218218

219219
std::tuple<std::vector<double>, std::vector<double>> SteeringOdometry::get_commands(
220-
const double v_bx, const double omega_bz, const bool open_loop)
220+
const double v_bx, const double omega_bz, const bool open_loop,
221+
const bool reduce_wheel_speed_until_steering_reached)
221222
{
222223
// desired wheel speed and steering angle of the middle of traction and steering axis
223224
double Ws, phi, phi_IK = steer_pos_;
@@ -244,6 +245,29 @@ std::tuple<std::vector<double>, std::vector<double>> SteeringOdometry::get_comma
244245
// wheel speed
245246
Ws = v_bx / wheel_radius_;
246247

248+
if (!open_loop && reduce_wheel_speed_until_steering_reached)
249+
{
250+
// Reduce wheel speed until the target angle has been reached
251+
double phi_delta = abs(steer_pos_ - phi);
252+
double scale;
253+
const double min_phi_delta = M_PI / 6.;
254+
if (phi_delta < min_phi_delta)
255+
{
256+
scale = 1;
257+
}
258+
else if (phi_delta >= 1.5608)
259+
{
260+
// cos(1.5608) = 0.01
261+
scale = 0.01 / cos(min_phi_delta);
262+
}
263+
else
264+
{
265+
// TODO(anyone): find the best function, e.g convex power functions
266+
scale = cos(phi_delta) / cos(min_phi_delta);
267+
}
268+
Ws *= scale;
269+
}
270+
247271
if (config_type_ == BICYCLE_CONFIG)
248272
{
249273
std::vector<double> traction_commands = {Ws};

steering_controllers_library/test/test_steering_odometry.cpp

Lines changed: 147 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -116,13 +116,59 @@ TEST(TestSteeringOdometry, ackermann_IK_right)
116116
odom.update_from_position(0., -0.2, 1.); // assume already turn
117117
auto cmd = odom.get_commands(1., -0.1, false);
118118
auto cmd0 = std::get<0>(cmd); // vel
119-
EXPECT_LT(cmd0[0], cmd0[1]); // right (inner) < left outer)
119+
EXPECT_LT(cmd0[0], cmd0[1]); // right (inner) < left (outer)
120120
EXPECT_GT(cmd0[0], 0);
121121
auto cmd1 = std::get<1>(cmd); // steer
122122
EXPECT_GT(std::abs(cmd1[0]), std::abs(cmd1[1])); // abs right (inner) > abs left (outer)
123123
EXPECT_LT(cmd1[0], 0);
124124
}
125125

126+
TEST(TestSteeringOdometry, ackermann_IK_right_steering_limited)
127+
{
128+
steering_odometry::SteeringOdometry odom(1);
129+
odom.set_wheel_params(1., 2., 1.);
130+
odom.set_odometry_type(steering_odometry::ACKERMANN_CONFIG);
131+
132+
{
133+
odom.update_from_position(0., -0.785, 1.); // already steered
134+
auto cmd = odom.get_commands(1., -0.5, false, true);
135+
auto vel_cmd_steered = std::get<0>(cmd); // vel
136+
EXPECT_LT(vel_cmd_steered[0], vel_cmd_steered[1]); // right (inner) < left (outer)
137+
EXPECT_GT(vel_cmd_steered[0], 0);
138+
auto cmd1 = std::get<1>(cmd); // steer
139+
EXPECT_GT(std::abs(cmd1[0]), std::abs(cmd1[1])); // abs right (inner) > abs left (outer)
140+
EXPECT_LT(cmd1[0], 0);
141+
}
142+
143+
std::vector<double> vel_cmd_not_steered;
144+
{
145+
odom.update_from_position(0., -0.1, 1.); // not fully steered
146+
auto cmd = odom.get_commands(1., -0.5, false, false);
147+
vel_cmd_not_steered = std::get<0>(cmd); // vel
148+
EXPECT_LT(vel_cmd_not_steered[0], vel_cmd_not_steered[1]); // right (inner) < left (outer)
149+
EXPECT_GT(vel_cmd_not_steered[0], 0);
150+
auto cmd1 = std::get<1>(cmd); // steer
151+
EXPECT_GT(std::abs(cmd1[0]), std::abs(cmd1[1])); // abs right (inner) > abs left (outer)
152+
EXPECT_LT(cmd1[0], 0);
153+
}
154+
155+
{
156+
odom.update_from_position(0., -0.1, 1.); // not fully steered
157+
auto cmd = odom.get_commands(1., -0.5, false, true);
158+
auto cmd0 = std::get<0>(cmd); // vel
159+
EXPECT_LT(cmd0[0], cmd0[1]); // right (inner) < left (outer)
160+
EXPECT_GT(cmd0[0], 0);
161+
// vel should be less than vel_cmd_not_steered now
162+
for (size_t i = 0; i < cmd0.size(); ++i)
163+
{
164+
EXPECT_LT(cmd0[i], vel_cmd_not_steered[i]);
165+
}
166+
auto cmd1 = std::get<1>(cmd); // steer
167+
EXPECT_GT(std::abs(cmd1[0]), std::abs(cmd1[1])); // abs right (inner) > abs left (outer)
168+
EXPECT_LT(cmd1[0], 0);
169+
}
170+
}
171+
126172
// ----------------- bicycle -----------------
127173

128174
TEST(TestSteeringOdometry, bicycle_IK_linear)
@@ -164,6 +210,62 @@ TEST(TestSteeringOdometry, bicycle_IK_right)
164210
EXPECT_LT(cmd1[0], 0); // left steering
165211
}
166212

213+
TEST(TestSteeringOdometry, bicycle_IK_right_steering_limited)
214+
{
215+
steering_odometry::SteeringOdometry odom(1);
216+
odom.set_wheel_params(1., 2., 1.);
217+
odom.set_odometry_type(steering_odometry::BICYCLE_CONFIG);
218+
219+
{
220+
odom.update_from_position(0., -0.785, 1.); // already steered
221+
auto cmd = odom.get_commands(1., -0.5, false, true);
222+
auto vel_cmd_steered = std::get<0>(cmd); // vel
223+
EXPECT_DOUBLE_EQ(vel_cmd_steered[0], 1.0); // equals linear
224+
auto cmd1 = std::get<1>(cmd); // steer
225+
EXPECT_LT(cmd1[0], 0);
226+
}
227+
228+
std::vector<double> vel_cmd_not_steered;
229+
{
230+
odom.update_from_position(0., -0.1, 1.); // not fully steered
231+
auto cmd = odom.get_commands(1., -0.5, false, false);
232+
vel_cmd_not_steered = std::get<0>(cmd); // vel
233+
EXPECT_DOUBLE_EQ(vel_cmd_not_steered[0], 1.0); // equals linear
234+
auto cmd1 = std::get<1>(cmd); // steer
235+
EXPECT_LT(cmd1[0], 0);
236+
}
237+
238+
std::vector<double> vel_cmd_not_steered_limited;
239+
{
240+
odom.update_from_position(0., -0.1, 1.); // not fully steered
241+
auto cmd = odom.get_commands(1., -0.5, false, true);
242+
vel_cmd_not_steered_limited = std::get<0>(cmd); // vel
243+
EXPECT_GT(vel_cmd_not_steered_limited[0], 0);
244+
// vel should be less than vel_cmd_not_steered now
245+
for (size_t i = 0; i < vel_cmd_not_steered_limited.size(); ++i)
246+
{
247+
EXPECT_LT(vel_cmd_not_steered_limited[i], vel_cmd_not_steered[i]);
248+
}
249+
auto cmd1 = std::get<1>(cmd); // steer
250+
EXPECT_LT(cmd1[0], 0);
251+
}
252+
253+
{
254+
// larger error -> check min of scale
255+
odom.update_from_position(0., M_PI, 1.); // not fully steered
256+
auto cmd = odom.get_commands(1., -0.5, false, true);
257+
auto cmd0 = std::get<0>(cmd); // vel
258+
EXPECT_GT(cmd0[0], 0);
259+
// vel should be less than vel_cmd_not_steered_limited now
260+
for (size_t i = 0; i < cmd0.size(); ++i)
261+
{
262+
EXPECT_LT(cmd0[i], vel_cmd_not_steered_limited[i]);
263+
}
264+
auto cmd1 = std::get<1>(cmd); // steer
265+
EXPECT_LT(cmd1[0], 0);
266+
}
267+
}
268+
167269
TEST(TestSteeringOdometry, bicycle_odometry)
168270
{
169271
steering_odometry::SteeringOdometry odom(1);
@@ -214,12 +316,55 @@ TEST(TestSteeringOdometry, tricycle_IK_right)
214316
odom.update_from_position(0., -0.2, 1.); // assume already turn
215317
auto cmd = odom.get_commands(1., -0.1, false);
216318
auto cmd0 = std::get<0>(cmd); // vel
217-
EXPECT_LT(cmd0[0], cmd0[1]); // right (inner) < left outer)
319+
EXPECT_LT(cmd0[0], cmd0[1]); // right (inner) < left (outer)
218320
EXPECT_GT(cmd0[0], 0);
219321
auto cmd1 = std::get<1>(cmd); // steer
220322
EXPECT_LT(cmd1[0], 0); // right steering
221323
}
222324

325+
TEST(TestSteeringOdometry, tricycle_IK_right_steering_limited)
326+
{
327+
steering_odometry::SteeringOdometry odom(1);
328+
odom.set_wheel_params(1., 2., 1.);
329+
odom.set_odometry_type(steering_odometry::TRICYCLE_CONFIG);
330+
331+
{
332+
odom.update_from_position(0., -0.785, 1.); // already steered
333+
auto cmd = odom.get_commands(1., -0.5, false, true);
334+
auto vel_cmd_steered = std::get<0>(cmd); // vel
335+
EXPECT_LT(vel_cmd_steered[0], vel_cmd_steered[1]); // right (inner) < left (outer)
336+
EXPECT_GT(vel_cmd_steered[0], 0);
337+
auto cmd1 = std::get<1>(cmd); // steer
338+
EXPECT_LT(cmd1[0], 0);
339+
}
340+
341+
std::vector<double> vel_cmd_not_steered;
342+
{
343+
odom.update_from_position(0., -0.1, 1.); // not fully steered
344+
auto cmd = odom.get_commands(1., -0.5, false, false);
345+
vel_cmd_not_steered = std::get<0>(cmd); // vel
346+
EXPECT_LT(vel_cmd_not_steered[0], vel_cmd_not_steered[1]); // right (inner) < left (outer)
347+
EXPECT_GT(vel_cmd_not_steered[0], 0);
348+
auto cmd1 = std::get<1>(cmd); // steer
349+
EXPECT_LT(cmd1[0], 0);
350+
}
351+
352+
{
353+
odom.update_from_position(0., -0.1, 1.); // not fully steered
354+
auto cmd = odom.get_commands(1., -0.5, false, true);
355+
auto cmd0 = std::get<0>(cmd); // vel
356+
EXPECT_LT(cmd0[0], cmd0[1]); // right (inner) < left (outer)
357+
EXPECT_GT(cmd0[0], 0);
358+
// vel should be less than vel_cmd_not_steered now
359+
for (size_t i = 0; i < cmd0.size(); ++i)
360+
{
361+
EXPECT_LT(cmd0[i], vel_cmd_not_steered[i]);
362+
}
363+
auto cmd1 = std::get<1>(cmd); // steer
364+
EXPECT_LT(cmd1[0], 0);
365+
}
366+
}
367+
223368
TEST(TestSteeringOdometry, tricycle_odometry)
224369
{
225370
steering_odometry::SteeringOdometry odom(1);

0 commit comments

Comments
 (0)