diff --git a/ackermann_steering_controller/test/test_ackermann_steering_controller.hpp b/ackermann_steering_controller/test/test_ackermann_steering_controller.hpp index a2849d5742..8af2f6bc94 100644 --- a/ackermann_steering_controller/test/test_ackermann_steering_controller.hpp +++ b/ackermann_steering_controller/test/test_ackermann_steering_controller.hpp @@ -147,7 +147,7 @@ class AckermannSteeringControllerFixture : public ::testing::Test protected: void SetUpController(const std::string controller_name = "test_ackermann_steering_controller") { - ASSERT_EQ(controller_->init(controller_name, "", 0), controller_interface::return_type::OK); + ASSERT_EQ(controller_->init(controller_name, ""), controller_interface::return_type::OK); if (position_feedback_ == true) { diff --git a/admittance_controller/test/test_admittance_controller.hpp b/admittance_controller/test/test_admittance_controller.hpp index 19908d7f9f..8888cd700a 100644 --- a/admittance_controller/test/test_admittance_controller.hpp +++ b/admittance_controller/test/test_admittance_controller.hpp @@ -185,7 +185,7 @@ class AdmittanceControllerTest : public ::testing::Test controller_interface::return_type SetUpControllerCommon( const std::string & controller_name, const rclcpp::NodeOptions & options) { - auto result = controller_->init(controller_name, "", 0, "", options); + auto result = controller_->init(controller_name, "", options); controller_->export_reference_interfaces(); assign_interfaces(); diff --git a/bicycle_steering_controller/test/test_bicycle_steering_controller.hpp b/bicycle_steering_controller/test/test_bicycle_steering_controller.hpp index 521506762b..34d6883a83 100644 --- a/bicycle_steering_controller/test/test_bicycle_steering_controller.hpp +++ b/bicycle_steering_controller/test/test_bicycle_steering_controller.hpp @@ -144,7 +144,7 @@ class BicycleSteeringControllerFixture : public ::testing::Test protected: void SetUpController(const std::string controller_name = "test_bicycle_steering_controller") { - ASSERT_EQ(controller_->init(controller_name, "", 0), controller_interface::return_type::OK); + ASSERT_EQ(controller_->init(controller_name, ""), controller_interface::return_type::OK); if (position_feedback_ == true) { diff --git a/diff_drive_controller/test/test_diff_drive_controller.cpp b/diff_drive_controller/test/test_diff_drive_controller.cpp index eb970d34a3..c7881df8ff 100644 --- a/diff_drive_controller/test/test_diff_drive_controller.cpp +++ b/diff_drive_controller/test/test_diff_drive_controller.cpp @@ -195,7 +195,7 @@ class TestDiffDriveController : public ::testing::Test TEST_F(TestDiffDriveController, configure_fails_without_parameters) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_, rclcpp::NodeOptions()); ASSERT_EQ(ret, controller_interface::return_type::OK); ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::ERROR); @@ -203,7 +203,7 @@ TEST_F(TestDiffDriveController, configure_fails_without_parameters) TEST_F(TestDiffDriveController, configure_fails_with_only_left_or_only_right_side_defined) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_, rclcpp::NodeOptions()); ASSERT_EQ(ret, controller_interface::return_type::OK); controller_->get_node()->set_parameter( @@ -223,7 +223,7 @@ TEST_F(TestDiffDriveController, configure_fails_with_only_left_or_only_right_sid TEST_F(TestDiffDriveController, configure_fails_with_mismatching_wheel_side_size) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_, rclcpp::NodeOptions()); ASSERT_EQ(ret, controller_interface::return_type::OK); controller_->get_node()->set_parameter( @@ -239,7 +239,7 @@ TEST_F(TestDiffDriveController, configure_fails_with_mismatching_wheel_side_size TEST_F(TestDiffDriveController, configure_succeeds_when_wheels_are_specified) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_, rclcpp::NodeOptions()); ASSERT_EQ(ret, controller_interface::return_type::OK); controller_->get_node()->set_parameter( @@ -259,7 +259,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_when_wheels_are_specified) TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_false_no_namespace) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_, rclcpp::NodeOptions()); ASSERT_EQ(ret, controller_interface::return_type::OK); std::string odom_id = "odom"; @@ -292,7 +292,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_false_no_names TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_true_no_namespace) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_, rclcpp::NodeOptions()); ASSERT_EQ(ret, controller_interface::return_type::OK); std::string odom_id = "odom"; @@ -327,7 +327,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_true_no_namesp TEST_F(TestDiffDriveController, configure_succeeds_tf_blank_prefix_true_no_namespace) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_); ASSERT_EQ(ret, controller_interface::return_type::OK); std::string odom_id = "odom"; @@ -363,7 +363,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_false_set_name { std::string test_namespace = "/test_namespace"; - const auto ret = controller_->init(controller_name, urdf_, 0, test_namespace); + const auto ret = controller_->init(controller_name, test_namespace); ASSERT_EQ(ret, controller_interface::return_type::OK); std::string odom_id = "odom"; @@ -398,7 +398,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_true_set_names { std::string test_namespace = "/test_namespace"; - const auto ret = controller_->init(controller_name, urdf_, 0, test_namespace); + const auto ret = controller_->init(controller_name, test_namespace); ASSERT_EQ(ret, controller_interface::return_type::OK); std::string odom_id = "odom"; @@ -435,7 +435,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_blank_prefix_true_set_name { std::string test_namespace = "/test_namespace"; - const auto ret = controller_->init(controller_name, urdf_, 0, test_namespace); + const auto ret = controller_->init(controller_name, test_namespace); ASSERT_EQ(ret, controller_interface::return_type::OK); std::string odom_id = "odom"; @@ -469,7 +469,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_blank_prefix_true_set_name TEST_F(TestDiffDriveController, activate_fails_without_resources_assigned) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_); ASSERT_EQ(ret, controller_interface::return_type::OK); controller_->get_node()->set_parameter( @@ -483,7 +483,7 @@ TEST_F(TestDiffDriveController, activate_fails_without_resources_assigned) TEST_F(TestDiffDriveController, activate_succeeds_with_pos_resources_assigned) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_); ASSERT_EQ(ret, controller_interface::return_type::OK); // We implicitly test that by default position feedback is required @@ -499,7 +499,7 @@ TEST_F(TestDiffDriveController, activate_succeeds_with_pos_resources_assigned) TEST_F(TestDiffDriveController, activate_succeeds_with_vel_resources_assigned) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_); ASSERT_EQ(ret, controller_interface::return_type::OK); controller_->get_node()->set_parameter( @@ -516,7 +516,7 @@ TEST_F(TestDiffDriveController, activate_succeeds_with_vel_resources_assigned) TEST_F(TestDiffDriveController, activate_fails_with_wrong_resources_assigned_1) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_); ASSERT_EQ(ret, controller_interface::return_type::OK); controller_->get_node()->set_parameter( @@ -533,7 +533,7 @@ TEST_F(TestDiffDriveController, activate_fails_with_wrong_resources_assigned_1) TEST_F(TestDiffDriveController, activate_fails_with_wrong_resources_assigned_2) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_); ASSERT_EQ(ret, controller_interface::return_type::OK); controller_->get_node()->set_parameter( @@ -550,7 +550,7 @@ TEST_F(TestDiffDriveController, activate_fails_with_wrong_resources_assigned_2) TEST_F(TestDiffDriveController, cleanup) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_); ASSERT_EQ(ret, controller_interface::return_type::OK); controller_->get_node()->set_parameter( @@ -599,7 +599,7 @@ TEST_F(TestDiffDriveController, cleanup) TEST_F(TestDiffDriveController, correct_initialization_using_parameters) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_); ASSERT_EQ(ret, controller_interface::return_type::OK); controller_->get_node()->set_parameter( diff --git a/effort_controllers/test/test_joint_group_effort_controller.cpp b/effort_controllers/test/test_joint_group_effort_controller.cpp index f9d72ab202..23555c578f 100644 --- a/effort_controllers/test/test_joint_group_effort_controller.cpp +++ b/effort_controllers/test/test_joint_group_effort_controller.cpp @@ -54,7 +54,7 @@ void JointGroupEffortControllerTest::TearDown() { controller_.reset(nullptr); } void JointGroupEffortControllerTest::SetUpController() { - const auto result = controller_->init("test_joint_group_effort_controller", "", 0); + const auto result = controller_->init("test_joint_group_effort_controller", ""); ASSERT_EQ(result, controller_interface::return_type::OK); std::vector command_ifs; diff --git a/force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.cpp b/force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.cpp index bfe7561642..82f677410e 100644 --- a/force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.cpp +++ b/force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.cpp @@ -53,7 +53,7 @@ void ForceTorqueSensorBroadcasterTest::TearDown() { fts_broadcaster_.reset(nullp void ForceTorqueSensorBroadcasterTest::SetUpFTSBroadcaster() { - const auto result = fts_broadcaster_->init("test_force_torque_sensor_broadcaster", "", 0); + const auto result = fts_broadcaster_->init("test_force_torque_sensor_broadcaster", ""); ASSERT_EQ(result, controller_interface::return_type::OK); std::vector state_ifs; diff --git a/forward_command_controller/test/test_forward_command_controller.cpp b/forward_command_controller/test/test_forward_command_controller.cpp index 62d5512b4e..1a2a545a98 100644 --- a/forward_command_controller/test/test_forward_command_controller.cpp +++ b/forward_command_controller/test/test_forward_command_controller.cpp @@ -60,7 +60,7 @@ void ForwardCommandControllerTest::TearDown() { controller_.reset(nullptr); } void ForwardCommandControllerTest::SetUpController() { - const auto result = controller_->init("forward_command_controller", "", 0); + const auto result = controller_->init("forward_command_controller", "", rclcpp::NodeOptions()); ASSERT_EQ(result, controller_interface::return_type::OK); std::vector command_ifs; diff --git a/forward_command_controller/test/test_multi_interface_forward_command_controller.cpp b/forward_command_controller/test/test_multi_interface_forward_command_controller.cpp index 7826c85355..80aae0e901 100644 --- a/forward_command_controller/test/test_multi_interface_forward_command_controller.cpp +++ b/forward_command_controller/test/test_multi_interface_forward_command_controller.cpp @@ -62,7 +62,7 @@ void MultiInterfaceForwardCommandControllerTest::TearDown() { controller_.reset( void MultiInterfaceForwardCommandControllerTest::SetUpController(bool set_params_and_activate) { - const auto result = controller_->init("multi_interface_forward_command_controller", "", 0); + const auto result = controller_->init("multi_interface_forward_command_controller", "", rclcpp::NodeOptions()); ASSERT_EQ(result, controller_interface::return_type::OK); std::vector command_ifs; diff --git a/gripper_controllers/test/test_gripper_controllers.cpp b/gripper_controllers/test/test_gripper_controllers.cpp index 0fc10c0c73..e94926113f 100644 --- a/gripper_controllers/test/test_gripper_controllers.cpp +++ b/gripper_controllers/test/test_gripper_controllers.cpp @@ -60,7 +60,7 @@ void GripperControllerTest::TearDown() template void GripperControllerTest::SetUpController() { - const auto result = controller_->init("gripper_controller", "", 0); + const auto result = controller_->init("gripper_controller", "", rclcpp::NodeOptions()); ASSERT_EQ(result, controller_interface::return_type::OK); std::vector command_ifs; diff --git a/imu_sensor_broadcaster/test/test_imu_sensor_broadcaster.cpp b/imu_sensor_broadcaster/test/test_imu_sensor_broadcaster.cpp index 0fb987ce77..0b782efc5f 100644 --- a/imu_sensor_broadcaster/test/test_imu_sensor_broadcaster.cpp +++ b/imu_sensor_broadcaster/test/test_imu_sensor_broadcaster.cpp @@ -53,7 +53,7 @@ void IMUSensorBroadcasterTest::TearDown() { imu_broadcaster_.reset(nullptr); } void IMUSensorBroadcasterTest::SetUpIMUBroadcaster() { - const auto result = imu_broadcaster_->init("test_imu_sensor_broadcaster", "", 0); + const auto result = imu_broadcaster_->init("test_imu_sensor_broadcaster", ""); ASSERT_EQ(result, controller_interface::return_type::OK); std::vector state_ifs; diff --git a/joint_state_broadcaster/test/test_joint_state_broadcaster.cpp b/joint_state_broadcaster/test/test_joint_state_broadcaster.cpp index 3a74f599b4..a6c0708fd9 100644 --- a/joint_state_broadcaster/test/test_joint_state_broadcaster.cpp +++ b/joint_state_broadcaster/test/test_joint_state_broadcaster.cpp @@ -69,7 +69,7 @@ void JointStateBroadcasterTest::SetUpStateBroadcaster( void JointStateBroadcasterTest::init_broadcaster_and_set_parameters( const std::vector & joint_names, const std::vector & interfaces) { - const auto result = state_broadcaster_->init("joint_state_broadcaster", "", 0); + const auto result = state_broadcaster_->init("joint_state_broadcaster", ""); ASSERT_EQ(result, controller_interface::return_type::OK); state_broadcaster_->get_node()->set_parameter({"joints", joint_names}); diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/trajectory.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/trajectory.hpp index 3bd4873a31..3f30d4c804 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/trajectory.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/trajectory.hpp @@ -154,6 +154,7 @@ class Trajectory rclcpp::Time time_before_traj_msg_; trajectory_msgs::msg::JointTrajectoryPoint state_before_traj_msg_; + size_t previous_start_idx_; bool sampled_already_ = false; }; diff --git a/joint_trajectory_controller/src/trajectory.cpp b/joint_trajectory_controller/src/trajectory.cpp index fae4c41ff9..8430e661cb 100644 --- a/joint_trajectory_controller/src/trajectory.cpp +++ b/joint_trajectory_controller/src/trajectory.cpp @@ -55,6 +55,7 @@ void Trajectory::update(std::shared_ptr j trajectory_msg_ = joint_trajectory; trajectory_start_time_ = static_cast(joint_trajectory->header.stamp); sampled_already_ = false; + previous_start_idx_ = 0; } bool Trajectory::sample( @@ -80,6 +81,7 @@ bool Trajectory::sample( trajectory_start_time_ = sample_time; } + previous_start_idx_ = 0; sampled_already_ = true; } @@ -120,7 +122,7 @@ bool Trajectory::sample( // time_from_start + trajectory time is the expected arrival time of trajectory const auto last_idx = trajectory_msg_->points.size() - 1; - for (size_t i = 0; i < last_idx; ++i) + for (size_t i = previous_start_idx_; i < last_idx; ++i) { auto & point = trajectory_msg_->points[i]; auto & next_point = trajectory_msg_->points[i + 1]; @@ -146,6 +148,7 @@ bool Trajectory::sample( } start_segment_itr = begin() + i; end_segment_itr = begin() + (i + 1); + previous_start_idx_ = i; return true; } } diff --git a/joint_trajectory_controller/test/test_trajectory.cpp b/joint_trajectory_controller/test/test_trajectory.cpp index b52aa67a04..e4701a9175 100644 --- a/joint_trajectory_controller/test/test_trajectory.cpp +++ b/joint_trajectory_controller/test/test_trajectory.cpp @@ -821,3 +821,68 @@ TEST(TestTrajectory, skip_interpolation) } } } + +TEST(TestTrajectory, check_index_increment){ + auto full_msg = std::make_shared(); + full_msg->header.stamp = rclcpp::Time(0); + + trajectory_msgs::msg::JointTrajectoryPoint p1; + p1.positions.push_back(1.0); + p1.time_from_start = rclcpp::Duration::from_seconds(1.0); + full_msg->points.push_back(p1); + + trajectory_msgs::msg::JointTrajectoryPoint p2; + p2.positions.push_back(2.0); + p2.time_from_start = rclcpp::Duration::from_seconds(2.0); + full_msg->points.push_back(p2); + + trajectory_msgs::msg::JointTrajectoryPoint p3; + p3.positions.push_back(3.0); + p3.time_from_start = rclcpp::Duration::from_seconds(3.0); + full_msg->points.push_back(p3); + + trajectory_msgs::msg::JointTrajectoryPoint point_before_msg; + point_before_msg.time_from_start = rclcpp::Duration::from_seconds(0.0); + point_before_msg.positions.push_back(0.0); + + // set current state before trajectory msg was sent + const rclcpp::Time time_now = rclcpp::Clock().now(); + auto traj = joint_trajectory_controller::Trajectory(time_now, point_before_msg, full_msg); + + trajectory_msgs::msg::JointTrajectoryPoint expected_state; + joint_trajectory_controller::TrajectoryPointConstIter start, end; + + double duration_first_seg = 1.0; + double velocity = (p1.positions[0] - point_before_msg.positions[0]) / duration_first_seg; + // sample trajectory before starting time + { + bool result = traj.sample( + time_now - rclcpp::Duration::from_seconds(0.5), DEFAULT_INTERPOLATION, expected_state, start, + end); + RCLCPP_INFO_STREAM(rclcpp::get_logger("test"), "ASSERTING"); + ASSERT_EQ(result, false); + } + + // sample at trajectory starting time + { + traj.sample(time_now, DEFAULT_INTERPOLATION, expected_state, start, end); + ASSERT_EQ(traj.begin(), start); + ASSERT_EQ(traj.begin(), end); + } + + // sample .5s into trajectory - should increment end iterator + { + traj.sample(time_now + rclcpp::Duration::from_seconds(0.5), DEFAULT_INTERPOLATION, expected_state, start, + end); + ASSERT_EQ(traj.begin(), start); + ASSERT_EQ(traj.begin() + 1, end); + } + + // sample 1.5s into trajectory - should increment both iterators + { + traj.sample(time_now + rclcpp::Duration::from_seconds(1.5), DEFAULT_INTERPOLATION, expected_state, start, + end); + ASSERT_EQ(traj.begin() + 1, start); + ASSERT_EQ(traj.begin() + 2, end); + } +} diff --git a/joint_trajectory_controller/test/test_trajectory_controller_utils.hpp b/joint_trajectory_controller/test/test_trajectory_controller_utils.hpp index 3a7e7e5cf1..46e3d45e29 100644 --- a/joint_trajectory_controller/test/test_trajectory_controller_utils.hpp +++ b/joint_trajectory_controller/test/test_trajectory_controller_utils.hpp @@ -196,7 +196,7 @@ class TrajectoryControllerTest : public ::testing::Test parameter_overrides.insert(parameter_overrides.end(), parameters.begin(), parameters.end()); node_options.parameter_overrides(parameter_overrides); - auto ret = traj_controller_->init(controller_name_, "", 0, "", node_options); + auto ret = traj_controller_->init(controller_name_, "", node_options); if (ret != controller_interface::return_type::OK) { FAIL(); diff --git a/position_controllers/test/test_joint_group_position_controller.cpp b/position_controllers/test/test_joint_group_position_controller.cpp index 3b4f00be12..07f42e4eba 100644 --- a/position_controllers/test/test_joint_group_position_controller.cpp +++ b/position_controllers/test/test_joint_group_position_controller.cpp @@ -54,7 +54,7 @@ void JointGroupPositionControllerTest::TearDown() { controller_.reset(nullptr); void JointGroupPositionControllerTest::SetUpController() { - const auto result = controller_->init("test_joint_group_position_controller", "", 0); + const auto result = controller_->init("test_joint_group_position_controller", ""); ASSERT_EQ(result, controller_interface::return_type::OK); std::vector command_ifs; diff --git a/range_sensor_broadcaster/test/test_range_sensor_broadcaster.cpp b/range_sensor_broadcaster/test/test_range_sensor_broadcaster.cpp index a857141ea9..ab937146cb 100644 --- a/range_sensor_broadcaster/test/test_range_sensor_broadcaster.cpp +++ b/range_sensor_broadcaster/test/test_range_sensor_broadcaster.cpp @@ -34,7 +34,7 @@ controller_interface::return_type RangeSensorBroadcasterTest::init_broadcaster( std::string broadcaster_name) { controller_interface::return_type result = controller_interface::return_type::ERROR; - result = range_broadcaster_->init(broadcaster_name, "", 0); + result = range_broadcaster_->init(broadcaster_name, ""); if (controller_interface::return_type::OK == result) { diff --git a/ros2_controllers_test_nodes/ros2_controllers_test_nodes/__pycache__/__init__.cpython-310.pyc b/ros2_controllers_test_nodes/ros2_controllers_test_nodes/__pycache__/__init__.cpython-310.pyc new file mode 100644 index 0000000000..39f76b8e22 Binary files /dev/null and b/ros2_controllers_test_nodes/ros2_controllers_test_nodes/__pycache__/__init__.cpython-310.pyc differ diff --git a/rqt_joint_trajectory_controller/rqt_joint_trajectory_controller/__pycache__/__init__.cpython-310.pyc b/rqt_joint_trajectory_controller/rqt_joint_trajectory_controller/__pycache__/__init__.cpython-310.pyc new file mode 100644 index 0000000000..d42b209cc6 Binary files /dev/null and b/rqt_joint_trajectory_controller/rqt_joint_trajectory_controller/__pycache__/__init__.cpython-310.pyc differ diff --git a/steering_controllers_library/test/test_steering_controllers_library.hpp b/steering_controllers_library/test/test_steering_controllers_library.hpp index 5caf347ac1..fd6399831b 100644 --- a/steering_controllers_library/test/test_steering_controllers_library.hpp +++ b/steering_controllers_library/test/test_steering_controllers_library.hpp @@ -168,7 +168,7 @@ class SteeringControllersLibraryFixture : public ::testing::Test protected: void SetUpController(const std::string controller_name = "test_steering_controllers_library") { - ASSERT_EQ(controller_->init(controller_name, "", 0), controller_interface::return_type::OK); + ASSERT_EQ(controller_->init(controller_name, "", rclcpp::NodeOptions()), controller_interface::return_type::OK); if (position_feedback_ == true) { diff --git a/tricycle_controller/test/test_tricycle_controller.cpp b/tricycle_controller/test/test_tricycle_controller.cpp index 504ca381ce..f5f3ccb084 100644 --- a/tricycle_controller/test/test_tricycle_controller.cpp +++ b/tricycle_controller/test/test_tricycle_controller.cpp @@ -173,14 +173,14 @@ class TestTricycleController : public ::testing::Test TEST_F(TestTricycleController, configure_fails_without_parameters) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_, rclcpp::NodeOptions()); ASSERT_EQ(ret, controller_interface::return_type::OK); ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::ERROR); } TEST_F(TestTricycleController, configure_fails_if_only_traction_or_steering_side_defined) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_, rclcpp::NodeOptions()); ASSERT_EQ(ret, controller_interface::return_type::OK); controller_->get_node()->set_parameter( @@ -200,7 +200,7 @@ TEST_F(TestTricycleController, configure_fails_if_only_traction_or_steering_side TEST_F(TestTricycleController, configure_succeeds_when_joints_are_specified) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_, rclcpp::NodeOptions()); ASSERT_EQ(ret, controller_interface::return_type::OK); controller_->get_node()->set_parameter( @@ -213,7 +213,7 @@ TEST_F(TestTricycleController, configure_succeeds_when_joints_are_specified) TEST_F(TestTricycleController, activate_fails_without_resources_assigned) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_, rclcpp::NodeOptions()); ASSERT_EQ(ret, controller_interface::return_type::OK); controller_->get_node()->set_parameter( @@ -227,7 +227,7 @@ TEST_F(TestTricycleController, activate_fails_without_resources_assigned) TEST_F(TestTricycleController, activate_succeeds_with_resources_assigned) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_, rclcpp::NodeOptions()); ASSERT_EQ(ret, controller_interface::return_type::OK); // We implicitly test that by default position feedback is required @@ -243,7 +243,7 @@ TEST_F(TestTricycleController, activate_succeeds_with_resources_assigned) TEST_F(TestTricycleController, cleanup) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_, rclcpp::NodeOptions()); ASSERT_EQ(ret, controller_interface::return_type::OK); controller_->get_node()->set_parameter( @@ -292,7 +292,7 @@ TEST_F(TestTricycleController, cleanup) TEST_F(TestTricycleController, correct_initialization_using_parameters) { - const auto ret = controller_->init(controller_name, urdf_, 0); + const auto ret = controller_->init(controller_name, urdf_, rclcpp::NodeOptions()); ASSERT_EQ(ret, controller_interface::return_type::OK); controller_->get_node()->set_parameter( diff --git a/tricycle_steering_controller/test/test_tricycle_steering_controller.hpp b/tricycle_steering_controller/test/test_tricycle_steering_controller.hpp index c5f6985d4e..e9d1023d98 100644 --- a/tricycle_steering_controller/test/test_tricycle_steering_controller.hpp +++ b/tricycle_steering_controller/test/test_tricycle_steering_controller.hpp @@ -146,7 +146,7 @@ class TricycleSteeringControllerFixture : public ::testing::Test protected: void SetUpController(const std::string controller_name = "test_tricycle_steering_controller") { - ASSERT_EQ(controller_->init(controller_name, "", 0), controller_interface::return_type::OK); + ASSERT_EQ(controller_->init(controller_name, ""), controller_interface::return_type::OK); if (position_feedback_ == true) { diff --git a/velocity_controllers/test/test_joint_group_velocity_controller.cpp b/velocity_controllers/test/test_joint_group_velocity_controller.cpp index 4cbf1b7342..185c630bc9 100644 --- a/velocity_controllers/test/test_joint_group_velocity_controller.cpp +++ b/velocity_controllers/test/test_joint_group_velocity_controller.cpp @@ -54,7 +54,7 @@ void JointGroupVelocityControllerTest::TearDown() { controller_.reset(nullptr); void JointGroupVelocityControllerTest::SetUpController() { - const auto result = controller_->init("test_joint_group_velocity_controller", "", 0); + const auto result = controller_->init("test_joint_group_velocity_controller", ""); ASSERT_EQ(result, controller_interface::return_type::OK); std::vector command_ifs;