Skip to content

Commit

Permalink
apply suggestions from review
Browse files Browse the repository at this point in the history
  • Loading branch information
mamueluth committed Feb 21, 2023
1 parent 62caac9 commit cc5082e
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,6 @@
#include "controller_manager_msgs/srv/switch_controller.hpp"
#include "controller_manager_msgs/srv/unload_controller.hpp"

#include "std_msgs/msg/string.hpp"

#include "diagnostic_updater/diagnostic_updater.hpp"
#include "hardware_interface/handle.hpp"
#include "hardware_interface/resource_manager.hpp"
Expand All @@ -54,6 +52,7 @@
#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

namespace controller_manager
{
Expand Down Expand Up @@ -305,7 +304,7 @@ class ControllerManager : public rclcpp::Node
std::shared_ptr<controller_manager_msgs::srv::SetHardwareComponentState::Response> response);

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

// Per controller update rate support
unsigned int update_loop_counter_ = 0;
Expand Down
14 changes: 8 additions & 6 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,10 +156,11 @@ ControllerManager::ControllerManager(
{
// 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_state_publisher for robot description file.");
RCLCPP_INFO(
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::init_resource_manager_cb, this, std::placeholders::_1));
namespace_ + "/robot_description", rclcpp::QoS(1).transient_local(),
std::bind(&ControllerManager::robot_description_callback, this, std::placeholders::_1));
}
else
{
Expand Down Expand Up @@ -201,10 +202,11 @@ ControllerManager::ControllerManager(
init_services();
}

void ControllerManager::init_resource_manager_cb(const std_msgs::msg::String & robot_description)
void ControllerManager::robot_description_callback(const std_msgs::msg::String & robot_description)
{
RCLCPP_ERROR(
get_logger(), "'init_resource_manager_cb called with %s", robot_description.data.c_str());
RCLCPP_INFO(get_logger(), "Received robot description file.");
RCLCPP_DEBUG(
get_logger(), "'Content of robot description file: %s", robot_description.data.c_str());
// TODO(Manuel) errors should probably be caught since we don't want controller_manager node
// to die if a non valid urdf is passed. However, should maybe be fine tuned.
try
Expand Down

0 comments on commit cc5082e

Please sign in to comment.