Skip to content

Commit

Permalink
workaround for topic issues while testing
Browse files Browse the repository at this point in the history
  • Loading branch information
mamueluth committed Apr 25, 2023
1 parent 0810735 commit a5b86c1
Show file tree
Hide file tree
Showing 5 changed files with 60 additions and 66 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,12 @@ class ControllerManager : public rclcpp::Node
CONTROLLER_MANAGER_PUBLIC
virtual ~ControllerManager() = default;

CONTROLLER_MANAGER_PUBLIC
void subscribe_to_robot_description_topic();

CONTROLLER_MANAGER_PUBLIC
void robot_description_callback(const std_msgs::msg::String & msg);

CONTROLLER_MANAGER_PUBLIC
void init_resource_manager(const std::string & robot_description);

Expand Down Expand Up @@ -307,9 +313,6 @@ class ControllerManager : public rclcpp::Node
const std::shared_ptr<controller_manager_msgs::srv::SetHardwareComponentState::Request> request,
std::shared_ptr<controller_manager_msgs::srv::SetHardwareComponentState::Response> response);

CONTROLLER_MANAGER_PUBLIC
void robot_description_callback(const std_msgs::msg::String & msg);

// Per controller update rate support
unsigned int update_loop_counter_ = 0;
unsigned int update_rate_ = 100;
Expand Down
26 changes: 13 additions & 13 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -154,13 +154,7 @@ ControllerManager::ControllerManager(
get_parameter("robot_description", robot_description);
if (robot_description.empty())
{
// set QoS to transient local to get messages that have already been published
// (if robot state publisher starts before controller manager)
RCLCPP_INFO(
get_logger(), "Subscribing to '~/robot_description' topic for robot description file.");
robot_description_subscription_ = create_subscription<std_msgs::msg::String>(
namespace_ + "/robot_description", rclcpp::QoS(1).transient_local(),
std::bind(&ControllerManager::robot_description_callback, this, std::placeholders::_1));
subscribe_to_robot_description_topic();
}
else
{
Expand Down Expand Up @@ -196,19 +190,25 @@ ControllerManager::ControllerManager(
RCLCPP_WARN(get_logger(), "'update_rate' parameter not set, using default value.");
}

// set QoS to transient local to get messages that have already been published
// (if robot state publisher starts before controller manager)
RCLCPP_INFO(get_logger(), "Subscribing to ~/robot_description topic for robot description file.");
robot_description_subscription_ = create_subscription<std_msgs::msg::String>(
namespace_ + "/robot_description", rclcpp::QoS(1).transient_local(),
std::bind(&ControllerManager::robot_description_callback, this, std::placeholders::_1));
subscribe_to_robot_description_topic();

diagnostics_updater_.setHardwareID("ros2_control");
diagnostics_updater_.add(
"Controllers Activity", this, &ControllerManager::controller_activity_diagnostic_callback);
init_services();
}

void ControllerManager::subscribe_to_robot_description_topic()
{
// set QoS to transient local to get messages that have already been published
// (if robot state publisher starts before controller manager)
RCLCPP_INFO_STREAM(
get_logger(), "Subscribing to '~/robot_description' topic for robot description file.");
robot_description_subscription_ = create_subscription<std_msgs::msg::String>(
"~/robot_description", rclcpp::QoS(1).transient_local(),
std::bind(&ControllerManager::robot_description_callback, this, std::placeholders::_1));
}

void ControllerManager::robot_description_callback(const std_msgs::msg::String & robot_description)
{
RCLCPP_INFO(get_logger(), "Received robot description file.");
Expand Down
53 changes: 10 additions & 43 deletions controller_manager/test/controller_manager_test_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,11 +65,10 @@ template <typename CtrlMgr>
class ControllerManagerFixture : public ::testing::Test
{
public:
// TODO(Manuel): Maybe add parameter of which hardware is to be expected
explicit ControllerManagerFixture(
const std::string & robot_description = ros2_control_test_assets::minimal_robot_urdf,
const std::string ns = "/", const bool & pass_urdf_as_parameter = false)
: robot_description_(robot_description), ns_(ns), pass_urdf_as_parameter_(pass_urdf_as_parameter)
const bool & pass_urdf_as_parameter = false)
: robot_description_(robot_description), pass_urdf_as_parameter_(pass_urdf_as_parameter)
{
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
// We want to be able to create a ResourceManager where no urdf file has been passed to
Expand All @@ -90,37 +89,16 @@ class ControllerManagerFixture : public ::testing::Test
}
else
{
// First wie create a node and a publisher for publishing the passed robot description file
urdf_publisher_node_ = std::make_shared<rclcpp::Node>("robot_description_publisher", ns_);
description_pub_ = urdf_publisher_node_->create_publisher<std_msgs::msg::String>(
"robot_description", rclcpp::QoS(1).transient_local());
executor_->add_node(urdf_publisher_node_);
publish_robot_description_file(robot_description_);
// Then we create controller manager which subscribes to topic and receive
// published robot description file. Publishing is transient_local so starting cm
// later should not pose problem and is closer to real world applications
// TODO(Manuel) : passing via topic not working in test setup, tested cm does
// not receive msg. Have to check this...

// this is just a workaround to skip passing
cm_ = std::make_shared<CtrlMgr>(
std::make_unique<hardware_interface::ResourceManager>(), executor_, TEST_CM_NAME);
executor_->add_node(cm_);
// Now we have to wait for cm to process callback and initialize everything.
// We have to wait here, otherwise controllers can not be initialized since
// no hardware has been received.
service_caller_node_ = std::make_shared<rclcpp::Node>("service_caller_node", ns_);
executor_->add_node(service_caller_node_);
auto client =
service_caller_node_->create_client<controller_manager_msgs::srv::ListHardwareInterfaces>(
"get_hw_interfaces");
auto request =
std::make_shared<controller_manager_msgs::srv::ListHardwareInterfaces::Request>();
EXPECT_TRUE(client->wait_for_service(std::chrono::milliseconds(500)));
auto future = client->async_send_request(request);
EXPECT_EQ(
executor_->spin_until_future_complete(future, std::chrono::milliseconds(1000)),
rclcpp::FutureReturnCode::SUCCESS);
auto res = future.get();
auto command_interfaces = res->command_interfaces;
auto state_interfaces = res->state_interfaces;
// check for command-/stateinterfaces but spin_until_future_complete times out...
// mimic topic call
auto msg = std_msgs::msg::String();
msg.data = robot_description_;
cm_->robot_description_callback(msg);
}
}
}
Expand Down Expand Up @@ -172,24 +150,13 @@ class ControllerManagerFixture : public ::testing::Test
EXPECT_EQ(expected_return, switch_future.get());
}

