diff --git a/diff_drive_controller/src/diff_drive_controller.cpp b/diff_drive_controller/src/diff_drive_controller.cpp index 537e32d3e1..486be105ce 100644 --- a/diff_drive_controller/src/diff_drive_controller.cpp +++ b/diff_drive_controller/src/diff_drive_controller.cpp @@ -167,9 +167,19 @@ controller_interface::return_type DiffDriveController::update_and_write_commands double right_feedback_mean = 0.0; for (size_t index = 0; index < static_cast(wheels_per_side_); ++index) { - const double left_feedback = registered_left_wheel_handles_[index].feedback.get().get_value(); - const double right_feedback = - registered_right_wheel_handles_[index].feedback.get().get_value(); + const auto left_feedback_op = + registered_left_wheel_handles_[index].feedback.get().get_optional(); + const auto right_feedback_op = + registered_right_wheel_handles_[index].feedback.get().get_optional(); + + if (!left_feedback_op.has_value() || !right_feedback_op.has_value()) + { + RCLCPP_DEBUG(logger, "Unable to retrieve the data from the left or right wheels feedback!"); + return controller_interface::return_type::OK; + } + + const double left_feedback = left_feedback_op.value(); + const double right_feedback = right_feedback_op.value(); if (std::isnan(left_feedback) || std::isnan(right_feedback)) { @@ -278,12 +288,18 @@ controller_interface::return_type DiffDriveController::update_and_write_commands (linear_command + angular_command * wheel_separation / 2.0) / right_wheel_radius; // Set wheels velocities: + bool set_command_result = true; for (size_t index = 0; index < static_cast(wheels_per_side_); ++index) { - registered_left_wheel_handles_[index].velocity.get().set_value(velocity_left); - registered_right_wheel_handles_[index].velocity.get().set_value(velocity_right); + set_command_result &= + registered_left_wheel_handles_[index].velocity.get().set_value(velocity_left); + set_command_result &= + registered_right_wheel_handles_[index].velocity.get().set_value(velocity_right); } + RCLCPP_DEBUG_EXPRESSION( + logger, !set_command_result, "Unable to set the command to one of the command handles!"); + return controller_interface::return_type::OK; } diff --git a/diff_drive_controller/test/test_diff_drive_controller.cpp b/diff_drive_controller/test/test_diff_drive_controller.cpp index 80fc1bf3b8..d348276cdc 100644 --- a/diff_drive_controller/test/test_diff_drive_controller.cpp +++ b/diff_drive_controller/test/test_diff_drive_controller.cpp @@ -507,8 +507,8 @@ TEST_F(TestDiffDriveController, test_speed_limiter) ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_NEAR(0.0, left_wheel_vel_cmd_.get_value(), 1e-3); - EXPECT_NEAR(0.0, right_wheel_vel_cmd_.get_value(), 1e-3); + EXPECT_NEAR(0.0, left_wheel_vel_cmd_.get_optional().value(), 1e-3); + EXPECT_NEAR(0.0, right_wheel_vel_cmd_.get_optional().value(), 1e-3); } const double dt = 0.001; @@ -528,18 +528,18 @@ TEST_F(TestDiffDriveController, test_speed_limiter) ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(dt)), controller_interface::return_type::OK); - EXPECT_GT(linear / wheel_radius, left_wheel_vel_cmd_.get_value()) + EXPECT_GT(linear / wheel_radius, left_wheel_vel_cmd_.get_optional().value()) << "at t: " << i * dt << "s, but this angular velocity should only be achieved at t: " << time_acc; - EXPECT_GT(linear / wheel_radius, right_wheel_vel_cmd_.get_value()) + EXPECT_GT(linear / wheel_radius, right_wheel_vel_cmd_.get_optional().value()) << "at t: " << i * dt << "s, but this angular velocity should only be achieved at t: " << time_acc; } ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(dt)), controller_interface::return_type::OK); - EXPECT_NEAR(linear / wheel_radius, left_wheel_vel_cmd_.get_value(), 1e-3); - EXPECT_NEAR(linear / wheel_radius, right_wheel_vel_cmd_.get_value(), 1e-3); + EXPECT_NEAR(linear / wheel_radius, left_wheel_vel_cmd_.get_optional().value(), 1e-3); + EXPECT_NEAR(linear / wheel_radius, right_wheel_vel_cmd_.get_optional().value(), 1e-3); // wait for the speed limiter to fill the queue for (int i = 0; i < 3; ++i) @@ -547,8 +547,8 @@ TEST_F(TestDiffDriveController, test_speed_limiter) ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_EQ(linear / wheel_radius, left_wheel_vel_cmd_.get_value()); - EXPECT_EQ(linear / wheel_radius, right_wheel_vel_cmd_.get_value()); + EXPECT_EQ(linear / wheel_radius, left_wheel_vel_cmd_.get_optional().value()); + EXPECT_EQ(linear / wheel_radius, right_wheel_vel_cmd_.get_optional().value()); } } @@ -565,18 +565,18 @@ TEST_F(TestDiffDriveController, test_speed_limiter) ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(dt)), controller_interface::return_type::OK); - EXPECT_LT(linear / wheel_radius, left_wheel_vel_cmd_.get_value()) + EXPECT_LT(linear / wheel_radius, left_wheel_vel_cmd_.get_optional().value()) << "at t: " << i * dt << "s, but this angular velocity should only be achieved at t: " << time_acc; - EXPECT_LT(linear / wheel_radius, right_wheel_vel_cmd_.get_value()) + EXPECT_LT(linear / wheel_radius, right_wheel_vel_cmd_.get_optional().value()) << "at t: " << i * dt << "s, but this angular velocity should only be achieved at t: " << time_acc; } ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(dt)), controller_interface::return_type::OK); - EXPECT_NEAR(linear / wheel_radius, left_wheel_vel_cmd_.get_value(), 1e-3); - EXPECT_NEAR(linear / wheel_radius, right_wheel_vel_cmd_.get_value(), 1e-3); + EXPECT_NEAR(linear / wheel_radius, left_wheel_vel_cmd_.get_optional().value(), 1e-3); + EXPECT_NEAR(linear / wheel_radius, right_wheel_vel_cmd_.get_optional().value(), 1e-3); // wait for the speed limiter to fill the queue for (int i = 0; i < 3; ++i) @@ -584,8 +584,8 @@ TEST_F(TestDiffDriveController, test_speed_limiter) ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_NEAR(linear / wheel_radius, left_wheel_vel_cmd_.get_value(), 1e-3); - EXPECT_NEAR(linear / wheel_radius, right_wheel_vel_cmd_.get_value(), 1e-3); + EXPECT_NEAR(linear / wheel_radius, left_wheel_vel_cmd_.get_optional().value(), 1e-3); + EXPECT_NEAR(linear / wheel_radius, right_wheel_vel_cmd_.get_optional().value(), 1e-3); } } @@ -602,18 +602,18 @@ TEST_F(TestDiffDriveController, test_speed_limiter) ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(dt)), controller_interface::return_type::OK); - EXPECT_LT(linear / wheel_radius, left_wheel_vel_cmd_.get_value()) + EXPECT_LT(linear / wheel_radius, left_wheel_vel_cmd_.get_optional().value()) << "at t: " << i * dt << "s, but this angular velocity should only be achieved at t: " << time_acc; - EXPECT_LT(linear / wheel_radius, right_wheel_vel_cmd_.get_value()) + EXPECT_LT(linear / wheel_radius, right_wheel_vel_cmd_.get_optional().value()) << "at t: " << i * dt << "s, but this angular velocity should only be achieved at t: " << time_acc; } ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(dt)), controller_interface::return_type::OK); - EXPECT_NEAR(linear / wheel_radius, left_wheel_vel_cmd_.get_value(), 1e-3); - EXPECT_NEAR(linear / wheel_radius, right_wheel_vel_cmd_.get_value(), 1e-3); + EXPECT_NEAR(linear / wheel_radius, left_wheel_vel_cmd_.get_optional().value(), 1e-3); + EXPECT_NEAR(linear / wheel_radius, right_wheel_vel_cmd_.get_optional().value(), 1e-3); // wait for the speed limiter to fill the queue for (int i = 0; i < 3; ++i) @@ -621,8 +621,8 @@ TEST_F(TestDiffDriveController, test_speed_limiter) ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_NEAR(linear / wheel_radius, left_wheel_vel_cmd_.get_value(), 1e-3); - EXPECT_NEAR(linear / wheel_radius, right_wheel_vel_cmd_.get_value(), 1e-3); + EXPECT_NEAR(linear / wheel_radius, left_wheel_vel_cmd_.get_optional().value(), 1e-3); + EXPECT_NEAR(linear / wheel_radius, right_wheel_vel_cmd_.get_optional().value(), 1e-3); } } @@ -639,18 +639,18 @@ TEST_F(TestDiffDriveController, test_speed_limiter) ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(dt)), controller_interface::return_type::OK); - EXPECT_GT(linear / wheel_radius, left_wheel_vel_cmd_.get_value()) + EXPECT_GT(linear / wheel_radius, left_wheel_vel_cmd_.get_optional().value()) << "at t: " << i * dt << "s, but this angular velocity should only be achieved at t: " << time_acc; - EXPECT_GT(linear / wheel_radius, right_wheel_vel_cmd_.get_value()) + EXPECT_GT(linear / wheel_radius, right_wheel_vel_cmd_.get_optional().value()) << "at t: " << i * dt << "s, but this angular velocity should only be achieved at t: " << time_acc; } ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(dt)), controller_interface::return_type::OK); - EXPECT_NEAR(linear / wheel_radius, left_wheel_vel_cmd_.get_value(), 1e-3); - EXPECT_NEAR(linear / wheel_radius, right_wheel_vel_cmd_.get_value(), 1e-3); + EXPECT_NEAR(linear / wheel_radius, left_wheel_vel_cmd_.get_optional().value(), 1e-3); + EXPECT_NEAR(linear / wheel_radius, right_wheel_vel_cmd_.get_optional().value(), 1e-3); // wait for the speed limiter to fill the queue for (int i = 0; i < 3; ++i) @@ -658,8 +658,8 @@ TEST_F(TestDiffDriveController, test_speed_limiter) ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_NEAR(linear / wheel_radius, left_wheel_vel_cmd_.get_value(), 1e-3); - EXPECT_NEAR(linear / wheel_radius, right_wheel_vel_cmd_.get_value(), 1e-3); + EXPECT_NEAR(linear / wheel_radius, left_wheel_vel_cmd_.get_optional().value(), 1e-3); + EXPECT_NEAR(linear / wheel_radius, right_wheel_vel_cmd_.get_optional().value(), 1e-3); } } } @@ -720,22 +720,24 @@ TEST_F(TestDiffDriveController, cleanup) controller_interface::return_type::OK); // should be moving - EXPECT_LT(0.0, left_wheel_vel_cmd_.get_value()); - EXPECT_LT(0.0, right_wheel_vel_cmd_.get_value()); + EXPECT_LT(0.0, left_wheel_vel_cmd_.get_optional().value()); + EXPECT_LT(0.0, right_wheel_vel_cmd_.get_optional().value()); state = controller_->get_node()->deactivate(); ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id()); // should be stopped - EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value()) << "Wheels should be halted on deactivate()"; - EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value()) << "Wheels should be halted on deactivate()"; + EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_optional().value()) + << "Wheels should be halted on deactivate()"; + EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value()) + << "Wheels should be halted on deactivate()"; state = controller_->get_node()->cleanup(); ASSERT_EQ(State::PRIMARY_STATE_UNCONFIGURED, state.id()); // should be stopped - EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value()); - EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value()); + EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_optional().value()); + EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value()); executor.cancel(); } @@ -755,8 +757,8 @@ TEST_F(TestDiffDriveController, correct_initialization_using_parameters) assignResourcesPosFeedback(); ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id()); - EXPECT_EQ(0.01, left_wheel_vel_cmd_.get_value()); - EXPECT_EQ(0.02, right_wheel_vel_cmd_.get_value()); + EXPECT_EQ(0.01, left_wheel_vel_cmd_.get_optional().value()); + EXPECT_EQ(0.02, right_wheel_vel_cmd_.get_optional().value()); state = controller_->get_node()->activate(); ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id()); @@ -771,8 +773,8 @@ TEST_F(TestDiffDriveController, correct_initialization_using_parameters) ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_EQ(1.0, left_wheel_vel_cmd_.get_value()); - EXPECT_EQ(1.0, right_wheel_vel_cmd_.get_value()); + EXPECT_EQ(1.0, left_wheel_vel_cmd_.get_optional().value()); + EXPECT_EQ(1.0, right_wheel_vel_cmd_.get_optional().value()); // deactivated // wait so controller process the second point when deactivated @@ -783,14 +785,15 @@ TEST_F(TestDiffDriveController, correct_initialization_using_parameters) controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value()) << "Wheels are halted on deactivate()"; - EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value()) << "Wheels are halted on deactivate()"; + EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_optional().value()) << "Wheels are halted on deactivate()"; + EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value()) + << "Wheels are halted on deactivate()"; // cleanup state = controller_->get_node()->cleanup(); ASSERT_EQ(State::PRIMARY_STATE_UNCONFIGURED, state.id()); - EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value()); - EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value()); + EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_optional().value()); + EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value()); state = controller_->get_node()->configure(); ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id()); @@ -836,8 +839,8 @@ TEST_F(TestDiffDriveController, chainable_controller_unchained_mode) } // But NaNs should not propagate to command interfaces // (these are set to 0.1 and 0.2 in InitController) - ASSERT_FALSE(std::isnan(left_wheel_vel_cmd_.get_value())); - ASSERT_FALSE(std::isnan(right_wheel_vel_cmd_.get_value())); + ASSERT_FALSE(std::isnan(left_wheel_vel_cmd_.get_optional().value())); + ASSERT_FALSE(std::isnan(right_wheel_vel_cmd_.get_optional().value())); // Check that a late command message causes the command interfaces to be set to 0.0 const double linear = 1.0; @@ -850,9 +853,9 @@ TEST_F(TestDiffDriveController, chainable_controller_unchained_mode) ASSERT_EQ( controller_->update(pub_node->get_clock()->now(), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value()) + EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_optional().value()) << "Wheels should halt if command message is older than cmd_vel_timeout"; - EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value()) + EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value()) << "Wheels should halt if command message is older than cmd_vel_timeout"; // Now check that a timely published command message sets the command interfaces to the correct @@ -864,8 +867,8 @@ TEST_F(TestDiffDriveController, chainable_controller_unchained_mode) ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_EQ(linear, left_wheel_vel_cmd_.get_value()); - EXPECT_EQ(linear, right_wheel_vel_cmd_.get_value()); + EXPECT_EQ(linear, left_wheel_vel_cmd_.get_optional().value()); + EXPECT_EQ(linear, right_wheel_vel_cmd_.get_optional().value()); // Now check that the command interfaces are set to 0.0 on deactivation // (despite calls to update()) @@ -876,14 +879,18 @@ TEST_F(TestDiffDriveController, chainable_controller_unchained_mode) controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value()) << "Wheels should be halted on deactivate()"; - EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value()) << "Wheels should be halted on deactivate()"; + EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_optional().value()) + << "Wheels should be halted on deactivate()"; + EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value()) + << "Wheels should be halted on deactivate()"; // cleanup state = controller_->get_node()->cleanup(); ASSERT_EQ(State::PRIMARY_STATE_UNCONFIGURED, state.id()); - EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value()) << "Wheels should be halted on cleanup()"; - EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value()) << "Wheels should be halted on cleanup()"; + EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_optional().value()) + << "Wheels should be halted on cleanup()"; + EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value()) + << "Wheels should be halted on cleanup()"; state = controller_->get_node()->configure(); ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id()); @@ -926,8 +933,8 @@ TEST_F(TestDiffDriveController, chainable_controller_chained_mode) } // But NaNs should not propagate to command interfaces // (these are set to 0.1 and 0.2 in InitController) - ASSERT_FALSE(std::isnan(left_wheel_vel_cmd_.get_value())); - ASSERT_FALSE(std::isnan(right_wheel_vel_cmd_.get_value())); + ASSERT_FALSE(std::isnan(left_wheel_vel_cmd_.get_optional().value())); + ASSERT_FALSE(std::isnan(right_wheel_vel_cmd_.get_optional().value())); // Imitate preceding controllers by setting reference_interfaces_ // (Note: reference_interfaces_ is protected, but this is @@ -939,8 +946,8 @@ TEST_F(TestDiffDriveController, chainable_controller_chained_mode) ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_EQ(linear, left_wheel_vel_cmd_.get_value()); - EXPECT_EQ(linear, right_wheel_vel_cmd_.get_value()); + EXPECT_EQ(linear, left_wheel_vel_cmd_.get_optional().value()); + EXPECT_EQ(linear, right_wheel_vel_cmd_.get_optional().value()); // Now check that the command interfaces are set to 0.0 on deactivation // (despite calls to update()) @@ -951,14 +958,18 @@ TEST_F(TestDiffDriveController, chainable_controller_chained_mode) controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value()) << "Wheels should be halted on deactivate()"; - EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value()) << "Wheels should be halted on deactivate()"; + EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_optional().value()) + << "Wheels should be halted on deactivate()"; + EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value()) + << "Wheels should be halted on deactivate()"; // cleanup state = controller_->get_node()->cleanup(); ASSERT_EQ(State::PRIMARY_STATE_UNCONFIGURED, state.id()); - EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value()) << "Wheels should be halted on cleanup()"; - EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value()) << "Wheels should be halted on cleanup()"; + EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_optional().value()) + << "Wheels should be halted on cleanup()"; + EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value()) + << "Wheels should be halted on cleanup()"; state = controller_->get_node()->configure(); ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id()); @@ -1028,8 +1039,8 @@ TEST_F(TestDiffDriveController, deactivate_then_activate) } // But NaNs should not propagate to command interfaces // (these are set to 0.1 and 0.2 in InitController) - ASSERT_FALSE(std::isnan(left_wheel_vel_cmd_.get_value())); - ASSERT_FALSE(std::isnan(right_wheel_vel_cmd_.get_value())); + ASSERT_FALSE(std::isnan(left_wheel_vel_cmd_.get_optional().value())); + ASSERT_FALSE(std::isnan(right_wheel_vel_cmd_.get_optional().value())); // published command message sets the command interfaces to the correct values const double linear = 1.0; @@ -1040,8 +1051,8 @@ TEST_F(TestDiffDriveController, deactivate_then_activate) ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_EQ(linear, left_wheel_vel_cmd_.get_value()); - EXPECT_EQ(linear, right_wheel_vel_cmd_.get_value()); + EXPECT_EQ(linear, left_wheel_vel_cmd_.get_optional().value()); + EXPECT_EQ(linear, right_wheel_vel_cmd_.get_optional().value()); // Now check that the command interfaces are set to 0.0 on deactivation // (despite calls to update()) @@ -1052,8 +1063,10 @@ TEST_F(TestDiffDriveController, deactivate_then_activate) controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value()) << "Wheels should be halted on deactivate()"; - EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value()) << "Wheels should be halted on deactivate()"; + EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_optional().value()) + << "Wheels should be halted on deactivate()"; + EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value()) + << "Wheels should be halted on deactivate()"; // Activate again state = controller_->get_node()->activate(); @@ -1068,9 +1081,9 @@ TEST_F(TestDiffDriveController, deactivate_then_activate) EXPECT_TRUE(std::isnan(interface)) << "Reference interfaces should initially be NaN on activation"; } - EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_value()) + EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_optional().value()) << "Wheels should still have the same command as when they were last set (on deactivation)"; - EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value()) + EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value()) << "Wheels should still have the same command as when they were last set (on deactivation)"; // A new command should work as expected @@ -1080,8 +1093,8 @@ TEST_F(TestDiffDriveController, deactivate_then_activate) ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_EQ(linear, left_wheel_vel_cmd_.get_value()); - EXPECT_EQ(linear, right_wheel_vel_cmd_.get_value()); + EXPECT_EQ(linear, left_wheel_vel_cmd_.get_optional().value()); + EXPECT_EQ(linear, right_wheel_vel_cmd_.get_optional().value()); // Deactivate again and cleanup std::this_thread::sleep_for(std::chrono::milliseconds(300)); @@ -1124,8 +1137,8 @@ TEST_F(TestDiffDriveController, command_with_zero_timestamp_is_accepted_with_war ASSERT_EQ( controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_EQ(linear, left_wheel_vel_cmd_.get_value()); - EXPECT_EQ(linear, right_wheel_vel_cmd_.get_value()); + EXPECT_EQ(linear, left_wheel_vel_cmd_.get_optional().value()); + EXPECT_EQ(linear, right_wheel_vel_cmd_.get_optional().value()); // Deactivate and cleanup std::this_thread::sleep_for(std::chrono::milliseconds(300));