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
50 changes: 25 additions & 25 deletions admittance_controller/test/test_admittance_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ TEST_F(AdmittanceControllerTest, all_parameters_set_configure_success)

ASSERT_EQ(result, controller_interface::return_type::OK);

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));

ASSERT_TRUE(!controller_->admittance_->parameters_.joints.empty());
ASSERT_TRUE(controller_->admittance_->parameters_.joints.size() == joint_names_.size());
Expand Down Expand Up @@ -156,7 +156,7 @@ TEST_F(AdmittanceControllerTest, check_interfaces)
{
SetUpController();

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));

auto command_interfaces = controller_->command_interface_configuration();
ASSERT_EQ(command_interfaces.names.size(), joint_command_values_.size());
Expand Down Expand Up @@ -200,26 +200,26 @@ TEST_F(AdmittanceControllerTest, activate_success)
{
SetUpController();

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
ASSERT_EQ(
controller_->command_interfaces_.size(), command_interface_types_.size() * joint_names_.size());
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(activate_succeeds(controller_));
}

TEST_F(AdmittanceControllerTest, missing_pos_state_interface)
{
auto overrides = {rclcpp::Parameter("state_interfaces", std::vector<std::string>{"velocity"})};
SetUpController("test_admittance_controller", overrides);
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_FAILURE);
ASSERT_FALSE(configure_succeeds(controller_));
}

TEST_F(AdmittanceControllerTest, only_vel_command_interface)
{
command_interface_types_ = {"velocity"};
auto overrides = {rclcpp::Parameter("command_interfaces", std::vector<std::string>{"velocity"})};
SetUpController("test_admittance_controller", overrides);
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
ASSERT_TRUE(activate_succeeds(controller_));
ASSERT_EQ(
controller_->update_and_write_commands(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
controller_interface::return_type::OK);
Expand All @@ -230,31 +230,31 @@ TEST_F(AdmittanceControllerTest, only_pos_reference_interface)
auto overrides = {
rclcpp::Parameter("chainable_command_interfaces", std::vector<std::string>{"position"})};
SetUpController("test_admittance_controller", overrides);
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
}

TEST_F(AdmittanceControllerTest, only_vel_reference_interface)
{
auto overrides = {
rclcpp::Parameter("chainable_command_interfaces", std::vector<std::string>{"velocity"})};
SetUpController("test_admittance_controller", overrides);
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
}

TEST_F(AdmittanceControllerTest, invalid_reference_interface)
{
auto overrides = {rclcpp::Parameter(
"chainable_command_interfaces", std::vector<std::string>{"invalid_interface"})};
SetUpController("test_admittance_controller", overrides);
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_ERROR);
ASSERT_FALSE(configure_succeeds(controller_));
}

