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

[JTC] Activate checks for parameter validation #857

Merged
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
139 changes: 70 additions & 69 deletions joint_trajectory_controller/test/test_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2005,72 +2005,73 @@ INSTANTIATE_TEST_SUITE_P(
std::vector<std::string>({"effort"}),
std::vector<std::string>({"position", "velocity", "acceleration"}))));

// TODO(destogl): this tests should be changed because we are using `generate_parameters_library`
// TEST_F(TrajectoryControllerTest, incorrect_initialization_using_interface_parameters)
// {
// auto set_parameter_and_check_result = [&]()
// {
// EXPECT_EQ(traj_controller_->get_state().id(), State::PRIMARY_STATE_UNCONFIGURED);
// SetParameters(); // This call is replacing the way parameters are set via launch
// traj_controller_->get_node()->configure();
// EXPECT_EQ(traj_controller_->get_state().id(), State::PRIMARY_STATE_UNCONFIGURED);
// };
//
// SetUpTrajectoryController(false);
//
// // command interfaces: empty
// command_interface_types_ = {};
// set_parameter_and_check_result();
//
// // command interfaces: bad_name
// command_interface_types_ = {"bad_name"};
// set_parameter_and_check_result();
//
// // command interfaces: effort has to be only
// command_interface_types_ = {"effort", "position"};
// set_parameter_and_check_result();
//
// // command interfaces: velocity - position not present
// command_interface_types_ = {"velocity", "acceleration"};
// set_parameter_and_check_result();
//
// // command interfaces: acceleration without position and velocity
// command_interface_types_ = {"acceleration"};
// set_parameter_and_check_result();
//
// // state interfaces: empty
// state_interface_types_ = {};
// set_parameter_and_check_result();
//
// // state interfaces: cannot not be effort
// state_interface_types_ = {"effort"};
// set_parameter_and_check_result();
//
// // state interfaces: bad name
// state_interface_types_ = {"bad_name"};
// set_parameter_and_check_result();
//
// // state interfaces: velocity - position not present
// state_interface_types_ = {"velocity"};
// set_parameter_and_check_result();
// state_interface_types_ = {"velocity", "acceleration"};
// set_parameter_and_check_result();
//
// // state interfaces: acceleration without position and velocity
// state_interface_types_ = {"acceleration"};
// set_parameter_and_check_result();
//
// // velocity-only command interface: position - velocity not present
// command_interface_types_ = {"velocity"};
// state_interface_types_ = {"position"};
// set_parameter_and_check_result();
// state_interface_types_ = {"velocity"};
// set_parameter_and_check_result();
//
// // effort-only command interface: position - velocity not present
// command_interface_types_ = {"effort"};
// state_interface_types_ = {"position"};
// set_parameter_and_check_result();
// state_interface_types_ = {"velocity"};
// set_parameter_and_check_result();
// }
/**
* @brief see if parameter validation is correct
*
* Note: generate_parameter_library validates parameters itself during on_init() method, but
* combinations of parameters are checked from JTC during on_configure()
*/
TEST_F(TrajectoryControllerTest, incorrect_initialization_using_interface_parameters)
{
// command interfaces: empty
command_interface_types_ = {};
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::OK);
traj_controller_->get_node()->configure();
christophfroehlich marked this conversation as resolved.
Show resolved Hide resolved
EXPECT_EQ(traj_controller_->get_state().id(), State::PRIMARY_STATE_UNCONFIGURED);

// command interfaces: bad_name
command_interface_types_ = {"bad_name"};
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::ERROR);

// command interfaces: effort has to be only
command_interface_types_ = {"effort", "position"};
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::ERROR);

// command interfaces: velocity - position not present
command_interface_types_ = {"velocity", "acceleration"};
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::ERROR);

// command interfaces: acceleration without position and velocity
command_interface_types_ = {"acceleration"};
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::ERROR);

// state interfaces: empty
state_interface_types_ = {};
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::ERROR);

// state interfaces: cannot not be effort
state_interface_types_ = {"effort"};
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::ERROR);

// state interfaces: bad name
state_interface_types_ = {"bad_name"};
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::ERROR);

// state interfaces: velocity - position not present
state_interface_types_ = {"velocity"};
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::ERROR);
state_interface_types_ = {"velocity", "acceleration"};
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::ERROR);

// state interfaces: acceleration without position and velocity
state_interface_types_ = {"acceleration"};
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::ERROR);

// velocity-only command interface: position - velocity not present
command_interface_types_ = {"velocity"};
state_interface_types_ = {"position"};
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::OK);
traj_controller_->get_node()->configure();
EXPECT_EQ(traj_controller_->get_state().id(), State::PRIMARY_STATE_UNCONFIGURED);
christophfroehlich marked this conversation as resolved.
Show resolved Hide resolved
state_interface_types_ = {"velocity"};
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::ERROR);

// effort-only command interface: position - velocity not present
command_interface_types_ = {"effort"};
state_interface_types_ = {"position"};
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::OK);
traj_controller_->get_node()->configure();
christophfroehlich marked this conversation as resolved.
Show resolved Hide resolved
EXPECT_EQ(traj_controller_->get_state().id(), State::PRIMARY_STATE_UNCONFIGURED);
state_interface_types_ = {"velocity"};
EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::ERROR);
}
Original file line number Diff line number Diff line change
Expand Up @@ -184,6 +184,17 @@ class TrajectoryControllerTest : public ::testing::Test

void SetUpTrajectoryController(
rclcpp::Executor & executor, const std::vector<rclcpp::Parameter> & parameters = {})
{
auto ret = SetUpTrajectoryControllerLocal(parameters);
if (ret != controller_interface::return_type::OK)
{
FAIL();
}
executor.add_node(traj_controller_->get_node()->get_node_base_interface());
}

controller_interface::return_type SetUpTrajectoryControllerLocal(
const std::vector<rclcpp::Parameter> & parameters = {})
{
traj_controller_ = std::make_shared<TestableJointTrajectoryController>();

Expand All @@ -196,12 +207,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);
if (ret != controller_interface::return_type::OK)
{
FAIL();
}
executor.add_node(traj_controller_->get_node()->get_node_base_interface());
return traj_controller_->init(controller_name_, "", 0, "", node_options);
}

void SetPidParameters(
Expand Down