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

Use new handles API in ros2_controllers to fix deprecation warnings #1566

Open
wants to merge 13 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 3 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
Original file line number Diff line number Diff line change
Expand Up @@ -56,18 +56,39 @@ controller_interface::CallbackReturn AckermannSteeringController::configure_odom

bool AckermannSteeringController::update_odometry(const rclcpp::Duration & period)
{
auto logger = get_node()->get_logger();

if (params_.open_loop)
{
odometry_.update_open_loop(last_linear_velocity_, last_angular_velocity_, period.seconds());
}
else
{
const double traction_right_wheel_value =
state_interfaces_[STATE_TRACTION_RIGHT_WHEEL].get_value();
const double traction_left_wheel_value =
state_interfaces_[STATE_TRACTION_LEFT_WHEEL].get_value();
const double steering_right_position = state_interfaces_[STATE_STEER_RIGHT_WHEEL].get_value();
const double steering_left_position = state_interfaces_[STATE_STEER_LEFT_WHEEL].get_value();
const auto traction_right_wheel_value_op =
state_interfaces_[STATE_TRACTION_RIGHT_WHEEL].get_optional();
const auto traction_left_wheel_value_op =
state_interfaces_[STATE_TRACTION_LEFT_WHEEL].get_optional();
const auto steering_right_position_op =
state_interfaces_[STATE_STEER_RIGHT_WHEEL].get_optional();
const auto steering_left_position_op = state_interfaces_[STATE_STEER_LEFT_WHEEL].get_optional();

if (
!traction_right_wheel_value_op.has_value() || !traction_left_wheel_value_op.has_value() ||
!steering_right_position_op.has_value() || !steering_left_position_op.has_value())
{
RCLCPP_DEBUG(
logger,
"Unable to retrieve the data from right wheel or left wheel or right steering position or "
"left steering position!");

return true;
}

const double traction_right_wheel_value = traction_right_wheel_value_op.value();
const double traction_left_wheel_value = traction_left_wheel_value_op.value();
const double steering_right_position = steering_right_position_op.value();
const double steering_left_position = steering_left_position_op.value();

if (
std::isfinite(traction_right_wheel_value) && std::isfinite(traction_left_wheel_value) &&
std::isfinite(steering_right_position) && std::isfinite(steering_left_position))
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -143,9 +143,9 @@ TEST_F(AckermannSteeringControllerTest, reactivate_success)
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(std::isnan(controller_->command_interfaces_[0].get_value()));
ASSERT_TRUE(std::isnan(controller_->command_interfaces_[0].get_optional().value()));
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(std::isnan(controller_->command_interfaces_[0].get_value()));
ASSERT_TRUE(std::isnan(controller_->command_interfaces_[0].get_optional().value()));

ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
Expand Down Expand Up @@ -176,17 +176,17 @@ TEST_F(AckermannSteeringControllerTest, test_update_logic)

// we test with open_loop=false, but steering angle was not updated (is zero) -> same commands
EXPECT_NEAR(
controller_->command_interfaces_[CMD_TRACTION_RIGHT_WHEEL].get_value(), 0.22222222222222224,
COMMON_THRESHOLD);
controller_->command_interfaces_[CMD_TRACTION_RIGHT_WHEEL].get_optional().value(),
0.22222222222222224, COMMON_THRESHOLD);
EXPECT_NEAR(
controller_->command_interfaces_[CMD_TRACTION_LEFT_WHEEL].get_value(), 0.22222222222222224,
COMMON_THRESHOLD);
controller_->command_interfaces_[CMD_TRACTION_LEFT_WHEEL].get_optional().value(),
0.22222222222222224, COMMON_THRESHOLD);
EXPECT_NEAR(
controller_->command_interfaces_[CMD_STEER_RIGHT_WHEEL].get_value(), 1.4179821977774734,
COMMON_THRESHOLD);
controller_->command_interfaces_[CMD_STEER_RIGHT_WHEEL].get_optional().value(),
1.4179821977774734, COMMON_THRESHOLD);
EXPECT_NEAR(
controller_->command_interfaces_[CMD_STEER_LEFT_WHEEL].get_value(), 1.4179821977774734,
COMMON_THRESHOLD);
controller_->command_interfaces_[CMD_STEER_LEFT_WHEEL].get_optional().value(),
1.4179821977774734, COMMON_THRESHOLD);

