Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(timeout): do not reset steer wheels to 0. on timeout #1289

Merged
merged 5 commits into from
Oct 1, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions doc/release_notes.rst
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,7 @@ steering_controllers_library
********************************
* 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>`_).
* A fix for Ackermann steering odometry was added (`#921 <https://github.com/ros-controls/ros2_controllers/pull/921>`_).
* Do not reset the steering wheels to ``0.0`` on timeout (`#1289 <https://github.com/ros-controls/ros2_controllers/pull/1289>`_).

tricycle_controller
************************
Expand Down
29 changes: 9 additions & 20 deletions steering_controllers_library/src/steering_controllers_library.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -355,26 +355,11 @@ controller_interface::return_type SteeringControllersLibrary::update_reference_f
const rclcpp::Time & time, const rclcpp::Duration & /*period*/)
{
auto current_ref = *(input_ref_.readFromRT());
const auto age_of_last_command = time - (current_ref)->header.stamp;

// send message only if there is no timeout
if (age_of_last_command <= ref_timeout_ || ref_timeout_ == rclcpp::Duration::from_seconds(0))
if (!std::isnan(current_ref->twist.linear.x) && !std::isnan(current_ref->twist.angular.z))
{
if (!std::isnan(current_ref->twist.linear.x) && !std::isnan(current_ref->twist.angular.z))
{
reference_interfaces_[0] = current_ref->twist.linear.x;
reference_interfaces_[1] = current_ref->twist.angular.z;
}
}
else
{
if (!std::isnan(current_ref->twist.linear.x) && !std::isnan(current_ref->twist.angular.z))
{
reference_interfaces_[0] = 0.0;
reference_interfaces_[1] = 0.0;
current_ref->twist.linear.x = std::numeric_limits<double>::quiet_NaN();
current_ref->twist.angular.z = std::numeric_limits<double>::quiet_NaN();
}
reference_interfaces_[0] = current_ref->twist.linear.x;
reference_interfaces_[1] = current_ref->twist.angular.z;
}

return controller_interface::return_type::OK;
Expand All @@ -396,13 +381,17 @@ controller_interface::return_type SteeringControllersLibrary::update_and_write_c
last_linear_velocity_ = reference_interfaces_[0];
last_angular_velocity_ = reference_interfaces_[1];

const auto age_of_last_command = time - (*(input_ref_.readFromRT()))->header.stamp;
const auto timeout =
age_of_last_command > ref_timeout_ && ref_timeout_ != rclcpp::Duration::from_seconds(0);

auto [traction_commands, steering_commands] =
odometry_.get_commands(last_linear_velocity_, last_angular_velocity_, params_.open_loop);
if (params_.front_steering)
{
for (size_t i = 0; i < params_.rear_wheels_names.size(); i++)
{
command_interfaces_[i].set_value(traction_commands[i]);
command_interfaces_[i].set_value(timeout ? 0. : traction_commands[i]);
}
for (size_t i = 0; i < params_.front_wheels_names.size(); i++)
{
Expand All @@ -414,7 +403,7 @@ controller_interface::return_type SteeringControllersLibrary::update_and_write_c
{
for (size_t i = 0; i < params_.front_wheels_names.size(); i++)
{
command_interfaces_[i].set_value(traction_commands[i]);
command_interfaces_[i].set_value(timeout ? 0. : traction_commands[i]);
}
for (size_t i = 0; i < params_.rear_wheels_names.size(); i++)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -133,19 +133,22 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout)
{
EXPECT_TRUE(std::isnan(interface));
}
EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromNonRT()))->twist.linear.x));
EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromNonRT()))->twist.angular.z));
ASSERT_EQ((*(controller_->input_ref_.readFromNonRT()))->twist.linear.x, TEST_LINEAR_VELOCITY_X);
ASSERT_EQ((*(controller_->input_ref_.readFromNonRT()))->twist.angular.z, TEST_ANGULAR_VELOCITY_Z);

EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[0]));
for (const auto & interface : controller_->reference_interfaces_)
{
EXPECT_TRUE(std::isnan(interface));
}

for (size_t i = 0; i < controller_->command_interfaces_.size(); ++i)
{
EXPECT_EQ(controller_->command_interfaces_[i].get_value(), 0);
}
// Wheel velocities should reset to 0
EXPECT_EQ(controller_->command_interfaces_[0].get_value(), 0);
EXPECT_EQ(controller_->command_interfaces_[1].get_value(), 0);

// Steer angles should not reset
EXPECT_NEAR(controller_->command_interfaces_[2].get_value(), 0.575875, 1e-6);
EXPECT_NEAR(controller_->command_interfaces_[3].get_value(), 0.575875, 1e-6);

// case 2 position_feedback = true
controller_->params_.position_feedback = true;
Expand Down Expand Up @@ -174,19 +177,22 @@ TEST_F(SteeringControllersLibraryTest, test_both_update_methods_for_ref_timeout)
{
EXPECT_TRUE(std::isnan(interface));
}
EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromNonRT()))->twist.linear.x));
EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromNonRT()))->twist.angular.z));
ASSERT_EQ((*(controller_->input_ref_.readFromNonRT()))->twist.linear.x, TEST_LINEAR_VELOCITY_X);
ASSERT_EQ((*(controller_->input_ref_.readFromNonRT()))->twist.angular.z, TEST_ANGULAR_VELOCITY_Z);

EXPECT_TRUE(std::isnan(controller_->reference_interfaces_[0]));
for (const auto & interface : controller_->reference_interfaces_)
{
EXPECT_TRUE(std::isnan(interface));
}

for (size_t i = 0; i < controller_->command_interfaces_.size(); ++i)
{
EXPECT_EQ(controller_->command_interfaces_[i].get_value(), 0);
}
// Wheel velocities should reset to 0
EXPECT_EQ(controller_->command_interfaces_[0].get_value(), 0);
EXPECT_EQ(controller_->command_interfaces_[1].get_value(), 0);

// Steer angles should not reset
EXPECT_NEAR(controller_->command_interfaces_[2].get_value(), 0.575875, 1e-6);
EXPECT_NEAR(controller_->command_interfaces_[3].get_value(), 0.575875, 1e-6);
}

int main(int argc, char ** argv)
Expand Down
Loading