From 37b9d2a3999ea3867864ef8d042b7c55edb4cc4f Mon Sep 17 00:00:00 2001
From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com>
Date: Fri, 12 Jan 2024 11:32:56 +0000
Subject: [PATCH 1/2] [JTC] Remove deprecation from parameters validation file.
(#476) (#926)
---
joint_trajectory_controller/CMakeLists.txt | 2 ++
joint_trajectory_controller/package.xml | 4 +++-
2 files changed, 5 insertions(+), 1 deletion(-)
diff --git a/joint_trajectory_controller/CMakeLists.txt b/joint_trajectory_controller/CMakeLists.txt
index 60116f2b0a..76969bd582 100644
--- a/joint_trajectory_controller/CMakeLists.txt
+++ b/joint_trajectory_controller/CMakeLists.txt
@@ -16,6 +16,8 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
rclcpp
rclcpp_lifecycle
realtime_tools
+ rsl
+ tl_expected
trajectory_msgs
)
diff --git a/joint_trajectory_controller/package.xml b/joint_trajectory_controller/package.xml
index 809b8ca084..4800e69759 100644
--- a/joint_trajectory_controller/package.xml
+++ b/joint_trajectory_controller/package.xml
@@ -23,11 +23,13 @@
controller_interface
control_msgs
control_toolbox
+ generate_parameter_library
hardware_interface
rclcpp
rclcpp_lifecycle
+ rsl
+ tl_expected
trajectory_msgs
- generate_parameter_library
ament_cmake_gmock
controller_manager
From 42766febb806e041f7c1dec0f346c99dcc1f1b14 Mon Sep 17 00:00:00 2001
From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com>
Date: Fri, 12 Jan 2024 11:35:20 +0000
Subject: [PATCH 2/2] Increase test coverage of interface configuration getters
(#856) (#865)
---
.../test_force_torque_sensor_broadcaster.cpp | 25 +++++++-
.../test_force_torque_sensor_broadcaster.hpp | 2 +-
.../test/test_forward_command_controller.cpp | 42 +++++++++++++
...i_interface_forward_command_controller.cpp | 23 +++++++
.../test/test_gripper_controllers.cpp | 12 ++++
.../test/test_imu_sensor_broadcaster.cpp | 23 +++++++
.../test/test_joint_state_broadcaster.cpp | 62 ++++++++++++++++++-
.../test/test_joint_state_broadcaster.hpp | 4 +-
.../test/test_range_sensor_broadcaster.cpp | 27 +++++++-
.../test/test_tricycle_controller.cpp | 15 +++++
10 files changed, 228 insertions(+), 7 deletions(-)
diff --git a/force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.cpp b/force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.cpp
index b88266712b..b98bc8c560 100644
--- a/force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.cpp
+++ b/force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.cpp
@@ -32,6 +32,8 @@
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
using hardware_interface::LoanedStateInterface;
+using testing::IsEmpty;
+using testing::SizeIs;
namespace
{
@@ -156,6 +158,12 @@ TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Configure_Success)
// configure passed
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
+
+ // check interface configuration
+ auto cmd_if_conf = fts_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ auto state_if_conf = fts_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, SizeIs(6lu));
}
TEST_F(ForceTorqueSensorBroadcasterTest, InterfaceNames_Configure_Success)
@@ -173,7 +181,7 @@ TEST_F(ForceTorqueSensorBroadcasterTest, InterfaceNames_Configure_Success)
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
}
-TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Activate_Success)
+TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_ActivateDeactivate_Success)
{
SetUpFTSBroadcaster();
@@ -184,6 +192,21 @@ TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Activate_Success)
// configure and activate success
ASSERT_EQ(fts_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(fts_broadcaster_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
+
+ // check interface configuration
+ auto cmd_if_conf = fts_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ auto state_if_conf = fts_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, SizeIs(6lu));
+
+ // deactivate passed
+ ASSERT_EQ(fts_broadcaster_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS);
+
+ // check interface configuration
+ cmd_if_conf = fts_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ state_if_conf = fts_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, SizeIs(6lu)); // did not change
}
TEST_F(ForceTorqueSensorBroadcasterTest, SensorName_Update_Success)
diff --git a/force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.hpp b/force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.hpp
index 5477b3fa6f..fe5b0ab3ba 100644
--- a/force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.hpp
+++ b/force_torque_sensor_broadcaster/test/test_force_torque_sensor_broadcaster.hpp
@@ -36,7 +36,7 @@ class FriendForceTorqueSensorBroadcaster
FRIEND_TEST(ForceTorqueSensorBroadcasterTest, SensorNameParameterIsEmpty);
FRIEND_TEST(ForceTorqueSensorBroadcasterTest, InterfaceNameParameterIsEmpty);
- FRIEND_TEST(ForceTorqueSensorBroadcasterTest, ActivateSuccess);
+ FRIEND_TEST(ForceTorqueSensorBroadcasterTest, SensorName_ActivateDeactivate_Success);
FRIEND_TEST(ForceTorqueSensorBroadcasterTest, UpdateTest);
FRIEND_TEST(ForceTorqueSensorBroadcasterTest, SensorStatePublishTest);
};
diff --git a/forward_command_controller/test/test_forward_command_controller.cpp b/forward_command_controller/test/test_forward_command_controller.cpp
index 697e42d671..b464f1f8ba 100644
--- a/forward_command_controller/test/test_forward_command_controller.cpp
+++ b/forward_command_controller/test/test_forward_command_controller.cpp
@@ -34,6 +34,8 @@
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
using hardware_interface::LoanedCommandInterface;
+using testing::IsEmpty;
+using testing::SizeIs;
namespace
{
@@ -128,6 +130,13 @@ TEST_F(ForwardCommandControllerTest, ConfigureParamsSuccess)
ASSERT_EQ(
controller_->on_configure(rclcpp_lifecycle::State()),
controller_interface::CallbackReturn::SUCCESS);
+
+ // check interface configuration
+ auto cmd_if_conf = controller_->command_interface_configuration();
+ EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
+ ASSERT_THAT(cmd_if_conf.names, SizeIs(2lu));
+ auto state_if_conf = controller_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, IsEmpty());
}
TEST_F(ForwardCommandControllerTest, ActivateWithWrongJointsNamesFails)
@@ -173,9 +182,23 @@ TEST_F(ForwardCommandControllerTest, ActivateSuccess)
ASSERT_EQ(
controller_->on_configure(rclcpp_lifecycle::State()),
controller_interface::CallbackReturn::SUCCESS);
+
+ // check interface configuration
+ auto cmd_if_conf = controller_->command_interface_configuration();
+ EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
+ ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size()));
+ auto state_if_conf = controller_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, IsEmpty());
+
ASSERT_EQ(
controller_->on_activate(rclcpp_lifecycle::State()),
controller_interface::CallbackReturn::SUCCESS);
+
+ // check interface configuration
+ cmd_if_conf = controller_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size()));
+ state_if_conf = controller_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, IsEmpty());
}
TEST_F(ForwardCommandControllerTest, CommandSuccessTest)
@@ -323,9 +346,22 @@ TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
auto node_state = controller_->configure();
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
+ // check interface configuration
+ auto cmd_if_conf = controller_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size()));
+ EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
+ auto state_if_conf = controller_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, IsEmpty());
+
node_state = controller_->get_node()->activate();
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);
+ // check interface configuration
+ cmd_if_conf = controller_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size()));
+ state_if_conf = controller_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, IsEmpty());
+
auto command_msg = std::make_shared();
command_msg->data = {10.0, 20.0, 30.0};
@@ -344,6 +380,12 @@ TEST_F(ForwardCommandControllerTest, ActivateDeactivateCommandsResetSuccess)
node_state = controller_->get_node()->deactivate();
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
+ // check interface configuration
+ cmd_if_conf = controller_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, SizeIs(joint_names_.size())); // did not change
+ state_if_conf = controller_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, IsEmpty());
+
// command ptr should be reset (nullptr) after deactivation - same check as in `update`
ASSERT_FALSE(
controller_->rt_command_ptr_.readFromNonRT() &&
diff --git a/forward_command_controller/test/test_multi_interface_forward_command_controller.cpp b/forward_command_controller/test/test_multi_interface_forward_command_controller.cpp
index 0cada04859..b850c01a4d 100644
--- a/forward_command_controller/test/test_multi_interface_forward_command_controller.cpp
+++ b/forward_command_controller/test/test_multi_interface_forward_command_controller.cpp
@@ -36,6 +36,8 @@
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
using hardware_interface::LoanedCommandInterface;
+using testing::IsEmpty;
+using testing::SizeIs;
namespace
{
@@ -148,6 +150,13 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, ConfigureParamsSuccess)
ASSERT_EQ(
controller_->on_configure(rclcpp_lifecycle::State()),
controller_interface::CallbackReturn::SUCCESS);
+
+ // check interface configuration
+ auto cmd_if_conf = controller_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, SizeIs(3lu));
+ EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
+ auto state_if_conf = controller_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, IsEmpty());
}
TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateWithWrongJointsNamesFails)
@@ -282,6 +291,13 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateDeactivateCommandsRes
{
SetUpController(true);
+ // check interface configuration
+ auto cmd_if_conf = controller_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, SizeIs(3lu));
+ EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
+ auto state_if_conf = controller_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, IsEmpty());
+
// send command
auto command_ptr = std::make_shared();
command_ptr->data = {10.0, 20.0, 30.0};
@@ -300,6 +316,13 @@ TEST_F(MultiInterfaceForwardCommandControllerTest, ActivateDeactivateCommandsRes
auto node_state = controller_->get_node()->deactivate();
ASSERT_EQ(node_state.id(), lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
+ // check interface configuration
+ cmd_if_conf = controller_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, SizeIs(3lu));
+ EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
+ state_if_conf = controller_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, IsEmpty());
+
// command ptr should be reset (nullptr) after deactivation - same check as in `update`
ASSERT_FALSE(
controller_->rt_command_ptr_.readFromNonRT() &&
diff --git a/gripper_controllers/test/test_gripper_controllers.cpp b/gripper_controllers/test/test_gripper_controllers.cpp
index 506f968b99..6963dfec93 100644
--- a/gripper_controllers/test/test_gripper_controllers.cpp
+++ b/gripper_controllers/test/test_gripper_controllers.cpp
@@ -31,6 +31,8 @@ using hardware_interface::LoanedCommandInterface;
using hardware_interface::LoanedStateInterface;
using GripperCommandAction = control_msgs::action::GripperCommand;
using GoalHandle = rclcpp_action::ServerGoalHandle;
+using testing::SizeIs;
+using testing::UnorderedElementsAre;
template
void GripperControllerTest::SetUpTestCase()
@@ -108,6 +110,16 @@ TYPED_TEST(GripperControllerTest, ConfigureParamsSuccess)
ASSERT_EQ(
this->controller_->on_configure(rclcpp_lifecycle::State()),
controller_interface::CallbackReturn::SUCCESS);
+
+ // check interface configuration
+ auto cmd_if_conf = this->controller_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, SizeIs(1lu));
+ ASSERT_THAT(cmd_if_conf.names, UnorderedElementsAre(std::string("joint_1/") + TypeParam::value));
+ EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
+ auto state_if_conf = this->controller_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, SizeIs(2lu));
+ ASSERT_THAT(state_if_conf.names, UnorderedElementsAre("joint_1/position", "joint_1/velocity"));
+ EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
}
TYPED_TEST(GripperControllerTest, ActivateWithWrongJointsNamesFails)
diff --git a/imu_sensor_broadcaster/test/test_imu_sensor_broadcaster.cpp b/imu_sensor_broadcaster/test/test_imu_sensor_broadcaster.cpp
index 8358088b1d..f336ece2ad 100644
--- a/imu_sensor_broadcaster/test/test_imu_sensor_broadcaster.cpp
+++ b/imu_sensor_broadcaster/test/test_imu_sensor_broadcaster.cpp
@@ -32,6 +32,8 @@
#include "sensor_msgs/msg/imu.hpp"
using hardware_interface::LoanedStateInterface;
+using testing::IsEmpty;
+using testing::SizeIs;
namespace
{
@@ -114,6 +116,12 @@ TEST_F(IMUSensorBroadcasterTest, SensorName_Configure_Success)
// configure passed
ASSERT_EQ(imu_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
+
+ // check interface configuration
+ auto cmd_if_conf = imu_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ auto state_if_conf = imu_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, SizeIs(10lu));
}
TEST_F(IMUSensorBroadcasterTest, SensorName_Activate_Success)
@@ -127,6 +135,21 @@ TEST_F(IMUSensorBroadcasterTest, SensorName_Activate_Success)
// configure and activate success
ASSERT_EQ(imu_broadcaster_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS);
ASSERT_EQ(imu_broadcaster_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
+
+ // check interface configuration
+ auto cmd_if_conf = imu_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ auto state_if_conf = imu_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, SizeIs(10lu));
+
+ // deactivate passed
+ ASSERT_EQ(imu_broadcaster_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS);
+
+ // check interface configuration
+ cmd_if_conf = imu_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ state_if_conf = imu_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, SizeIs(10lu)); // did not change
}
TEST_F(IMUSensorBroadcasterTest, SensorName_Update_Success)
diff --git a/joint_state_broadcaster/test/test_joint_state_broadcaster.cpp b/joint_state_broadcaster/test/test_joint_state_broadcaster.cpp
index 98dac68924..cfe985b638 100644
--- a/joint_state_broadcaster/test/test_joint_state_broadcaster.cpp
+++ b/joint_state_broadcaster/test/test_joint_state_broadcaster.cpp
@@ -163,7 +163,7 @@ TEST_F(JointStateBroadcasterTest, ConfigureErrorTest)
ASSERT_FALSE(state_broadcaster_->realtime_dynamic_joint_state_publisher_);
}
-TEST_F(JointStateBroadcasterTest, ActivateTest)
+TEST_F(JointStateBroadcasterTest, ActivateEmptyTest)
{
// publishers not initialized yet
ASSERT_FALSE(state_broadcaster_->joint_state_publisher_);
@@ -177,6 +177,12 @@ TEST_F(JointStateBroadcasterTest, ActivateTest)
const size_t NUM_JOINTS = joint_names_.size();
+ // check interface configuration
+ auto cmd_if_conf = state_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ auto state_if_conf = state_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, IsEmpty());
+
// publishers initialized
ASSERT_TRUE(state_broadcaster_->realtime_joint_state_publisher_);
ASSERT_TRUE(state_broadcaster_->realtime_dynamic_joint_state_publisher_);
@@ -218,6 +224,12 @@ TEST_F(JointStateBroadcasterTest, ActivateTestWithoutJointsParameter)
const size_t NUM_JOINTS = joint_names_.size();
+ // check interface configuration
+ auto cmd_if_conf = state_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ auto state_if_conf = state_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, IsEmpty());
+
// publishers initialized
ASSERT_TRUE(state_broadcaster_->realtime_joint_state_publisher_);
ASSERT_TRUE(state_broadcaster_->realtime_dynamic_joint_state_publisher_);
@@ -259,6 +271,12 @@ TEST_F(JointStateBroadcasterTest, ActivateTestWithoutInterfacesParameter)
const size_t NUM_JOINTS = joint_names_.size();
+ // check interface configuration
+ auto cmd_if_conf = state_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ auto state_if_conf = state_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, IsEmpty());
+
// publishers initialized
ASSERT_TRUE(state_broadcaster_->realtime_joint_state_publisher_);
ASSERT_TRUE(state_broadcaster_->realtime_dynamic_joint_state_publisher_);
@@ -287,7 +305,7 @@ TEST_F(JointStateBroadcasterTest, ActivateTestWithoutInterfacesParameter)
ElementsAreArray(interface_names_));
}
-TEST_F(JointStateBroadcasterTest, ActivateTestTwoJointsOneInterface)
+TEST_F(JointStateBroadcasterTest, ActivateDeactivateTestTwoJointsOneInterface)
{
const std::vector JOINT_NAMES = {joint_names_[0], joint_names_[1]};
const std::vector IF_NAMES = {interface_names_[0]};
@@ -300,6 +318,12 @@ TEST_F(JointStateBroadcasterTest, ActivateTestTwoJointsOneInterface)
const size_t NUM_JOINTS = JOINT_NAMES.size();
+ // check interface configuration
+ auto cmd_if_conf = state_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ auto state_if_conf = state_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, SizeIs(JOINT_NAMES.size() * IF_NAMES.size()));
+
// publishers initialized
ASSERT_TRUE(state_broadcaster_->realtime_joint_state_publisher_);
ASSERT_TRUE(state_broadcaster_->realtime_dynamic_joint_state_publisher_);
@@ -329,6 +353,16 @@ TEST_F(JointStateBroadcasterTest, ActivateTestTwoJointsOneInterface)
dynamic_joint_state_msg.interface_values[0].interface_names, ElementsAreArray(IF_NAMES));
ASSERT_THAT(
dynamic_joint_state_msg.interface_values[1].interface_names, ElementsAreArray(IF_NAMES));
+
+ // deactivate
+ ASSERT_EQ(state_broadcaster_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS);
+
+ // check interface configuration
+ cmd_if_conf = state_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ state_if_conf = state_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(
+ state_if_conf.names, SizeIs(JOINT_NAMES.size() * IF_NAMES.size())); // does not change
}
TEST_F(JointStateBroadcasterTest, ActivateTestOneJointTwoInterfaces)
@@ -344,6 +378,12 @@ TEST_F(JointStateBroadcasterTest, ActivateTestOneJointTwoInterfaces)
const size_t NUM_JOINTS = JOINT_NAMES.size();
+ // check interface configuration
+ auto cmd_if_conf = state_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ auto state_if_conf = state_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, SizeIs(JOINT_NAMES.size() * IF_NAMES.size()));
+
// publishers initialized
ASSERT_TRUE(state_broadcaster_->realtime_joint_state_publisher_);
ASSERT_TRUE(state_broadcaster_->realtime_dynamic_joint_state_publisher_);
@@ -412,6 +452,12 @@ TEST_F(JointStateBroadcasterTest, ActivateTestTwoJointTwoInterfacesOneMissing)
const size_t NUM_JOINTS = JOINT_NAMES.size();
+ // check interface configuration
+ auto cmd_if_conf = state_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ auto state_if_conf = state_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, SizeIs(JOINT_NAMES.size() * IF_NAMES.size()));
+
// publishers initialized
ASSERT_TRUE(state_broadcaster_->realtime_joint_state_publisher_);
ASSERT_TRUE(state_broadcaster_->realtime_dynamic_joint_state_publisher_);
@@ -455,6 +501,12 @@ TEST_F(JointStateBroadcasterTest, TestCustomInterfaceWithoutMapping)
const size_t NUM_JOINTS = JOINT_NAMES.size();
+ // check interface configuration
+ auto cmd_if_conf = state_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ auto state_if_conf = state_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, SizeIs(JOINT_NAMES.size() * IF_NAMES.size()));
+
// joint state initialized
const auto & joint_state_msg = state_broadcaster_->realtime_joint_state_publisher_->msg_;
ASSERT_THAT(joint_state_msg.name, SizeIs(0));
@@ -492,6 +544,12 @@ TEST_F(JointStateBroadcasterTest, TestCustomInterfaceMapping)
const size_t NUM_JOINTS = JOINT_NAMES.size();
+ // check interface configuration
+ auto cmd_if_conf = state_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ auto state_if_conf = state_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, SizeIs(JOINT_NAMES.size() * IF_NAMES.size()));
+
// joint state initialized
const auto & joint_state_msg = state_broadcaster_->realtime_joint_state_publisher_->msg_;
ASSERT_THAT(joint_state_msg.name, ElementsAreArray(JOINT_NAMES));
diff --git a/joint_state_broadcaster/test/test_joint_state_broadcaster.hpp b/joint_state_broadcaster/test/test_joint_state_broadcaster.hpp
index fcaa40e8d5..fa9d29c936 100644
--- a/joint_state_broadcaster/test/test_joint_state_broadcaster.hpp
+++ b/joint_state_broadcaster/test/test_joint_state_broadcaster.hpp
@@ -33,10 +33,10 @@ using hardware_interface::HW_IF_VELOCITY;
class FriendJointStateBroadcaster : public joint_state_broadcaster::JointStateBroadcaster
{
FRIEND_TEST(JointStateBroadcasterTest, ConfigureErrorTest);
- FRIEND_TEST(JointStateBroadcasterTest, ActivateTest);
+ FRIEND_TEST(JointStateBroadcasterTest, ActivateEmptyTest);
FRIEND_TEST(JointStateBroadcasterTest, ActivateTestWithoutJointsParameter);
FRIEND_TEST(JointStateBroadcasterTest, ActivateTestWithoutInterfacesParameter);
- FRIEND_TEST(JointStateBroadcasterTest, ActivateTestTwoJointsOneInterface);
+ FRIEND_TEST(JointStateBroadcasterTest, ActivateDeactivateTestTwoJointsOneInterface);
FRIEND_TEST(JointStateBroadcasterTest, ActivateTestOneJointTwoInterfaces);
FRIEND_TEST(JointStateBroadcasterTest, ActivateTestTwoJointTwoInterfacesAllMissing);
FRIEND_TEST(JointStateBroadcasterTest, ActivateTestTwoJointTwoInterfacesOneMissing);
diff --git a/range_sensor_broadcaster/test/test_range_sensor_broadcaster.cpp b/range_sensor_broadcaster/test/test_range_sensor_broadcaster.cpp
index 02d7de814e..7b06c321fe 100644
--- a/range_sensor_broadcaster/test/test_range_sensor_broadcaster.cpp
+++ b/range_sensor_broadcaster/test/test_range_sensor_broadcaster.cpp
@@ -22,6 +22,9 @@
#include "hardware_interface/loaned_state_interface.hpp"
+using testing::IsEmpty;
+using testing::SizeIs;
+
void RangeSensorBroadcasterTest::SetUp()
{
// initialize controller
@@ -130,9 +133,15 @@ TEST_F(RangeSensorBroadcasterTest, Configure_RangeBroadcaster_Success)
ASSERT_EQ(
range_broadcaster_->on_configure(rclcpp_lifecycle::State()),
controller_interface::CallbackReturn::SUCCESS);
+
+ // check interface configuration
+ auto cmd_if_conf = range_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ auto state_if_conf = range_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, SizeIs(1lu));
}
-TEST_F(RangeSensorBroadcasterTest, Activate_RangeBroadcaster_Success)
+TEST_F(RangeSensorBroadcasterTest, ActivateDeactivate_RangeBroadcaster_Success)
{
init_broadcaster("test_range_sensor_broadcaster");
@@ -141,6 +150,22 @@ TEST_F(RangeSensorBroadcasterTest, Activate_RangeBroadcaster_Success)
ASSERT_EQ(
range_broadcaster_->on_activate(rclcpp_lifecycle::State()),
controller_interface::CallbackReturn::SUCCESS);
+
+ // check interface configuration
+ auto cmd_if_conf = range_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ auto state_if_conf = range_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, SizeIs(1lu));
+
+ ASSERT_EQ(
+ range_broadcaster_->on_deactivate(rclcpp_lifecycle::State()),
+ controller_interface::CallbackReturn::SUCCESS);
+
+ // check interface configuration
+ cmd_if_conf = range_broadcaster_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, IsEmpty());
+ state_if_conf = range_broadcaster_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, SizeIs(1lu)); // did not change
}
TEST_F(RangeSensorBroadcasterTest, Update_RangeBroadcaster_Success)
diff --git a/tricycle_controller/test/test_tricycle_controller.cpp b/tricycle_controller/test/test_tricycle_controller.cpp
index 1d6edf261a..2355425f10 100644
--- a/tricycle_controller/test/test_tricycle_controller.cpp
+++ b/tricycle_controller/test/test_tricycle_controller.cpp
@@ -39,6 +39,7 @@ using hardware_interface::LoanedCommandInterface;
using hardware_interface::LoanedStateInterface;
using lifecycle_msgs::msg::State;
using testing::SizeIs;
+using testing::UnorderedElementsAre;
class TestableTricycleController : public tricycle_controller::TricycleController
{
@@ -207,6 +208,20 @@ TEST_F(TestTricycleController, configure_succeeds_when_joints_are_specified)
rclcpp::Parameter("steering_joint_name", rclcpp::ParameterValue(steering_joint_name)));
ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), CallbackReturn::SUCCESS);
+
+ // check interface configuration
+ auto cmd_if_conf = controller_->command_interface_configuration();
+ ASSERT_THAT(cmd_if_conf.names, SizeIs(2lu));
+ ASSERT_THAT(
+ cmd_if_conf.names,
+ UnorderedElementsAre(traction_joint_name + "/velocity", steering_joint_name + "/position"));
+ EXPECT_EQ(cmd_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
+ auto state_if_conf = controller_->state_interface_configuration();
+ ASSERT_THAT(state_if_conf.names, SizeIs(2lu));
+ ASSERT_THAT(
+ state_if_conf.names,
+ UnorderedElementsAre(traction_joint_name + "/velocity", steering_joint_name + "/position"));
+ EXPECT_EQ(state_if_conf.type, controller_interface::interface_configuration_type::INDIVIDUAL);
}
TEST_F(TestTricycleController, activate_fails_without_resources_assigned)