EXPECT_FALSE(std::isnan((*(controller_->input_ref_.readFromRT()))->twist.linear.x));
EXPECT_EQ(controller_->reference_interfaces_.size(), joint_reference_interfaces_.size());
Expand Down Expand Up @@ -216,17 +216,17 @@ TEST_F(AckermannSteeringControllerTest, test_update_logic_chained)

// we test with open_loop=false, but steering angle was not updated (is zero) -> same commands
EXPECT_NEAR(
controller_->command_interfaces_[STATE_TRACTION_RIGHT_WHEEL].get_value(), 0.22222222222222224,
COMMON_THRESHOLD);
controller_->command_interfaces_[STATE_TRACTION_RIGHT_WHEEL].get_optional().value(),
0.22222222222222224, COMMON_THRESHOLD);
EXPECT_NEAR(
controller_->command_interfaces_[STATE_TRACTION_LEFT_WHEEL].get_value(), 0.22222222222222224,
COMMON_THRESHOLD);
controller_->command_interfaces_[STATE_TRACTION_LEFT_WHEEL].get_optional().value(),
0.22222222222222224, COMMON_THRESHOLD);
EXPECT_NEAR(
controller_->command_interfaces_[STATE_STEER_RIGHT_WHEEL].get_value(), 1.4179821977774734,
COMMON_THRESHOLD);
controller_->command_interfaces_[STATE_STEER_RIGHT_WHEEL].get_optional().value(),
1.4179821977774734, COMMON_THRESHOLD);
EXPECT_NEAR(
controller_->command_interfaces_[STATE_STEER_LEFT_WHEEL].get_value(), 1.4179821977774734,
COMMON_THRESHOLD);
controller_->command_interfaces_[STATE_STEER_LEFT_WHEEL].get_optional().value(),
1.4179821977774734, COMMON_THRESHOLD);

EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->twist.linear.x));
EXPECT_EQ(controller_->reference_interfaces_.size(), joint_reference_interfaces_.size());
Expand Down Expand Up @@ -266,17 +266,17 @@ TEST_F(AckermannSteeringControllerTest, receive_message_and_publish_updated_stat

// we test with open_loop=false, but steering angle was not updated (is zero) -> same commands
EXPECT_NEAR(
controller_->command_interfaces_[CMD_TRACTION_RIGHT_WHEEL].get_value(), 0.22222222222222224,
COMMON_THRESHOLD);
controller_->command_interfaces_[CMD_TRACTION_RIGHT_WHEEL].get_optional().value(),
0.22222222222222224, COMMON_THRESHOLD);
EXPECT_NEAR(
controller_->command_interfaces_[CMD_TRACTION_LEFT_WHEEL].get_value(), 0.22222222222222224,
COMMON_THRESHOLD);
controller_->command_interfaces_[CMD_TRACTION_LEFT_WHEEL].get_optional().value(),
0.22222222222222224, COMMON_THRESHOLD);
EXPECT_NEAR(
controller_->command_interfaces_[CMD_STEER_RIGHT_WHEEL].get_value(), 1.4179821977774734,
COMMON_THRESHOLD);
controller_->command_interfaces_[CMD_STEER_RIGHT_WHEEL].get_optional().value(),
1.4179821977774734, COMMON_THRESHOLD);
EXPECT_NEAR(
controller_->command_interfaces_[CMD_STEER_LEFT_WHEEL].get_value(), 1.4179821977774734,
COMMON_THRESHOLD);
controller_->command_interfaces_[CMD_STEER_LEFT_WHEEL].get_optional().value(),
1.4179821977774734, COMMON_THRESHOLD);

subscribe_and_get_messages(msg);

