Skip to content
Draft
146 changes: 85 additions & 61 deletions diff_drive_controller/test/test_diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -198,6 +198,27 @@ class TestDiffDriveController : public ::testing::Test
return controller_->init(controller_name, urdf_, 0, ns, node_options);
}

void expect_configure_succeeded(
std::unique_ptr<TestableDiffDriveController> & controller, bool succeeded)
{
auto state = controller->configure();

if (succeeded)
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
else
ASSERT_EQ(State::PRIMARY_STATE_UNCONFIGURED, state.id());
}

void expect_activate_succeeded(
std::unique_ptr<TestableDiffDriveController> & controller, bool succeeded)
{
auto state = controller->get_node()->activate();
if (succeeded)
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
else
ASSERT_EQ(State::PRIMARY_STATE_UNCONFIGURED, state.id());
}

std::string controller_name;
std::unique_ptr<TestableDiffDriveController> controller_;

Expand Down Expand Up @@ -243,7 +264,7 @@ TEST_F(TestDiffDriveController, configure_fails_with_mismatching_wheel_side_size
InitController(left_wheel_names, {right_wheel_names[0], "extra_wheel"}),
controller_interface::return_type::OK);

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::ERROR);
expect_configure_succeeded(controller_, false);
}

TEST_F(
Expand All @@ -252,7 +273,7 @@ TEST_F(
{
ASSERT_EQ(InitController(), controller_interface::return_type::OK);

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
expect_configure_succeeded(controller_, true);

auto state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, SizeIs(left_wheel_names.size() + right_wheel_names.size()));
Expand All @@ -277,7 +298,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_false_no_names
rclcpp::Parameter("base_frame_id", rclcpp::ParameterValue(base_link_id))}),
controller_interface::return_type::OK);

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
expect_configure_succeeded(controller_, true);

auto odometry_message = controller_->get_rt_odom_publisher()->msg_;
std::string test_odom_frame_id = odometry_message.header.frame_id;
Expand All @@ -302,7 +323,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_true_no_namesp
rclcpp::Parameter("base_frame_id", rclcpp::ParameterValue(base_link_id))}),
controller_interface::return_type::OK);

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
expect_configure_succeeded(controller_, true);

auto odometry_message = controller_->get_rt_odom_publisher()->msg_;
std::string test_odom_frame_id = odometry_message.header.frame_id;
Expand All @@ -329,7 +350,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_blank_prefix_true_no_names
rclcpp::Parameter("base_frame_id", rclcpp::ParameterValue(base_link_id))}),
controller_interface::return_type::OK);

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
expect_configure_succeeded(controller_, true);

auto odometry_message = controller_->get_rt_odom_publisher()->msg_;
std::string test_odom_frame_id = odometry_message.header.frame_id;
Expand Down Expand Up @@ -358,7 +379,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_false_set_name
test_namespace),
controller_interface::return_type::OK);

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
expect_configure_succeeded(controller_, true);

auto odometry_message = controller_->get_rt_odom_publisher()->msg_;
std::string test_odom_frame_id = odometry_message.header.frame_id;
Expand Down Expand Up @@ -386,7 +407,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_test_prefix_true_set_names
test_namespace),
controller_interface::return_type::OK);

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
expect_configure_succeeded(controller_, true);

auto odometry_message = controller_->get_rt_odom_publisher()->msg_;
std::string test_odom_frame_id = odometry_message.header.frame_id;
Expand Down Expand Up @@ -415,7 +436,7 @@ TEST_F(TestDiffDriveController, configure_succeeds_tf_blank_prefix_true_set_name
test_namespace),
controller_interface::return_type::OK);

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
expect_configure_succeeded(controller_, true);

auto odometry_message = controller_->get_rt_odom_publisher()->msg_;
std::string test_odom_frame_id = odometry_message.header.frame_id;
Expand All @@ -431,18 +452,21 @@ TEST_F(TestDiffDriveController, activate_fails_without_resources_assigned)
{
ASSERT_EQ(InitController(), controller_interface::return_type::OK);

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), CallbackReturn::ERROR);
expect_configure_succeeded(controller_, true);

expect_activate_succeeded(controller_, false);
}

TEST_F(TestDiffDriveController, activate_succeeds_with_pos_resources_assigned)
{
ASSERT_EQ(InitController(), controller_interface::return_type::OK);

// We implicitly test that by default position feedback is required
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
expect_configure_succeeded(controller_, true);

assignResourcesPosFeedback();
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);

