Skip to content
Open
Show file tree
Hide file tree
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
149 changes: 88 additions & 61 deletions diff_drive_controller/test/test_diff_drive_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -203,6 +203,30 @@ class TestDiffDriveController : public ::testing::Test
return controller_->init(controller_name, urdf_, 0, ns, node_options);
}

bool is_configure_succeeded(const std::unique_ptr<TestableDiffDriveController> & controller)
{
auto state = controller->configure();
return State::PRIMARY_STATE_INACTIVE == state.id();
}

bool is_configure_failed(const std::unique_ptr<TestableDiffDriveController> & controller)
{
auto state = controller->configure();
return State::PRIMARY_STATE_UNCONFIGURED == state.id();
}

bool is_activate_succeeded(const std::unique_ptr<TestableDiffDriveController> & controller)
{
auto state = controller->get_node()->activate();
return State::PRIMARY_STATE_ACTIVE == state.id();
}

bool is_activate_failed(const std::unique_ptr<TestableDiffDriveController> & controller)
{
auto state = controller->get_node()->activate();
return State::PRIMARY_STATE_UNCONFIGURED == state.id();
}

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

Expand Down Expand Up @@ -248,7 +272,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);
ASSERT_TRUE(is_configure_failed(controller_));
}

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

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
ASSERT_TRUE(is_configure_succeeded(controller_));

auto state_if_conf = controller_->state_interface_configuration();
ASSERT_THAT(state_if_conf.names, SizeIs(left_wheel_names.size() + right_wheel_names.size()));
Expand Down Expand Up @@ -302,7 +326,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);
ASSERT_TRUE(is_configure_succeeded(controller_));

auto odometry_message = controller_->get_rt_odom_publisher()->msg_;
std::string test_odom_frame_id = odometry_message.header.frame_id;
Expand All @@ -327,7 +351,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);
ASSERT_TRUE(is_configure_succeeded(controller_));

auto odometry_message = controller_->get_rt_odom_publisher()->msg_;
std::string test_odom_frame_id = odometry_message.header.frame_id;
Expand All @@ -354,7 +378,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);
ASSERT_TRUE(is_configure_succeeded(controller_));

auto odometry_message = controller_->get_rt_odom_publisher()->msg_;
std::string test_odom_frame_id = odometry_message.header.frame_id;
Expand Down Expand Up @@ -383,7 +407,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);
ASSERT_TRUE(is_configure_succeeded(controller_));

auto odometry_message = controller_->get_rt_odom_publisher()->msg_;
std::string test_odom_frame_id = odometry_message.header.frame_id;
Expand Down Expand Up @@ -411,7 +435,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);
ASSERT_TRUE(is_configure_succeeded(controller_));

auto odometry_message = controller_->get_rt_odom_publisher()->msg_;
std::string test_odom_frame_id = odometry_message.header.frame_id;
Expand Down Expand Up @@ -440,7 +464,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);
ASSERT_TRUE(is_configure_succeeded(controller_));

auto odometry_message = controller_->get_rt_odom_publisher()->msg_;
std::string test_odom_frame_id = odometry_message.header.frame_id;
Expand All @@ -456,18 +480,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);
ASSERT_TRUE(is_configure_succeeded(controller_));

ASSERT_TRUE(is_activate_failed(controller_));
}

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);
ASSERT_TRUE(is_configure_succeeded(controller_));

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

ASSERT_TRUE(is_activate_succeeded(controller_));
}

TEST_F(TestDiffDriveController, activate_succeeds_with_vel_resources_assigned)
Expand All @@ -478,9 +505,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);
ASSERT_TRUE(is_configure_succeeded(controller_));

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

ASSERT_TRUE(is_activate_succeeded(controller_));
}

TEST_F(TestDiffDriveController, activate_succeeds_with_open_loop_assigned)
Expand Down Expand Up @@ -525,12 +554,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());

ASSERT_TRUE(is_configure_succeeded(controller_));

assignResourcesPosFeedback();

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

waitForSetup();

Expand Down Expand Up @@ -710,9 +739,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);
ASSERT_TRUE(is_configure_succeeded(controller_));

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

ASSERT_TRUE(is_activate_failed(controller_));
}

TEST_F(TestDiffDriveController, activate_fails_with_wrong_resources_assigned_2)
Expand All @@ -723,9 +754,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);
ASSERT_TRUE(is_configure_succeeded(controller_));

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

ASSERT_TRUE(is_activate_failed(controller_));
}

TEST_F(TestDiffDriveController, activate_silently_ignores_with_unnecessary_resources_assigned_1)
Expand Down Expand Up @@ -766,12 +799,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());

ASSERT_TRUE(is_configure_succeeded(controller_));

assignResourcesPosFeedback();

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

waitForSetup();

Expand All @@ -789,7 +822,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 @@ -819,15 +852,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();
ASSERT_TRUE(is_configure_succeeded(controller_));

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());
ASSERT_TRUE(is_activate_succeeded(controller_));

// send msg
const double linear = 1.0;
Expand All @@ -845,7 +877,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 @@ -861,8 +893,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());
ASSERT_TRUE(is_configure_succeeded(controller_));

executor.cancel();
}

Expand All @@ -887,12 +919,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());
ASSERT_TRUE(is_configure_succeeded(controller_));

assignResourcesPosFeedback();

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

waitForSetup();

Expand Down Expand Up @@ -939,7 +970,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 @@ -958,8 +989,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());
ASSERT_TRUE(is_configure_succeeded(controller_));

executor.cancel();
}

Expand All @@ -983,12 +1014,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());
ASSERT_TRUE(is_configure_succeeded(controller_));

assignResourcesPosFeedback();

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

waitForSetup();

Expand Down Expand Up @@ -1018,7 +1048,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 @@ -1037,8 +1067,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());
ASSERT_TRUE(is_configure_succeeded(controller_));

executor.cancel();
}

Expand All @@ -1047,7 +1077,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);
ASSERT_TRUE(is_configure_succeeded(controller_));

auto reference_interfaces = controller_->export_reference_interfaces();
ASSERT_EQ(reference_interfaces.size(), 2)
Expand Down Expand Up @@ -1087,12 +1117,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());
ASSERT_TRUE(is_configure_succeeded(controller_));

assignResourcesPosFeedback();

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

waitForSetup();

Expand Down Expand Up @@ -1123,7 +1152,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 @@ -1135,8 +1164,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());
ASSERT_TRUE(is_activate_succeeded(controller_));

waitForSetup();

Expand Down Expand Up @@ -1185,12 +1213,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());
ASSERT_TRUE(is_configure_succeeded(controller_));

assignResourcesPosFeedback();

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

waitForSetup();

Expand All @@ -1208,7 +1235,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