Expand Down
17 changes: 15 additions & 2 deletions bicycle_steering_controller/src/bicycle_steering_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,14 +54,27 @@ controller_interface::CallbackReturn BicycleSteeringController::configure_odomet

bool BicycleSteeringController::update_odometry(const rclcpp::Duration & period)
{
auto logger = get_node()->get_logger();

if (params_.open_loop)
{
odometry_.update_open_loop(last_linear_velocity_, last_angular_velocity_, period.seconds());
}
else
{
const double traction_wheel_value = state_interfaces_[STATE_TRACTION_WHEEL].get_value();
const double steering_position = state_interfaces_[STATE_STEER_AXIS].get_value();
const auto traction_wheel_value_op = state_interfaces_[STATE_TRACTION_WHEEL].get_optional();
const auto steering_position_op = state_interfaces_[STATE_STEER_AXIS].get_optional();

if (!traction_wheel_value_op.has_value() || !steering_position_op.has_value())
{
RCLCPP_DEBUG(
logger, "Unable to retrieve the data from the traction wheel or steering position!");
return true;
}

const double traction_wheel_value = traction_wheel_value_op.value();
const double steering_position = steering_position_op.value();

if (std::isfinite(traction_wheel_value) && std::isfinite(steering_position))
{
if (params_.position_feedback)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -127,9 +127,9 @@ TEST_F(BicycleSteeringControllerTest, reactivate_success)
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(std::isnan(controller_->command_interfaces_[0].get_value()));
ASSERT_TRUE(std::isnan(controller_->command_interfaces_[0].get_optional().value()));
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(std::isnan(controller_->command_interfaces_[0].get_value()));
ASSERT_TRUE(std::isnan(controller_->command_interfaces_[0].get_optional().value()));

ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
Expand Down Expand Up @@ -159,9 +159,10 @@ TEST_F(BicycleSteeringControllerTest, test_update_logic)
controller_interface::return_type::OK);

EXPECT_NEAR(
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_value(), 0.1 / 0.45, COMMON_THRESHOLD);
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_optional().value(), 0.1 / 0.45,
COMMON_THRESHOLD);
EXPECT_NEAR(
controller_->command_interfaces_[CMD_STEER_WHEEL].get_value(), 1.4179821977774734,
controller_->command_interfaces_[CMD_STEER_WHEEL].get_optional().value(), 1.4179821977774734,
COMMON_THRESHOLD);

EXPECT_FALSE(std::isnan((*(controller_->input_ref_.readFromRT()))->twist.linear.x));
Expand Down Expand Up @@ -191,9 +192,10 @@ TEST_F(BicycleSteeringControllerTest, test_update_logic_chained)
controller_interface::return_type::OK);

EXPECT_NEAR(
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_value(), 0.1 / 0.45, COMMON_THRESHOLD);
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_optional().value(), 0.1 / 0.45,
COMMON_THRESHOLD);
EXPECT_NEAR(
controller_->command_interfaces_[CMD_STEER_WHEEL].get_value(), 1.4179821977774734,
controller_->command_interfaces_[CMD_STEER_WHEEL].get_optional().value(), 1.4179821977774734,
COMMON_THRESHOLD);

EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->twist.linear.x));
Expand Down Expand Up @@ -246,9 +248,10 @@ TEST_F(BicycleSteeringControllerTest, receive_message_and_publish_updated_status
controller_interface::return_type::OK);

EXPECT_NEAR(
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_value(), 0.1 / 0.45, COMMON_THRESHOLD);
controller_->command_interfaces_[CMD_TRACTION_WHEEL].get_optional().value(), 0.1 / 0.45,
COMMON_THRESHOLD);
EXPECT_NEAR(
controller_->command_interfaces_[CMD_STEER_WHEEL].get_value(), 1.4179821977774734,
controller_->command_interfaces_[CMD_STEER_WHEEL].get_optional().value(), 1.4179821977774734,
COMMON_THRESHOLD);

subscribe_and_get_messages(msg);
Expand Down
Loading