TEST_F(AdmittanceControllerTest, update_success)
{
SetUpController();

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
ASSERT_TRUE(activate_succeeds(controller_));
broadcast_tfs();
ASSERT_EQ(
controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
Expand All @@ -265,20 +265,20 @@ TEST_F(AdmittanceControllerTest, deactivate_success)
{
SetUpController();

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
ASSERT_TRUE(activate_succeeds(controller_));
ASSERT_TRUE(deactivate_succeeds(controller_));
}

TEST_F(AdmittanceControllerTest, reactivate_success)
{
SetUpController();

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
ASSERT_TRUE(activate_succeeds(controller_));
ASSERT_TRUE(deactivate_succeeds(controller_));
assign_interfaces();
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(activate_succeeds(controller_));
broadcast_tfs();
ASSERT_EQ(
controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
Expand All @@ -289,8 +289,8 @@ TEST_F(AdmittanceControllerTest, publish_status_success)
{
SetUpController();

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
ASSERT_TRUE(activate_succeeds(controller_));

broadcast_tfs();
ASSERT_EQ(
Expand Down Expand Up @@ -325,8 +325,8 @@ TEST_F(AdmittanceControllerTest, receive_message_and_publish_updated_status)
rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(controller_->get_node()->get_node_base_interface());

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
ASSERT_TRUE(activate_succeeds(controller_));
broadcast_tfs();
ASSERT_EQ(
controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)),
Expand Down Expand Up @@ -360,8 +360,8 @@ TEST_F(AdmittanceControllerTest, check_frame_ids_in_controller_state)
{
SetUpController();

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
ASSERT_TRUE(activate_succeeds(controller_));

broadcast_tfs(); // force torque sensor

Expand Down
6 changes: 6 additions & 0 deletions admittance_controller/test/test_admittance_controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@

#include "admittance_controller/admittance_controller.hpp"
#include "control_msgs/msg/admittance_controller_state.hpp"
#include "controller_interface/test_utils.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "hardware_interface/loaned_command_interface.hpp"
#include "hardware_interface/loaned_state_interface.hpp"
Expand All @@ -50,6 +51,11 @@ using ControllerCommandPoseMsg = geometry_msgs::msg::PoseStamped;
using ControllerCommandJointMsg = trajectory_msgs::msg::JointTrajectoryPoint;
using ControllerStateMsg = control_msgs::msg::AdmittanceControllerState;

using controller_interface::activate_succeeds;
using controller_interface::cleanup_succeeds;
using controller_interface::configure_succeeds;
using controller_interface::deactivate_succeeds;

namespace
{
const double COMMON_THRESHOLD = 0.001;
Expand Down
40 changes: 10 additions & 30 deletions pose_broadcaster/test/test_pose_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,7 @@ TEST_F(PoseBroadcasterTest, Configure_Success)
pose_broadcaster_->get_node()->set_parameter({"frame_id", frame_id_});

// Configure controller
ASSERT_EQ(
pose_broadcaster_->on_configure(rclcpp_lifecycle::State{}),
controller_interface::CallbackReturn::SUCCESS);
ASSERT_TRUE(configure_succeeds(pose_broadcaster_));

// Verify command interface configuration
const auto command_interface_conf = pose_broadcaster_->command_interface_configuration();
Expand All @@ -81,12 +79,8 @@ TEST_F(PoseBroadcasterTest, Activate_Success)
pose_broadcaster_->get_node()->set_parameter({"frame_id", frame_id_});

// Configure and activate controller
ASSERT_EQ(
pose_broadcaster_->on_configure(rclcpp_lifecycle::State{}),
controller_interface::CallbackReturn::SUCCESS);
ASSERT_EQ(
pose_broadcaster_->on_activate(rclcpp_lifecycle::State{}),
controller_interface::CallbackReturn::SUCCESS);
ASSERT_TRUE(configure_succeeds(pose_broadcaster_));
ASSERT_TRUE(activate_succeeds(pose_broadcaster_));

// Verify command and state interface configuration
{
Expand All @@ -102,9 +96,7 @@ TEST_F(PoseBroadcasterTest, Activate_Success)
}

// Deactivate controller
ASSERT_EQ(
pose_broadcaster_->on_deactivate(rclcpp_lifecycle::State{}),
controller_interface::CallbackReturn::SUCCESS);
ASSERT_TRUE(deactivate_succeeds(pose_broadcaster_));

// Verify command and state interface configuration
{
Expand All @@ -129,12 +121,8 @@ TEST_F(PoseBroadcasterTest, Update_Success)
pose_broadcaster_->get_node()->set_parameter({"frame_id", frame_id_});

// Configure and activate controller
ASSERT_EQ(
pose_broadcaster_->on_configure(rclcpp_lifecycle::State{}),
controller_interface::CallbackReturn::SUCCESS);
ASSERT_EQ(
pose_broadcaster_->on_activate(rclcpp_lifecycle::State{}),
controller_interface::CallbackReturn::SUCCESS);
ASSERT_TRUE(configure_succeeds(pose_broadcaster_));
ASSERT_TRUE(activate_succeeds(pose_broadcaster_));

ASSERT_EQ(
pose_broadcaster_->update(rclcpp::Time{0}, rclcpp::Duration::from_seconds(0.01)),
Expand All @@ -154,12 +142,8 @@ TEST_F(PoseBroadcasterTest, PublishSuccess)
pose_broadcaster_->get_node()->set_parameter({"tf.child_frame_id", tf_child_frame_id_});

// Configure and activate controller
ASSERT_EQ(
pose_broadcaster_->on_configure(rclcpp_lifecycle::State{}),
controller_interface::CallbackReturn::SUCCESS);
ASSERT_EQ(
pose_broadcaster_->on_activate(rclcpp_lifecycle::State{}),
controller_interface::CallbackReturn::SUCCESS);
ASSERT_TRUE(configure_succeeds(pose_broadcaster_));
ASSERT_TRUE(activate_succeeds(pose_broadcaster_));

// Subscribe to pose topic
geometry_msgs::msg::PoseStamped pose_msg;
Expand Down Expand Up @@ -205,12 +189,8 @@ TEST_F(PoseBroadcasterTest, invalid_pose_no_tf_published)
pose_broadcaster_->get_node()->set_parameter({"tf.child_frame_id", tf_child_frame_id_});

// Configure and activate controller
ASSERT_EQ(
pose_broadcaster_->on_configure(rclcpp_lifecycle::State{}),
controller_interface::CallbackReturn::SUCCESS);
ASSERT_EQ(
pose_broadcaster_->on_activate(rclcpp_lifecycle::State{}),
controller_interface::CallbackReturn::SUCCESS);
ASSERT_TRUE(configure_succeeds(pose_broadcaster_));
ASSERT_TRUE(activate_succeeds(pose_broadcaster_));

ASSERT_TRUE(pose_position_x_->set_value(std::numeric_limits<double>::quiet_NaN()));

Expand Down
6 changes: 6 additions & 0 deletions pose_broadcaster/test/test_pose_broadcaster.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,18 @@
#include <memory>
#include <string>

#include "controller_interface/test_utils.hpp"
#include "rclcpp/executors.hpp"

#include "pose_broadcaster/pose_broadcaster.hpp"

using pose_broadcaster::PoseBroadcaster;

using controller_interface::activate_succeeds;
using controller_interface::cleanup_succeeds;
using controller_interface::configure_succeeds;
using controller_interface::deactivate_succeeds;

class PoseBroadcasterTest : public ::testing::Test
{
public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ TEST_F(TricycleSteeringControllerTest, all_parameters_set_configure_success)
{
SetUpController();

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));

ASSERT_THAT(
controller_->params_.traction_joints_names, testing::ElementsAreArray(traction_joints_names_));
Expand All @@ -46,7 +46,7 @@ TEST_F(TricycleSteeringControllerTest, check_exported_interfaces)
{
SetUpController();

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));

auto cmd_if_conf = controller_->command_interface_configuration();
ASSERT_EQ(cmd_if_conf.names.size(), joint_command_values_.size());
Expand Down Expand Up @@ -92,8 +92,8 @@ TEST_F(TricycleSteeringControllerTest, activate_success)
{
SetUpController();

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
ASSERT_TRUE(activate_succeeds(controller_));

// check that the message is reset
auto msg = controller_->input_ref_.get();
Expand All @@ -109,8 +109,8 @@ TEST_F(TricycleSteeringControllerTest, update_success)
{
SetUpController();

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
ASSERT_TRUE(activate_succeeds(controller_));

ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
Expand All @@ -121,20 +121,20 @@ TEST_F(TricycleSteeringControllerTest, deactivate_success)
{
SetUpController();

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
ASSERT_TRUE(activate_succeeds(controller_));
ASSERT_TRUE(deactivate_succeeds(controller_));
}

TEST_F(TricycleSteeringControllerTest, reactivate_success)
{
SetUpController();

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
ASSERT_TRUE(activate_succeeds(controller_));
ASSERT_TRUE(deactivate_succeeds(controller_));
ASSERT_TRUE(std::isnan(controller_->command_interfaces_[0].get_optional().value()));
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(activate_succeeds(controller_));
ASSERT_TRUE(std::isnan(controller_->command_interfaces_[0].get_optional().value()));

ASSERT_EQ(
Expand All @@ -148,9 +148,9 @@ TEST_F(TricycleSteeringControllerTest, test_update_logic)
rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(controller_->get_node()->get_node_base_interface());

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
controller_->set_chained_mode(false);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(activate_succeeds(controller_));
ASSERT_FALSE(controller_->is_in_chained_mode());

// set command statically
Expand Down Expand Up @@ -188,9 +188,9 @@ TEST_F(TricycleSteeringControllerTest, test_update_logic_chained)
rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(controller_->get_node()->get_node_base_interface());

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
controller_->set_chained_mode(true);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(activate_succeeds(controller_));
ASSERT_TRUE(controller_->is_in_chained_mode());

controller_->reference_interfaces_[0] = 0.1;
Expand Down Expand Up @@ -225,8 +225,8 @@ TEST_F(TricycleSteeringControllerTest, receive_message_and_publish_updated_statu
rclcpp::executors::MultiThreadedExecutor executor;
executor.add_node(controller_->get_node()->get_node_base_interface());

ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_TRUE(configure_succeeds(controller_));
ASSERT_TRUE(activate_succeeds(controller_));

ASSERT_EQ(
controller_->update(rclcpp::Time(0, 0, RCL_ROS_TIME), rclcpp::Duration::from_seconds(0.01)),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include <utility>
#include <vector>

#include "controller_interface/test_utils.hpp"
#include "hardware_interface/loaned_command_interface.hpp"
#include "hardware_interface/loaned_state_interface.hpp"
#include "rclcpp/executor.hpp"
Expand All @@ -46,6 +47,11 @@ using tricycle_steering_controller::CMD_STEER_WHEEL;
using tricycle_steering_controller::CMD_TRACTION_LEFT_WHEEL;
using tricycle_steering_controller::CMD_TRACTION_RIGHT_WHEEL;

using controller_interface::activate_succeeds;
using controller_interface::cleanup_succeeds;
using controller_interface::configure_succeeds;
using controller_interface::deactivate_succeeds;

namespace
{
constexpr auto NODE_SUCCESS = controller_interface::CallbackReturn::SUCCESS;
Expand Down
Loading
Loading