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

Final variant support #25

Draft
wants to merge 7 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from 1 commit
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
Next Next commit
change get_value function to new templated version
  • Loading branch information
mamueluth committed Jul 29, 2024
commit d753fb4bbb26cacc6fa9a9b1d9599525a082de4f
20 changes: 10 additions & 10 deletions diff_drive_controller/test/test_diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -513,8 +513,8 @@ TEST_F(TestDiffDriveController, 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_value<double>());
EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value<double>());

executor.cancel();
}
Expand All @@ -534,8 +534,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_value<double>());
EXPECT_EQ(0.02, right_wheel_vel_cmd_.get_value<double>());

state = controller_->get_node()->activate();
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
Expand All @@ -550,8 +550,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_value<double>());
EXPECT_EQ(1.0, right_wheel_vel_cmd_.get_value<double>());

// deactivated
// wait so controller process the second point when deactivated
Expand All @@ -562,14 +562,14 @@ 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_value<double>()) << "Wheels are halted on deactivate()";
EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value<double>()) << "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_value<double>());
EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_value<double>());

state = controller_->get_node()->configure();
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
Expand Down
48 changes: 24 additions & 24 deletions effort_controllers/test/test_joint_group_effort_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,9 +105,9 @@ TEST_F(JointGroupEffortControllerTest, CommandSuccessTest)
controller_interface::return_type::OK);

// check joint commands are still the default ones
ASSERT_EQ(joint_1_cmd_.get_value(), 1.1);
ASSERT_EQ(joint_2_cmd_.get_value(), 2.1);
ASSERT_EQ(joint_3_cmd_.get_value(), 3.1);
ASSERT_EQ(joint_1_cmd_.get_value<double>(), 1.1);
ASSERT_EQ(joint_2_cmd_.get_value<double>(), 2.1);
ASSERT_EQ(joint_3_cmd_.get_value<double>(), 3.1);

// send command
auto command_ptr = std::make_shared<forward_command_controller::CmdType>();
Expand All @@ -120,9 +120,9 @@ TEST_F(JointGroupEffortControllerTest, CommandSuccessTest)
controller_interface::return_type::OK);

// check joint commands have been modified
ASSERT_EQ(joint_1_cmd_.get_value(), 10.0);
ASSERT_EQ(joint_2_cmd_.get_value(), 20.0);
ASSERT_EQ(joint_3_cmd_.get_value(), 30.0);
ASSERT_EQ(joint_1_cmd_.get_value<double>(), 10.0);
ASSERT_EQ(joint_2_cmd_.get_value<double>(), 20.0);
ASSERT_EQ(joint_3_cmd_.get_value<double>(), 30.0);
}

TEST_F(JointGroupEffortControllerTest, WrongCommandCheckTest)
Expand All @@ -142,9 +142,9 @@ TEST_F(JointGroupEffortControllerTest, WrongCommandCheckTest)
controller_interface::return_type::ERROR);

// check joint commands are still the default ones
ASSERT_EQ(joint_1_cmd_.get_value(), 1.1);
ASSERT_EQ(joint_2_cmd_.get_value(), 2.1);
ASSERT_EQ(joint_3_cmd_.get_value(), 3.1);
ASSERT_EQ(joint_1_cmd_.get_value<double>(), 1.1);
ASSERT_EQ(joint_2_cmd_.get_value<double>(), 2.1);
ASSERT_EQ(joint_3_cmd_.get_value<double>(), 3.1);
}

TEST_F(JointGroupEffortControllerTest, NoCommandCheckTest)
Expand All @@ -159,9 +159,9 @@ TEST_F(JointGroupEffortControllerTest, NoCommandCheckTest)
controller_interface::return_type::OK);

// check joint commands are still the default ones
ASSERT_EQ(joint_1_cmd_.get_value(), 1.1);
ASSERT_EQ(joint_2_cmd_.get_value(), 2.1);
ASSERT_EQ(joint_3_cmd_.get_value(), 3.1);
ASSERT_EQ(joint_1_cmd_.get_value<double>(), 1.1);
ASSERT_EQ(joint_2_cmd_.get_value<double>(), 2.1);
ASSERT_EQ(joint_3_cmd_.get_value<double>(), 3.1);
}

