Skip to content

Commit b9cdcfe

Browse files
authored
[CM] Use robot_description topic instead of parameter and don't crash on empty URDF 🦿 (backport #940) (#1052)
1 parent 9dd62fe commit b9cdcfe

File tree

11 files changed

+308
-30
lines changed

11 files changed

+308
-30
lines changed

controller_manager/CMakeLists.txt

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
1313
pluginlib
1414
rclcpp
1515
realtime_tools
16+
std_msgs
1617
)
1718

1819
find_package(ament_cmake REQUIRED)
@@ -133,6 +134,17 @@ if(BUILD_TESTING)
133134
controller_manager_msgs
134135
ros2_control_test_assets
135136
)
137+
ament_add_gmock(test_controller_manager_urdf_passing
138+
test/test_controller_manager_urdf_passing.cpp
139+
)
140+
target_include_directories(test_controller_manager_urdf_passing PRIVATE include)
141+
target_link_libraries(test_controller_manager_urdf_passing
142+
controller_manager
143+
)
144+
ament_target_dependencies(test_controller_manager_urdf_passing
145+
controller_manager_msgs
146+
ros2_control_test_assets
147+
)
136148

137149
add_library(test_controller_with_interfaces SHARED test/test_controller_with_interfaces/test_controller_with_interfaces.cpp)
138150
target_include_directories(test_controller_with_interfaces PRIVATE include)

controller_manager/include/controller_manager/controller_manager.hpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,8 @@
5050
#include "rclcpp/node_interfaces/node_logging_interface.hpp"
5151
#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
5252
#include "rclcpp/parameter.hpp"
53+
#include "rclcpp/rclcpp.hpp"
54+
#include "std_msgs/msg/string.hpp"
5355