expect_activate_succeeded(controller_, true);
}

TEST_F(TestDiffDriveController, activate_succeeds_with_vel_resources_assigned)
Expand All @@ -453,9 +477,11 @@ TEST_F(TestDiffDriveController, activate_succeeds_with_vel_resources_assigned)
{rclcpp::Parameter("position_feedback", rclcpp::ParameterValue(false))}),
controller_interface::return_type::OK);

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
expect_configure_succeeded(controller_, true);

assignResourcesVelFeedback();
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);

expect_activate_succeeded(controller_, true);
}

TEST_F(TestDiffDriveController, test_speed_limiter)
Expand Down Expand Up @@ -487,12 +513,12 @@ TEST_F(TestDiffDriveController, test_speed_limiter)

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(controller_->get_node()->get_node_base_interface());
auto state = controller_->configure();
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());

expect_configure_succeeded(controller_, true);

assignResourcesPosFeedback();

state = controller_->get_node()->activate();
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
expect_activate_succeeded(controller_, true);

waitForSetup();

Expand Down Expand Up @@ -672,9 +698,11 @@ TEST_F(TestDiffDriveController, activate_fails_with_wrong_resources_assigned_1)
{rclcpp::Parameter("position_feedback", rclcpp::ParameterValue(false))}),
controller_interface::return_type::OK);

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
expect_configure_succeeded(controller_, true);

assignResourcesPosFeedback();
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), CallbackReturn::ERROR);

expect_activate_succeeded(controller_, false);
}

TEST_F(TestDiffDriveController, activate_fails_with_wrong_resources_assigned_2)
Expand All @@ -685,9 +713,11 @@ TEST_F(TestDiffDriveController, activate_fails_with_wrong_resources_assigned_2)
{rclcpp::Parameter("position_feedback", rclcpp::ParameterValue(true))}),
controller_interface::return_type::OK);

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
expect_configure_succeeded(controller_, true);

assignResourcesVelFeedback();
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), CallbackReturn::ERROR);

expect_activate_succeeded(controller_, false);
}

TEST_F(TestDiffDriveController, cleanup)
Expand All @@ -700,12 +730,12 @@ TEST_F(TestDiffDriveController, cleanup)

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(controller_->get_node()->get_node_base_interface());
auto state = controller_->configure();
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());

expect_configure_succeeded(controller_, true);

assignResourcesPosFeedback();

state = controller_->get_node()->activate();
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
expect_activate_succeeded(controller_, true);

waitForSetup();

Expand All @@ -723,7 +753,7 @@ TEST_F(TestDiffDriveController, cleanup)
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();
auto state = controller_->get_node()->deactivate();
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());

// should be stopped
Expand Down Expand Up @@ -753,15 +783,14 @@ TEST_F(TestDiffDriveController, correct_initialization_using_parameters)
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(controller_->get_node()->get_node_base_interface());

auto state = controller_->configure();
expect_configure_succeeded(controller_, true);

assignResourcesPosFeedback();

ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
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());
expect_activate_succeeded(controller_, true);

// send msg
const double linear = 1.0;
Expand All @@ -779,7 +808,7 @@ TEST_F(TestDiffDriveController, correct_initialization_using_parameters)
// deactivated
// wait so controller process the second point when deactivated
std::this_thread::sleep_for(std::chrono::milliseconds(500));
state = controller_->get_node()->deactivate();
auto state = controller_->get_node()->deactivate();
ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE);
ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
Expand All @@ -795,8 +824,8 @@ TEST_F(TestDiffDriveController, correct_initialization_using_parameters)
EXPECT_EQ(0.0, left_wheel_vel_cmd_.get_optional().value());
EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value());

state = controller_->configure();
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
expect_configure_succeeded(controller_, true);

executor.cancel();
}

Expand All @@ -821,12 +850,11 @@ TEST_F(TestDiffDriveController, chainable_controller_unchained_mode)
ASSERT_TRUE(controller_->set_chained_mode(false));
ASSERT_FALSE(controller_->is_in_chained_mode());

auto state = controller_->configure();
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
expect_configure_succeeded(controller_, true);

assignResourcesPosFeedback();

state = controller_->get_node()->activate();
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
expect_activate_succeeded(controller_, true);

waitForSetup();

