Skip to content

Commit d299208

Browse files
mamueluthdestogl
andauthored
[CM] Use robot_description topic instead of parameter and don't crash on empty URDF 🦿 (#940)
* on startup wait for robot description, however allow receiving later --------- Co-authored-by: Dr. Denis <[email protected]>
1 parent 50ad772 commit d299208

File tree

10 files changed

+253
-15
lines changed

10 files changed

+253
-15
lines changed

controller_manager/CMakeLists.txt

Lines changed: 11 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
1414
pluginlib
1515
rclcpp
1616
realtime_tools
17+
std_msgs
1718
)
1819

1920
find_package(ament_cmake REQUIRED)
@@ -143,6 +144,16 @@ if(BUILD_TESTING)
143144
ament_target_dependencies(test_controller_manager_srvs
144145
controller_manager_msgs
145146
)
147+
ament_add_gmock(test_controller_manager_urdf_passing
148+
test/test_controller_manager_urdf_passing.cpp
149+
)
150+
target_link_libraries(test_controller_manager_urdf_passing
151+
controller_manager
152+
ros2_control_test_assets::ros2_control_test_assets
153+
)
154+
ament_target_dependencies(test_controller_manager_urdf_passing
155+
controller_manager_msgs
156+
)
146157

147158
add_library(test_controller_with_interfaces SHARED
148159
test/test_controller_with_interfaces/test_controller_with_interfaces.cpp

controller_manager/include/controller_manager/controller_manager.hpp

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

5557
namespace controller_manager
5658
{
@@ -82,6 +84,9 @@ class ControllerManager : public rclcpp::Node
8284
CONTROLLER_MANAGER_PUBLIC
8385
virtual ~ControllerManager() = default;
8486

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

@@ -316,6 +321,7 @@ class ControllerManager : public rclcpp::Node
316321
std::vector<std::string> get_controller_names();
317322
std::pair<std::string, std::string> split_command_interface(
318323
const std::string & command_interface);
324+
void subscribe_to_robot_description_topic();
319325

320326
/**
321327
* Clear request lists used when switching controllers. The lists are shared between "callback"
@@ -504,6 +510,8 @@ class ControllerManager : public rclcpp::Node
504510
std::vector<std::string> activate_command_interface_request_,
505511
deactivate_command_interface_request_;
506512

513+
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr robot_description_subscription_;
514+
507515
struct SwitchParams
508516
{
509517
bool do_switch = {false};

controller_manager/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626
<depend>ros2_control_test_assets</depend>
2727
<depend>ros2param</depend>
2828
<depend>ros2run</depend>
29+
<depend>std_msgs</depend>
2930

3031
<test_depend>ament_cmake_gmock</test_depend>
3132
<test_depend>ros2_control_test_assets</test_depend>

controller_manager/src/controller_manager.cpp

Lines changed: 54 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -151,13 +151,20 @@ ControllerManager::ControllerManager(
151151
}
152152

153153
std::string robot_description = "";
154+
// TODO(destogl): remove support at the end of 2023
154155
get_parameter("robot_description", robot_description);
155156
if (robot_description.empty())
156157
{
157-
throw std::runtime_error("Unable to initialize resource manager, no robot description found.");
158+
subscribe_to_robot_description_topic();
159+
}
160+
else
161+
{
162+
RCLCPP_WARN(
163+
get_logger(),
164+
"[Deprecated] Passing the robot description parameter directly to the control_manager node "
165+
"is deprecated. Use '~/robot_description' topic from 'robot_state_publisher' instead.");
166+
init_resource_manager(robot_description);
158167
}
159-
160-
init_resource_manager(robot_description);
161168

162169
diagnostics_updater_.setHardwareID("ros2_control");
163170
diagnostics_updater_.add(
@@ -183,12 +190,55 @@ ControllerManager::ControllerManager(
183190
{
184191
RCLCPP_WARN(get_logger(), "'update_rate' parameter not set, using default value.");
185192
}
193+
194+
subscribe_to_robot_description_topic();
195+
186196
diagnostics_updater_.setHardwareID("ros2_control");
187197
diagnostics_updater_.add(
188198
"Controllers Activity", this, &ControllerManager::controller_activity_diagnostic_callback);
189199
init_services();
190200
}
191201

202+
void ControllerManager::subscribe_to_robot_description_topic()
203+
{
204+
// set QoS to transient local to get messages that have already been published
205+
// (if robot state publisher starts before controller manager)
206+
RCLCPP_INFO(
207+
get_logger(), "Subscribing to '~/robot_description' topic for robot description file.");
208+
robot_description_subscription_ = create_subscription<std_msgs::msg::String>(
209+
"~/robot_description", rclcpp::QoS(1).transient_local(),
210+
std::bind(&ControllerManager::robot_description_callback, this, std::placeholders::_1));
211+
}
212+
213+
void ControllerManager::robot_description_callback(const std_msgs::msg::String & robot_description)
214+
{
215+
RCLCPP_INFO(get_logger(), "Received robot description file.");
216+
RCLCPP_DEBUG(
217+
get_logger(), "'Content of robot description file: %s", robot_description.data.c_str());
218+
// TODO(Manuel): errors should probably be caught since we don't want controller_manager node
219+
// to die if a non valid urdf is passed. However, should maybe be fine tuned.
220+
try
221+
{
222+
if (resource_manager_->is_urdf_already_loaded())
223+
{
224+
RCLCPP_WARN(
225+
get_logger(),
226+
"ResourceManager has already loaded an urdf file. Ignoring attempt to reload a robot "
227+
"description file.");
228+
return;
229+
}
230+
init_resource_manager(robot_description.data.c_str());
231+
}
232+
catch (std::runtime_error & e)
233+
{
234+
RCLCPP_ERROR_STREAM(
235+
get_logger(),
236+
"The published robot description file (urdf) seems not to be genuine. The following error "
237+
"was caught:"
238+
<< e.what());
239+
}
240+
}
241+
192242
void ControllerManager::init_resource_manager(const std::string & robot_description)
193243
{
194244
// TODO(destogl): manage this when there is an error - CM should not die because URDF is wrong...
@@ -199,7 +249,7 @@ void ControllerManager::init_resource_manager(const std::string & robot_descript
199249
std::vector<std::string> configure_components_on_start = std::vector<std::string>({});
200250
if (get_parameter("configure_components_on_start", configure_components_on_start))
201251
{
202-
RCLCPP_WARN_STREAM(
252+
RCLCPP_WARN(
203253
get_logger(),
204254
"[Deprecated]: Usage of parameter \"configure_components_on_start\" is deprecated. Use "
205255
"hardware_spawner instead.");

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
{
@@ -120,6 +155,8 @@ class ControllerManagerFixture : public ::testing::Test
120155

121156
std::thread updater_;
122157
bool run_updater_;
158+
const std::string robot_description_;
159+
const bool pass_urdf_as_parameter_;
123160
};
124161

125162
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: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@ Parameters
2828
,,,,,,,,,,
2929

3030
disable_commands (optional; boolean; default: false)
31-
Disables mirroring commands to states.
31+
Disables mirroring commands to states.
3232
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.
3333
Or it can help you to test your setup when the hardware is running without feedback, i.e., in open loop configuration.
3434

hardware_interface/include/hardware_interface/resource_manager.hpp

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

93+
/**
94+
* @brief if the resource manager load_urdf(...) function has been called this returns true.
95+
* We want to permit to load the urdf later on but we currently don't want to permit multiple
96+
* calls to load_urdf (reloading/loading different urdf).
97+
*
98+
* @return true if resource manager's load_urdf() has been already called.
99+
* @return false if resource manager's load_urdf() has not been yet called.
100+
*/
101+
bool is_urdf_already_loaded() const;
102+
93103
/// Claim a state interface given its key.
94104
/**
95105
* The resource is claimed as long as being in scope.
@@ -413,6 +423,8 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager
413423

414424
// Structure to store read and write status so it is not initialized in the real-time loop
415425
HardwareReadWriteStatus read_write_status;
426+
427+
bool is_urdf_loaded__ = false;
416428
};
417429

418430
} // namespace hardware_interface

hardware_interface/src/resource_manager.cpp

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -703,6 +703,7 @@ ResourceManager::ResourceManager(
703703
// CM API: Called in "callback/slow"-thread
704704
void ResourceManager::load_urdf(const std::string & urdf, bool validate_interfaces)
705705
{
706+
is_urdf_loaded__ = true;
706707
const std::string system_type = "system";
707708
const std::string sensor_type = "sensor";
708709
const std::string actuator_type = "actuator";
@@ -741,6 +742,8 @@ void ResourceManager::load_urdf(const std::string & urdf, bool validate_interfac
741742
resource_storage_->systems_.size());
742743
}
743744

745+
bool ResourceManager::is_urdf_already_loaded() const { return is_urdf_loaded__; }
746+
744747
// CM API: Called in "update"-thread
745748
LoanedStateInterface ResourceManager::claim_state_interface(const std::string & key)
746749
{

0 commit comments

Comments
 (0)