void publish_robot_description_file(const std::string & robot_description_file)
{
auto msg = std::make_unique<std_msgs::msg::String>();
msg->data = robot_description_file;
description_pub_->publish(std::move(msg));
}

std::shared_ptr<rclcpp::Executor> executor_;
std::shared_ptr<CtrlMgr> cm_;

std::thread updater_;
bool run_updater_;
const std::string robot_description_;
const std::string ns_;
const bool pass_urdf_as_parameter_;
std::shared_ptr<rclcpp::Node> urdf_publisher_node_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr description_pub_;
std::shared_ptr<rclcpp::Node> service_caller_node_;
};

class TestControllerManagerSrvs
Expand Down
35 changes: 30 additions & 5 deletions controller_manager/test/test_controller_manager_urdf_passing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,14 +21,19 @@
#include "controller_manager/controller_manager.hpp"
#include "controller_manager_test_common.hpp"

#include "ros2_control_test_assets/descriptions.hpp"

class TestControllerManagerWithTestableCM;

class TestableControllerManager : public controller_manager::ControllerManager
{
friend TestControllerManagerWithTestableCM;

FRIEND_TEST(TestControllerManagerWithTestableCM, callback_gets_passed);
FRIEND_TEST(TestControllerManagerWithTestableCM, initial_failing);
FRIEND_TEST(TestControllerManagerWithTestableCM, initial_no_load_urdf_called);
FRIEND_TEST(TestControllerManagerWithTestableCM, load_urdf_called_after_callback);
FRIEND_TEST(TestControllerManagerWithTestableCM, load_urdf_called_after_invalid_urdf_passed);
FRIEND_TEST(TestControllerManagerWithTestableCM, load_urdf_called_after_callback);
FRIEND_TEST(TestControllerManagerWithTestableCM, load_urdf_called_after_callback);

public:
TestableControllerManager(
Expand All @@ -46,16 +51,36 @@ class TestControllerManagerWithTestableCM
: public ControllerManagerFixture<TestableControllerManager>,
public testing::WithParamInterface<Strictness>
{
public:
// create cm with no urdf
TestControllerManagerWithTestableCM()
: ControllerManagerFixture<TestableControllerManager>("", false)
{
}
};

// only exemplary to test if working not a useful test yet
TEST_P(TestControllerManagerWithTestableCM, callback_gets_passed)
TEST_P(TestControllerManagerWithTestableCM, initial_no_load_urdf_called)
{
ASSERT_FALSE(cm_->resource_manager_->load_urdf_called());
}

TEST_P(TestControllerManagerWithTestableCM, load_urdf_called_after_callback)
{
ASSERT_FALSE(cm_->resource_manager_->load_urdf_called());
// mimic callback
auto msg = std_msgs::msg::String();
msg.data = ros2_control_test_assets::minimal_robot_urdf;
cm_->robot_description_callback(msg);
ASSERT_TRUE(cm_->resource_manager_->load_urdf_called());
}

TEST_P(TestControllerManagerWithTestableCM, initial_failing)
TEST_P(TestControllerManagerWithTestableCM, load_urdf_called_after_invalid_urdf_passed)
{
ASSERT_FALSE(cm_->resource_manager_->load_urdf_called());
// mimic callback
auto msg = std_msgs::msg::String();
msg.data = ros2_control_test_assets::minimal_robot_missing_command_keys_urdf;
cm_->robot_description_callback(msg);
ASSERT_TRUE(cm_->resource_manager_->load_urdf_called());
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,8 +65,7 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager
* "autostart_components" and "autoconfigure_components" instead.
*/
explicit ResourceManager(
const std::string & urdf, bool validate_interfaces = true, bool activate_all = false,
bool urdf_loaded = false);
const std::string & urdf, bool validate_interfaces = true, bool activate_all = false);

ResourceManager(const ResourceManager &) = delete;

Expand Down

0 comments on commit a5b86c1

Please sign in to comment.