Expand Down Expand Up @@ -873,7 +901,7 @@ TEST_F(TestDiffDriveController, chainable_controller_unchained_mode)
// Now check that the command interfaces are set to 0.0 on deactivation
// (despite calls to update())
std::this_thread::sleep_for(std::chrono::milliseconds(300));
state = controller_->get_node()->deactivate();
auto state = controller_->get_node()->deactivate();
ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE);
ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
Expand All @@ -892,8 +920,8 @@ TEST_F(TestDiffDriveController, chainable_controller_unchained_mode)
EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value())
<< "Wheels should be halted on cleanup()";

state = controller_->configure();
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
expect_configure_succeeded(controller_, true);

executor.cancel();
}

Expand All @@ -917,12 +945,11 @@ TEST_F(TestDiffDriveController, chainable_controller_chained_mode)
ASSERT_TRUE(controller_->set_chained_mode(true));
ASSERT_TRUE(controller_->is_in_chained_mode());

auto state = controller_->configure();
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
expect_configure_succeeded(controller_, true);

assignResourcesPosFeedback();

state = controller_->get_node()->activate();
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
expect_activate_succeeded(controller_, true);

waitForSetup();

Expand Down Expand Up @@ -952,7 +979,7 @@ TEST_F(TestDiffDriveController, chainable_controller_chained_mode)
// Now check that the command interfaces are set to 0.0 on deactivation
// (despite calls to update())
std::this_thread::sleep_for(std::chrono::milliseconds(300));
state = controller_->get_node()->deactivate();
auto state = controller_->get_node()->deactivate();
ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE);
ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
Expand All @@ -971,8 +998,8 @@ TEST_F(TestDiffDriveController, chainable_controller_chained_mode)
EXPECT_EQ(0.0, right_wheel_vel_cmd_.get_optional().value())
<< "Wheels should be halted on cleanup()";

state = controller_->configure();
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
expect_configure_succeeded(controller_, true);

executor.cancel();
}

Expand All @@ -981,7 +1008,7 @@ TEST_F(TestDiffDriveController, reference_interfaces_are_properly_exported)
ASSERT_EQ(
InitController(left_wheel_names, right_wheel_names), controller_interface::return_type::OK);

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
expect_configure_succeeded(controller_, true);

auto reference_interfaces = controller_->export_reference_interfaces();
ASSERT_EQ(reference_interfaces.size(), 2)
Expand Down Expand Up @@ -1021,12 +1048,11 @@ TEST_F(TestDiffDriveController, deactivate_then_activate)

ASSERT_TRUE(controller_->set_chained_mode(false));

auto state = controller_->configure();
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
expect_configure_succeeded(controller_, true);

assignResourcesPosFeedback();

state = controller_->get_node()->activate();
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
expect_activate_succeeded(controller_, true);

waitForSetup();

Expand Down Expand Up @@ -1057,7 +1083,7 @@ TEST_F(TestDiffDriveController, deactivate_then_activate)
// Now check that the command interfaces are set to 0.0 on deactivation
// (despite calls to update())
std::this_thread::sleep_for(std::chrono::milliseconds(300));
state = controller_->get_node()->deactivate();
auto state = controller_->get_node()->deactivate();
ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE);
ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
Expand All @@ -1069,8 +1095,7 @@ TEST_F(TestDiffDriveController, deactivate_then_activate)
<< "Wheels should be halted on deactivate()";

// Activate again
state = controller_->get_node()->activate();
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
expect_activate_succeeded(controller_, true);

waitForSetup();

Expand Down Expand Up @@ -1119,12 +1144,11 @@ TEST_F(TestDiffDriveController, command_with_zero_timestamp_is_accepted_with_war

ASSERT_TRUE(controller_->set_chained_mode(false));

auto state = controller_->configure();
ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id());
expect_configure_succeeded(controller_, true);

assignResourcesPosFeedback();

state = controller_->get_node()->activate();
ASSERT_EQ(State::PRIMARY_STATE_ACTIVE, state.id());
expect_activate_succeeded(controller_, true);

waitForSetup();

Expand All @@ -1142,7 +1166,7 @@ TEST_F(TestDiffDriveController, command_with_zero_timestamp_is_accepted_with_war

// Deactivate and cleanup
std::this_thread::sleep_for(std::chrono::milliseconds(300));
state = controller_->get_node()->deactivate();
auto state = controller_->get_node()->deactivate();
ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE);
state = controller_->get_node()->cleanup();
ASSERT_EQ(state.id(), State::PRIMARY_STATE_UNCONFIGURED);
Expand Down
Loading
Loading