TEST_F(JointGroupEffortControllerTest, CommandCallbackTest)
Expand All @@ -170,9 +170,9 @@ TEST_F(JointGroupEffortControllerTest, CommandCallbackTest)
controller_->get_node()->set_parameter({"joints", joint_names_});

// default values
ASSERT_EQ(joint_1_cmd_.get_value(), 1.1);
ASSERT_EQ(joint_2_cmd_.get_value(), 2.1);
ASSERT_EQ(joint_3_cmd_.get_value(), 3.1);
ASSERT_EQ(joint_1_cmd_.get_value<double>(), 1.1);
ASSERT_EQ(joint_2_cmd_.get_value<double>(), 2.1);
ASSERT_EQ(joint_3_cmd_.get_value<double>(), 3.1);

auto node_state = controller_->get_node()->configure();
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
Expand Down Expand Up @@ -203,9 +203,9 @@ TEST_F(JointGroupEffortControllerTest, CommandCallbackTest)
controller_interface::return_type::OK);

// check command in handle was set
ASSERT_EQ(joint_1_cmd_.get_value(), 10.0);
ASSERT_EQ(joint_2_cmd_.get_value(), 20.0);
ASSERT_EQ(joint_3_cmd_.get_value(), 30.0);
ASSERT_EQ(joint_1_cmd_.get_value<double>(), 10.0);
ASSERT_EQ(joint_2_cmd_.get_value<double>(), 20.0);
ASSERT_EQ(joint_3_cmd_.get_value<double>(), 30.0);
}

TEST_F(JointGroupEffortControllerTest, StopJointsOnDeactivateTest)
Expand All @@ -217,15 +217,15 @@ TEST_F(JointGroupEffortControllerTest, StopJointsOnDeactivateTest)
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);

// check joint commands are still the default ones
ASSERT_EQ(joint_1_cmd_.get_value(), 1.1);
ASSERT_EQ(joint_2_cmd_.get_value(), 2.1);
ASSERT_EQ(joint_3_cmd_.get_value(), 3.1);
ASSERT_EQ(joint_1_cmd_.get_value<double>(), 1.1);
ASSERT_EQ(joint_2_cmd_.get_value<double>(), 2.1);
ASSERT_EQ(joint_3_cmd_.get_value<double>(), 3.1);

// stop the controller
ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);

// check joint commands are now zero
ASSERT_EQ(joint_1_cmd_.get_value(), 0.0);
ASSERT_EQ(joint_2_cmd_.get_value(), 0.0);
ASSERT_EQ(joint_3_cmd_.get_value(), 0.0);
ASSERT_EQ(joint_1_cmd_.get_value<double>(), 0.0);
ASSERT_EQ(joint_2_cmd_.get_value<double>(), 0.0);
ASSERT_EQ(joint_3_cmd_.get_value<double>(), 0.0);
}
60 changes: 30 additions & 30 deletions forward_command_controller/test/test_forward_command_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -212,9 +212,9 @@ TEST_F(ForwardCommandControllerTest, CommandSuccessTest)
controller_interface::return_type::OK);

// check joint commands are still the default ones
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1);
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1);
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 3.1);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 1.1);
ASSERT_EQ(joint_2_pos_cmd_.get_value<double>(), 2.1);
ASSERT_EQ(joint_3_pos_cmd_.get_value<double>(), 3.1);

// send command
auto command_ptr = std::make_shared<forward_command_controller::CmdType>();
Expand All @@ -227,9 +227,9 @@ TEST_F(ForwardCommandControllerTest, CommandSuccessTest)
controller_interface::return_type::OK);

// check joint commands have been modified
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10.0);
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 20.0);
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 30.0);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 10.0);
ASSERT_EQ(joint_2_pos_cmd_.get_value<double>(), 20.0);
ASSERT_EQ(joint_3_pos_cmd_.get_value<double>(), 30.0);
}

TEST_F(ForwardCommandControllerTest, WrongCommandCheckTest)
Expand All @@ -255,9 +255,9 @@ TEST_F(ForwardCommandControllerTest, WrongCommandCheckTest)
controller_interface::return_type::ERROR);