5456
namespace controller_manager
5557
{
@@ -81,6 +83,9 @@ class ControllerManager : public rclcpp::Node
8183
CONTROLLER_MANAGER_PUBLIC
8284
virtual ~ControllerManager() = default;
8385

86+
CONTROLLER_MANAGER_PUBLIC
87+
void robot_description_callback(const std_msgs::msg::String & msg);
88+
8489
CONTROLLER_MANAGER_PUBLIC
8590
void init_resource_manager(const std::string & robot_description);
8691

@@ -282,6 +287,7 @@ class ControllerManager : public rclcpp::Node
282287
std::vector<std::string> get_controller_names();
283288
std::pair<std::string, std::string> split_command_interface(
284289
const std::string & command_interface);
290+
void subscribe_to_robot_description_topic();
285291

286292
/**
287293
* Clear request lists used when switching controllers. The lists are shared between "callback"
@@ -490,6 +496,8 @@ class ControllerManager : public rclcpp::Node
490496
std::vector<std::string> activate_command_interface_request_,
491497
deactivate_command_interface_request_;
492498

499+
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr robot_description_subscription_;
500+
493501
struct SwitchParams
494502
{
495503
bool do_switch = {false};

controller_manager/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
<depend>ros2_control_test_assets</depend>
2626
<depend>ros2param</depend>
2727
<depend>ros2run</depend>
28+
<depend>std_msgs</depend>
2829

2930
<test_depend>ament_cmake_gmock</test_depend>
3031

controller_manager/src/controller_manager.cpp

Lines changed: 54 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -270,10 +270,16 @@ ControllerManager::ControllerManager(
270270
get_parameter("robot_description", robot_description);
271271
if (robot_description.empty())
272272
{
273-
throw std::runtime_error("Unable to initialize resource manager, no robot description found.");
273+
subscribe_to_robot_description_topic();
274+
}
275+
else
276+
{
277+
RCLCPP_WARN(
278+
get_logger(),
279+
"[Deprecated] Passing the robot description parameter directly to the control_manager node "
280+
"is deprecated. Use '~/robot_description' topic from 'robot_state_publisher' instead.");
281+
init_resource_manager(robot_description);
274282
}
275-
276-
init_resource_manager(robot_description);
277283

278284
init_services();
279285
}
@@ -295,9 +301,54 @@ ControllerManager::ControllerManager(
295301
{
296302
RCLCPP_WARN(get_logger(), "'update_rate' parameter not set, using default value.");
297303
}
304+
305+
if (!resource_manager_->is_urdf_already_loaded())
306+
{
307+
subscribe_to_robot_description_topic();
308+
}
298309
init_services();
299310
}
300311

312+
void ControllerManager::subscribe_to_robot_description_topic()
313+
{
314+
// set QoS to transient local to get messages that have already been published
315+
// (if robot state publisher starts before controller manager)
316+
RCLCPP_INFO(
317+
get_logger(), "Subscribing to '~/robot_description' topic for robot description file.");
318+
robot_description_subscription_ = create_subscription<std_msgs::msg::String>(
319+
"~/robot_description", rclcpp::QoS(1).transient_local(),
320+
std::bind(&ControllerManager::robot_description_callback, this, std::placeholders::_1));
321+
}
322+
323+
void ControllerManager::robot_description_callback(const std_msgs::msg::String & robot_description)
324+
{
325+
RCLCPP_INFO(get_logger(), "Received robot description file.");
326+
RCLCPP_DEBUG(
327+
get_logger(), "'Content of robot description file: %s", robot_description.data.c_str());
328+
// TODO(Manuel): errors should probably be caught since we don't want controller_manager node
329+
// to die if a non valid urdf is passed. However, should maybe be fine tuned.
330+
try
331+
{
332+
if (resource_manager_->is_urdf_already_loaded())
333+
{
334+
RCLCPP_WARN(
335+
get_logger(),
336+
"ResourceManager has already loaded an urdf file. Ignoring attempt to reload a robot "
337+
"description file.");
338+
return;
339+
}
340+
init_resource_manager(robot_description.data.c_str());
341+
}
342+
catch (std::runtime_error & e)
343+
{
344+
RCLCPP_ERROR_STREAM(
345+
get_logger(),
346+
"The published robot description file (urdf) seems not to be genuine. The following error "
347+
"was caught:"
348+
<< e.what());
349+
}
350+
}
351+
301352
void ControllerManager::init_resource_manager(const std::string & robot_description)
302353
{
303354
// TODO(destogl): manage this when there is an error - CM should not die because URDF is wrong...

controller_manager/test/controller_manager_test_common.hpp

Lines changed: 47 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -22,15 +22,20 @@
2222
#include <memory>
2323
#include <string>
2424
#include <thread>
25+
#include <utility>
2526
#include <vector>
2627

2728
#include "controller_interface/controller_interface.hpp"
2829

2930
#include "controller_manager/controller_manager.hpp"
31+
#include "controller_manager_msgs/srv/list_hardware_interfaces.hpp"
3032
#include "controller_manager_msgs/srv/switch_controller.hpp"
3133

34+
#include "rclcpp/rclcpp.hpp"
3235
#include "rclcpp/utilities.hpp"
3336

37+
#include "std_msgs/msg/string.hpp"
38+
3439
#include "ros2_control_test_assets/descriptions.hpp"
3540
#include "test_controller_failed_init/test_controller_failed_init.hpp"
3641

@@ -60,21 +65,51 @@ template <typename CtrlMgr>
6065
class ControllerManagerFixture : public ::testing::Test
6166
{
6267
public:
68+
explicit ControllerManagerFixture(
69+
const std::string & robot_description = ros2_control_test_assets::minimal_robot_urdf,
70+
const bool & pass_urdf_as_parameter = false)
71+
: robot_description_(robot_description), pass_urdf_as_parameter_(pass_urdf_as_parameter)
72+
{
73+
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
74+
// We want to be able to create a ResourceManager where no urdf file has been passed to
75+
if (robot_description_.empty())
76+
{
77+
cm_ = std::make_shared<CtrlMgr>(
78+
std::make_unique<hardware_interface::ResourceManager>(), executor_, TEST_CM_NAME);
79+
}
80+
else
81+
{
82+
// can be removed later, needed if we want to have the deprecated way of passing the robot
83+
// description file to the controller manager covered by tests
84+
if (pass_urdf_as_parameter_)
85+
{
86+
cm_ = std::make_shared<CtrlMgr>(
87+
std::make_unique<hardware_interface::ResourceManager>(robot_description_, true, true),
88+
executor_, TEST_CM_NAME);
89+
}
90+
else
91+
{
92+
// TODO(Manuel) : passing via topic not working in test setup, tested cm does
93+
// not receive msg. Have to check this...
94+
95+
// this is just a workaround to skip passing
96+
cm_ = std::make_shared<CtrlMgr>(
97+
std::make_unique<hardware_interface::ResourceManager>(), executor_, TEST_CM_NAME);
98+
// mimic topic call
99+
auto msg = std_msgs::msg::String();
100+
msg.data = robot_description_;
101+
cm_->robot_description_callback(msg);
102+
}
103+
}
104+
}
105+
63106
static void SetUpTestCase() { rclcpp::init(0, nullptr); }
64107

65108
static void TearDownTestCase() { rclcpp::shutdown(); }
66109

67-
void SetUp()
68-
{
69-
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
70-
cm_ = std::make_shared<CtrlMgr>(
71-
std::make_unique<hardware_interface::ResourceManager>(
72-
ros2_control_test_assets::minimal_robot_urdf, true, true),
73-
executor_, TEST_CM_NAME);
74-
run_updater_ = false;
75-
}
110+
void SetUp() override { run_updater_ = false; }
76111

77-
void TearDown() { stopCmUpdater(); }
112+
void TearDown() override { stopCmUpdater(); }
78113

79114
void startCmUpdater()
80115
{
@@ -121,6 +156,8 @@ class ControllerManagerFixture : public ::testing::Test
121156

122157
std::thread updater_;
123158
bool run_updater_;
159+
const std::string robot_description_;
160+
const bool pass_urdf_as_parameter_;
124161
};
125162

126163
class TestControllerManagerSrvs
Lines changed: 88 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,88 @@
1+
// Copyright 2020 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include <gtest/gtest.h>
16+
#include <memory>
17+
#include <string>
18+
#include <utility>
19+
#include <vector>
20+
21+
#include "controller_manager/controller_manager.hpp"
22+
#include "controller_manager_test_common.hpp"
23+
24+
#include "ros2_control_test_assets/descriptions.hpp"
25+
26+
class TestControllerManagerWithTestableCM;
27+
28+
class TestableControllerManager : public controller_manager::ControllerManager
29+
{
30+
friend TestControllerManagerWithTestableCM;
31+
32+
FRIEND_TEST(TestControllerManagerWithTestableCM, initial_no_load_urdf_called);
33+
FRIEND_TEST(TestControllerManagerWithTestableCM, load_urdf_called_after_callback);
34+
FRIEND_TEST(TestControllerManagerWithTestableCM, load_urdf_called_after_invalid_urdf_passed);
35+
FRIEND_TEST(TestControllerManagerWithTestableCM, load_urdf_called_after_callback);
36+
FRIEND_TEST(TestControllerManagerWithTestableCM, load_urdf_called_after_callback);
37+
38+
public:
39+
TestableControllerManager(
40+
std::unique_ptr<hardware_interface::ResourceManager> resource_manager,
41+
std::shared_ptr<rclcpp::Executor> executor,
42+
const std::string & manager_node_name = "controller_manager",
43+
const std::string & namespace_ = "")
44+
: controller_manager::ControllerManager(
45+
std::move(resource_manager), executor, manager_node_name, namespace_)
46+
{
47+
}
48+
};
49+
50+
class TestControllerManagerWithTestableCM
51+
: public ControllerManagerFixture<TestableControllerManager>,
52+
public testing::WithParamInterface<Strictness>
53+
{
54+
public:
55+
// create cm with no urdf
56+
TestControllerManagerWithTestableCM()
57+
: ControllerManagerFixture<TestableControllerManager>("", false)
58+
{
59+
}
60+
};
61+
62+
TEST_P(TestControllerManagerWithTestableCM, initial_no_load_urdf_called)
63+
{
64+
ASSERT_FALSE(cm_->resource_manager_->is_urdf_already_loaded());
65+
}
66+
67+
TEST_P(TestControllerManagerWithTestableCM, load_urdf_called_after_callback)
68+
{
69+
ASSERT_FALSE(cm_->resource_manager_->is_urdf_already_loaded());
70+
// mimic callback
71+
auto msg = std_msgs::msg::String();
72+
msg.data = ros2_control_test_assets::minimal_robot_urdf;
73+
cm_->robot_description_callback(msg);
74+
ASSERT_TRUE(cm_->resource_manager_->is_urdf_already_loaded());
75+
}
76+
77+
TEST_P(TestControllerManagerWithTestableCM, load_urdf_called_after_invalid_urdf_passed)
78+
{
79+
ASSERT_FALSE(cm_->resource_manager_->is_urdf_already_loaded());
80+
// mimic callback
81+
auto msg = std_msgs::msg::String();
82+
msg.data = ros2_control_test_assets::minimal_robot_missing_command_keys_urdf;
83+
cm_->robot_description_callback(msg);
84+
ASSERT_TRUE(cm_->resource_manager_->is_urdf_already_loaded());
85+
}
86+
87+
INSTANTIATE_TEST_SUITE_P(
88+
test_best_effort, TestControllerManagerWithTestableCM, testing::Values(best_effort));

hardware_interface/doc/mock_components_userdoc.rst

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,12 @@ Features:
2727
Parameters
2828
,,,,,,,,,,
2929

30-
fake_sensor_commands (optional; boolean; default: false)
30+
disable_commands (optional; boolean; default: false)
31+
Disables mirroring commands to states.
32+
This option is helpful to simulate an erroneous connection to the hardware when nothing breaks, but suddenly there is no feedback from a hardware interface.
33+
Or it can help you to test your setup when the hardware is running without feedback, i.e., in open loop configuration.
34+
35+
mock_sensor_commands (optional; boolean; default: false)
3136
Creates fake command interfaces for faking sensor measurements with an external command.
3237
Those interfaces are usually used by a :ref:`forward controller <forward_command_controller_userdoc>` to provide access from ROS-world.
3338

hardware_interface/include/hardware_interface/resource_manager.hpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -77,6 +77,16 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager
7777
*/
7878
void load_urdf(const std::string & urdf, bool validate_interfaces = true);
7979

80+
/**
81+
* @brief if the resource manager load_urdf(...) function has been called this returns true.
82+
* We want to permit to load the urdf later on but we currently don't want to permit multiple
83+
* calls to load_urdf (reloading/loading different urdf).
84+
*
85+
* @return true if resource manager's load_urdf() has been already called.
86+
* @return false if resource manager's load_urdf() has not been yet called.
87+
*/
88+
bool is_urdf_already_loaded() const;
89+
8090
/// Claim a state interface given its key.
8191
/**
8292
* The resource is claimed as long as being in scope.
@@ -374,6 +384,8 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager
374384
mutable std::recursive_mutex resource_interfaces_lock_;
375385
mutable std::recursive_mutex claimed_command_interfaces_lock_;
376386
std::unique_ptr<ResourceStorage> resource_storage_;
387+
388+
bool is_urdf_loaded__ = false;
377389
};
378390

379391
} // namespace hardware_interface

hardware_interface/src/resource_manager.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -667,6 +667,7 @@ ResourceManager::ResourceManager(
667667

668668
void ResourceManager::load_urdf(const std::string & urdf, bool validate_interfaces)
669669
{
670+
is_urdf_loaded__ = true;
670671
const std::string system_type = "system";
671672
const std::string sensor_type = "sensor";
672673
const std::string actuator_type = "actuator";
@@ -700,6 +701,9 @@ void ResourceManager::load_urdf(const std::string & urdf, bool validate_interfac
700701
}
701702
}
702703

704+
bool ResourceManager::is_urdf_already_loaded() const { return is_urdf_loaded__; }
705+
706+
// CM API: Called in "update"-thread
703707
LoanedStateInterface ResourceManager::claim_state_interface(const std::string & key)
704708
{
705709
if (!state_interface_is_available(key))

0 commit comments

Comments
 (0)