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

Add modifications corresponding new get_value API #1467

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
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
53 changes: 29 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,10 @@ 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);
bool status;
ASSERT_EQ(joint_1_cmd_.get_value(status), 1.1);
ASSERT_EQ(joint_2_cmd_.get_value(status), 2.1);
ASSERT_EQ(joint_3_cmd_.get_value(status), 3.1);

// send command
auto command_ptr = std::make_shared<forward_command_controller::CmdType>();
Expand All @@ -120,9 +121,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(status), 10.0);
ASSERT_EQ(joint_2_cmd_.get_value(status), 20.0);
ASSERT_EQ(joint_3_cmd_.get_value(status), 30.0);
}

TEST_F(JointGroupEffortControllerTest, WrongCommandCheckTest)
Expand All @@ -142,9 +143,10 @@ 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);
bool status;
ASSERT_EQ(joint_1_cmd_.get_value(status), 1.1);
ASSERT_EQ(joint_2_cmd_.get_value(status), 2.1);
ASSERT_EQ(joint_3_cmd_.get_value(status), 3.1);
}

TEST_F(JointGroupEffortControllerTest, NoCommandCheckTest)
Expand All @@ -159,9 +161,10 @@ 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);
bool status;
ASSERT_EQ(joint_1_cmd_.get_value(status), 1.1);
ASSERT_EQ(joint_2_cmd_.get_value(status), 2.1);
ASSERT_EQ(joint_3_cmd_.get_value(status), 3.1);
}

TEST_F(JointGroupEffortControllerTest, CommandCallbackTest)
Expand All @@ -170,9 +173,10 @@ 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);
bool status;
ASSERT_EQ(joint_1_cmd_.get_value(status), 1.1);
ASSERT_EQ(joint_2_cmd_.get_value(status), 2.1);
ASSERT_EQ(joint_3_cmd_.get_value(status), 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 +207,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(status), 10.0);
ASSERT_EQ(joint_2_cmd_.get_value(status), 20.0);
ASSERT_EQ(joint_3_cmd_.get_value(status), 30.0);
}

TEST_F(JointGroupEffortControllerTest, StopJointsOnDeactivateTest)
Expand All @@ -217,15 +221,16 @@ 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);
bool status;
ASSERT_EQ(joint_1_cmd_.get_value(status), 1.1);
ASSERT_EQ(joint_2_cmd_.get_value(status), 2.1);
ASSERT_EQ(joint_3_cmd_.get_value(status), 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(status), 0.0);
ASSERT_EQ(joint_2_cmd_.get_value(status), 0.0);
ASSERT_EQ(joint_3_cmd_.get_value(status), 0.0);
}
Loading