// check joint commands are still the default ones
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1);
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1);
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 3.1);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 1.1);
ASSERT_EQ(joint_2_pos_cmd_.get_value<double>(), 2.1);
ASSERT_EQ(joint_3_pos_cmd_.get_value<double>(), 3.1);
}

TEST_F(ForwardCommandControllerTest, NoCommandCheckTest)
Expand All @@ -277,9 +277,9 @@ TEST_F(ForwardCommandControllerTest, NoCommandCheckTest)
controller_interface::return_type::OK);

// check joint commands are still the default ones
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1);
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1);
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 3.1);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 1.1);
ASSERT_EQ(joint_2_pos_cmd_.get_value<double>(), 2.1);
ASSERT_EQ(joint_3_pos_cmd_.get_value<double>(), 3.1);
}

TEST_F(ForwardCommandControllerTest, CommandCallbackTest)
Expand All @@ -290,9 +290,9 @@ TEST_F(ForwardCommandControllerTest, CommandCallbackTest)
controller_->get_node()->set_parameter({"interface_name", "position"});

// default values
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1);
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1);
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 3.1);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 1.1);
ASSERT_EQ(joint_2_pos_cmd_.get_value<double>(), 2.1);
ASSERT_EQ(joint_3_pos_cmd_.get_value<double>(), 3.1);

auto node_state = controller_->get_node()->configure();
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
Expand Down Expand Up @@ -323,9 +323,9 @@ TEST_F(ForwardCommandControllerTest, CommandCallbackTest)
controller_interface::return_type::OK);

// check command in handle was set
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10.0);
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 20.0);
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 30.0);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 10.0);
ASSERT_EQ(joint_2_pos_cmd_.get_value<double>(), 20.0);
ASSERT_EQ(joint_3_pos_cmd_.get_value<double>(), 30.0);
}

TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
Expand All @@ -336,9 +336,9 @@ TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
controller_->get_node()->set_parameter({"interface_name", "position"});

// default values
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1);
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 2.1);
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 3.1);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 1.1);
ASSERT_EQ(joint_2_pos_cmd_.get_value<double>(), 2.1);
ASSERT_EQ(joint_3_pos_cmd_.get_value<double>(), 3.1);

auto node_state = controller_->configure();
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
Expand Down Expand Up @@ -373,9 +373,9 @@ TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
controller_interface::return_type::OK);

// check command in handle was set
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10);
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 20);
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 30);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 10);
ASSERT_EQ(joint_2_pos_cmd_.get_value<double>(), 20);
ASSERT_EQ(joint_3_pos_cmd_.get_value<double>(), 30);

node_state = controller_->get_node()->deactivate();
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
Expand Down Expand Up @@ -425,9 +425,9 @@ TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
controller_interface::return_type::OK);

// values should not change
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10);
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 20);
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 30);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 10);
ASSERT_EQ(joint_2_pos_cmd_.get_value<double>(), 20);
ASSERT_EQ(joint_3_pos_cmd_.get_value<double>(), 30);

// set commands again
controller_->rt_command_ptr_.writeFromNonRT(command_msg);
Expand All @@ -438,7 +438,7 @@ TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
controller_interface::return_type::OK);

// check command in handle was set
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 5.5);
ASSERT_EQ(joint_2_pos_cmd_.get_value(), 6.6);
ASSERT_EQ(joint_3_pos_cmd_.get_value(), 7.7);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 5.5);
ASSERT_EQ(joint_2_pos_cmd_.get_value<double>(), 6.6);
ASSERT_EQ(joint_3_pos_cmd_.get_value<double>(), 7.7);
}
Original file line number Diff line number Diff line change
Expand Up @@ -189,9 +189,9 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateSuccess)
SetUpController(true);

// check joint commands are the default ones
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1);
ASSERT_EQ(joint_1_vel_cmd_.get_value(), 2.1);
ASSERT_EQ(joint_1_eff_cmd_.get_value(), 3.1);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 1.1);
ASSERT_EQ(joint_1_vel_cmd_.get_value<double>(), 2.1);
ASSERT_EQ(joint_1_eff_cmd_.get_value<double>(), 3.1);
}

TEST_F(MultiInterfaceForwardCommandControllerTest, CommandSuccessTest)
Expand All @@ -209,9 +209,9 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, CommandSuccessTest)
controller_interface::return_type::OK);

