Skip to content

Commit

Permalink
Apply suggestions from code review
Browse files Browse the repository at this point in the history
  • Loading branch information
destogl authored Apr 4, 2023
1 parent c0de993 commit 09329fb
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 10 deletions.
9 changes: 4 additions & 5 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,7 +157,7 @@ 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_description topic for robot description file.");
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));
Expand All @@ -174,7 +174,6 @@ ControllerManager::ControllerManager(
diagnostics_updater_.setHardwareID("ros2_control");
diagnostics_updater_.add(
"Controllers Activity", this, &ControllerManager::controller_activity_diagnostic_callback);

init_services();
}

Expand Down Expand Up @@ -207,7 +206,7 @@ void ControllerManager::robot_description_callback(const std_msgs::msg::String &
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
// 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 All @@ -225,8 +224,8 @@ void ControllerManager::robot_description_callback(const std_msgs::msg::String &
{
RCLCPP_ERROR_STREAM(
get_logger(),
"The published robot description file (urdf) seems not to be genuine. Following error was "
"caught:"
"The published robot description file (urdf) seems not to be genuine. The following error "
"was caught:"
<< e.what());
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -87,10 +87,10 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager
/**
* @brief if the resource manager load_urdf(...) function has been called this returns true.
* We want to permit to load the urdf later on but we currently don't want to permit multiple
* calls to load_urdf (reloading/loading different urdf)
* calls to load_urdf (reloading/loading different urdf).
*
* @return true if resource manager's load_urdf() has been called
* @return false if resource manager's load_urdf() has not been called
* @return true if resource manager's load_urdf() has been already called.
* @return false if resource manager's load_urdf() has not been yet called.
*/
bool load_urdf_called() const;

Expand Down
4 changes: 2 additions & 2 deletions hardware_interface/src/resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -574,8 +574,8 @@ ResourceManager::ResourceManager() : resource_storage_(std::make_unique<Resource
ResourceManager::~ResourceManager() = default;

ResourceManager::ResourceManager(
const std::string & urdf, bool validate_interfaces, bool activate_all, bool load_urdf_called)
: resource_storage_(std::make_unique<ResourceStorage>()), load_urdf_called_(load_urdf_called)
const std::string & urdf, bool validate_interfaces, bool activate_all)
: resource_storage_(std::make_unique<ResourceStorage>())
{
load_urdf(urdf, validate_interfaces);

Expand Down

0 comments on commit 09329fb

Please sign in to comment.