// check command in handle was set
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10.0);
ASSERT_EQ(joint_1_vel_cmd_.get_value(), 20.0);
ASSERT_EQ(joint_1_eff_cmd_.get_value(), 30.0);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 10.0);
ASSERT_EQ(joint_1_vel_cmd_.get_value<double>(), 20.0);
ASSERT_EQ(joint_1_eff_cmd_.get_value<double>(), 30.0);
}

TEST_F(MultiInterfaceForwardCommandControllerTest, NoCommandCheckTest)
Expand All @@ -224,9 +224,9 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, NoCommandCheckTest)
controller_interface::return_type::OK);

// check joint commands are still the default ones
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1);
ASSERT_EQ(joint_1_vel_cmd_.get_value(), 2.1);
ASSERT_EQ(joint_1_eff_cmd_.get_value(), 3.1);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 1.1);
ASSERT_EQ(joint_1_vel_cmd_.get_value<double>(), 2.1);
ASSERT_EQ(joint_1_eff_cmd_.get_value<double>(), 3.1);
}

TEST_F(MultiInterfaceForwardCommandControllerTest, WrongCommandCheckTest)
Expand All @@ -244,9 +244,9 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, WrongCommandCheckTest)
controller_interface::return_type::ERROR);

// check joint commands are still the default ones
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 1.1);
ASSERT_EQ(joint_1_vel_cmd_.get_value(), 2.1);
ASSERT_EQ(joint_1_eff_cmd_.get_value(), 3.1);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 1.1);
ASSERT_EQ(joint_1_vel_cmd_.get_value<double>(), 2.1);
ASSERT_EQ(joint_1_eff_cmd_.get_value<double>(), 3.1);
}

TEST_F(MultiInterfaceForwardCommandControllerTest, CommandCallbackTest)
Expand Down Expand Up @@ -276,9 +276,9 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, CommandCallbackTest)
controller_interface::return_type::OK);

// check command in handle was set
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10.0);
ASSERT_EQ(joint_1_vel_cmd_.get_value(), 20.0);
ASSERT_EQ(joint_1_eff_cmd_.get_value(), 30.0);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 10.0);
ASSERT_EQ(joint_1_vel_cmd_.get_value<double>(), 20.0);
ASSERT_EQ(joint_1_eff_cmd_.get_value<double>(), 30.0);
}

TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
Expand All @@ -304,9 +304,9 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateDeactivateCommandsRes
controller_interface::return_type::OK);

// check command in handle was set
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10.0);
ASSERT_EQ(joint_1_vel_cmd_.get_value(), 20.0);
ASSERT_EQ(joint_1_eff_cmd_.get_value(), 30.0);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 10.0);
ASSERT_EQ(joint_1_vel_cmd_.get_value<double>(), 20.0);
ASSERT_EQ(joint_1_eff_cmd_.get_value<double>(), 30.0);

auto node_state = controller_->get_node()->deactivate();
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
Expand Down Expand Up @@ -355,9 +355,9 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateDeactivateCommandsRes
controller_interface::return_type::OK);

// values should not change
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 10.0);
ASSERT_EQ(joint_1_vel_cmd_.get_value(), 20.0);
ASSERT_EQ(joint_1_eff_cmd_.get_value(), 30.0);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 10.0);
ASSERT_EQ(joint_1_vel_cmd_.get_value<double>(), 20.0);
ASSERT_EQ(joint_1_eff_cmd_.get_value<double>(), 30.0);

// set commands again
controller_->rt_command_ptr_.writeFromNonRT(command_msg);
Expand All @@ -368,7 +368,7 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateDeactivateCommandsRes
controller_interface::return_type::OK);

// check command in handle was set
ASSERT_EQ(joint_1_pos_cmd_.get_value(), 5.5);
ASSERT_EQ(joint_1_vel_cmd_.get_value(), 6.6);
ASSERT_EQ(joint_1_eff_cmd_.get_value(), 7.7);
ASSERT_EQ(joint_1_pos_cmd_.get_value<double>(), 5.5);
ASSERT_EQ(joint_1_vel_cmd_.get_value<double>(), 6.6);
ASSERT_EQ(joint_1_eff_cmd_.get_value<double>(), 7.7);
}
Loading