Skip to content

Commit

Permalink
Replace RCUTILS_ with RCLCPP_ for logging (ros-controls#62)
Browse files Browse the repository at this point in the history
  • Loading branch information
JafarAbdi authored Mar 9, 2020
1 parent e3e22a3 commit 55105d2
Show file tree
Hide file tree
Showing 12 changed files with 56 additions and 41 deletions.
7 changes: 5 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -122,6 +122,9 @@ int main()
{
// do all the init stuff

// Logger
const rclcpp::Logger logger = rclcpp::get_logger("my_robot_logger");

// create my_robot instance
auto my_robot = std::make_shared<MyRobot>();

Expand Down Expand Up @@ -156,12 +159,12 @@ int main()
// we can either configure each controller individually through its services
// or we use the controller manager to configure every loaded controller
if (cm.configure() != controller_interface::CONTROLLER_INTERFACE_RET_SUCCESS) {
RCUTILS_LOG_ERROR("at least one controller failed to configure")
RCLCPP_ERROR(logger, "at least one controller failed to configure")
return -1;
}
// and activate all controller
if (cm.activate() != controller_interface::CONTROLLER_INTERFACE_RET_SUCCESS) {
RCUTILS_LOG_ERROR("at least one controller failed to activate")
RCLCPP_ERROR(logger, "at least one controller failed to activate")
return -1;
}

Expand Down
2 changes: 0 additions & 2 deletions controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@ find_package(controller_interface REQUIRED)
find_package(hardware_interface REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rcpputils REQUIRED)

add_library(controller_manager SHARED src/controller_manager.cpp src/controller_loader_pluginlib.cpp)
target_include_directories(controller_manager PRIVATE include)
Expand All @@ -27,7 +26,6 @@ ament_target_dependencies(controller_manager
"hardware_interface"
"pluginlib"
"rclcpp"
"rcpputils"
)
# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
Expand Down
6 changes: 3 additions & 3 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@

#include "lifecycle_msgs/msg/state.hpp"

#include "rcutils/logging_macros.h"
#include "rclcpp/rclcpp.hpp"

namespace controller_manager
{
Expand All @@ -46,7 +46,7 @@ ControllerManager::load_controller(
const std::string & controller_name,
const std::string & controller_type)
{
RCUTILS_LOG_INFO("Loading controller '%s'\n", controller_name.c_str());
RCLCPP_INFO(get_logger(), "Loading controller '%s'\n", controller_name.c_str());

auto it = std::find_if(
loaders_.cbegin(), loaders_.cend(),
Expand All @@ -58,7 +58,7 @@ ControllerManager::load_controller(
controller = (*it)->create(controller_type);
} else {
const std::string error_msg("Loader for controller '" + controller_name + "' not found\n");
RCUTILS_LOG_ERROR("%s", error_msg.c_str());
RCLCPP_ERROR(get_logger(), "%s", error_msg.c_str());
throw std::runtime_error(error_msg);
}

Expand Down
4 changes: 4 additions & 0 deletions controller_parameter_server/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,10 @@ if(BUILD_TESTING)
test_parameter_server test/test_parameter_server.cpp
ENV config_file=${test_config_file})
target_link_libraries(test_parameter_server parameter_server)
ament_target_dependencies(
test_parameter_server
rclcpp
)
endif()

ament_export_include_directories(
Expand Down
6 changes: 4 additions & 2 deletions controller_parameter_server/test/test_parameter_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,10 +87,12 @@ TEST_F(TestControllerParameterServer, load_config_file) {
std::this_thread::sleep_for(1s);
while (!parameters_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
RCUTILS_LOG_ERROR("Interrupted while waiting for the service. Exiting.");
RCLCPP_ERROR(
client_node->get_logger(),
"Interrupted while waiting for the service. Exiting.");
FAIL();
}
RCUTILS_LOG_INFO("service not available, waiting again...");
RCLCPP_INFO(client_node->get_logger(), "service not available, waiting again...");
}

std::vector<std::string> expected_keys =
Expand Down
4 changes: 2 additions & 2 deletions hardware_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()

find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rcpputils REQUIRED)
find_package(rcutils REQUIRED)

add_library(
hardware_interface
Expand All @@ -28,8 +28,8 @@ target_include_directories(
include)
ament_target_dependencies(
hardware_interface
"rclcpp"
"rcpputils"
"rcutils"
)

# Causes the visibility macros to use dllexport rather than dllimport,
Expand Down
2 changes: 1 addition & 1 deletion hardware_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,8 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<depend>rclcpp</depend>
<depend>rcpputils</depend>
<depend>rcutils</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
32 changes: 19 additions & 13 deletions hardware_interface/src/robot_hardware.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
#include <vector>

#include "hardware_interface/macros.hpp"
#include "rcutils/logging_macros.h"
#include "rclcpp/rclcpp.hpp"

namespace hardware_interface
{
Expand Down Expand Up @@ -80,8 +80,9 @@ RobotHardware::get_joint_state_handle(
const std::string & name, const JointStateHandle ** joint_state_handle)
{
if (name.empty()) {
RCUTILS_LOG_ERROR_NAMED(
"joint state handle", "cannot get handle! No name given");
RCLCPP_ERROR(
rclcpp::get_logger("joint state handle"),
"cannot get handle! No name given");
return HW_RET_ERROR;
}

Expand All @@ -94,8 +95,9 @@ RobotHardware::get_joint_state_handle(
});

if (handle_pos == registered_joint_state_handles_.end()) {
RCUTILS_LOG_ERROR_NAMED(
"joint state handle", "cannot get handle. No joint %s found.\n", name.c_str());
RCLCPP_ERROR(
rclcpp::get_logger("joint state handle"),
"cannot get handle. No joint %s found.\n", name.c_str());
return HW_RET_ERROR;
}

Expand All @@ -108,8 +110,9 @@ RobotHardware::get_joint_command_handle(
const std::string & name, JointCommandHandle ** joint_command_handle)
{
if (name.empty()) {
RCUTILS_LOG_ERROR_NAMED(
"joint cmd handle", "cannot get handle! No name given");
RCLCPP_ERROR(
rclcpp::get_logger("joint cmd handle"),
"cannot get handle! No name given");
return HW_RET_ERROR;
}

Expand All @@ -122,8 +125,9 @@ RobotHardware::get_joint_command_handle(
});

if (handle_pos == registered_joint_command_handles_.end()) {
RCUTILS_LOG_ERROR_NAMED(
"joint cmd handle", "cannot get handle. No joint %s found.\n", name.c_str());
RCLCPP_ERROR(
rclcpp::get_logger("joint cmd handle"),
"cannot get handle. No joint %s found.\n", name.c_str());
return HW_RET_ERROR;
}

Expand All @@ -136,8 +140,9 @@ RobotHardware::get_operation_mode_handle(
const std::string & name, OperationModeHandle ** operation_mode_handle)
{
if (name.empty()) {
RCUTILS_LOG_ERROR_NAMED(
"joint operation mode handle", "cannot get handle! No name given");
RCLCPP_ERROR(
rclcpp::get_logger("joint operation mode handle"),
"cannot get handle! No name given");
return HW_RET_ERROR;
}

Expand All @@ -150,8 +155,9 @@ RobotHardware::get_operation_mode_handle(
});

if (handle_pos == registered_operation_mode_handles_.end()) {
RCUTILS_LOG_ERROR_NAMED(
"joint operation mode handle", "cannot get handle. No joint %s found.\n", name.c_str());
RCLCPP_ERROR(
rclcpp::get_logger("joint operation mode handle"),
"cannot get handle. No joint %s found.\n", name.c_str());
return HW_RET_ERROR;
}

Expand Down
4 changes: 2 additions & 2 deletions test_robot_hardware/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@ endif()

find_package(ament_cmake REQUIRED)
find_package(hardware_interface REQUIRED)
find_package(rcutils REQUIRED)
find_package(rclcpp REQUIRED)

add_library(test_robot_hardware SHARED src/test_robot_hardware.cpp)
target_include_directories(test_robot_hardware PRIVATE include)
ament_target_dependencies(
test_robot_hardware
hardware_interface
rcutils
rclcpp
)

# Causes the visibility macros to use dllexport rather than dllimport,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@
#include "hardware_interface/robot_hardware.hpp"
#include "hardware_interface/types/hardware_interface_return_values.hpp"

#include "rclcpp/rclcpp.hpp"

#include "test_robot_hardware/visibility_control.h"

namespace test_robot_hardware
Expand Down Expand Up @@ -84,6 +86,8 @@ class TestRobotHardware : public hardware_interface::RobotHardware

hardware_interface::OperationModeHandle write_op_handle1;
hardware_interface::OperationModeHandle write_op_handle2;

const rclcpp::Logger logger = rclcpp::get_logger("test_robot_hardware");
};

} // namespace test_robot_hardware
Expand Down
4 changes: 2 additions & 2 deletions test_robot_hardware/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,10 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>hardware_interface</build_depend>
<build_depend>rcutils</build_depend>
<build_depend>rclcpp</build_depend>

<exec_depend>hardware_interface</exec_depend>
<exec_depend>rcutils</exec_depend>
<exec_depend>rclcpp</exec_depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
22 changes: 10 additions & 12 deletions test_robot_hardware/src/test_robot_hardware.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,6 @@
#include <string>
#include <vector>

#include "rcutils/logging_macros.h"

namespace test_robot_hardware
{

Expand All @@ -31,44 +29,44 @@ TestRobotHardware::init()
joint_name1, &pos1, &vel1, &eff1);
ret = register_joint_state_handle(&js1);
if (ret != hardware_interface::HW_RET_OK) {
RCUTILS_LOG_WARN("can't register joint state handle %s", joint_name1.c_str());
RCLCPP_WARN(logger, "can't register joint state handle %s", joint_name1.c_str());
return ret;
}

js2 = hardware_interface::JointStateHandle(
joint_name2, &pos2, &vel2, &eff2);
ret = register_joint_state_handle(&js2);
if (ret != hardware_interface::HW_RET_OK) {
RCUTILS_LOG_WARN("can't register joint state handle %s", joint_name2.c_str());
RCLCPP_WARN(logger, "can't register joint state handle %s", joint_name2.c_str());
return ret;
}

js3 = hardware_interface::JointStateHandle(
joint_name3, &pos3, &vel3, &eff3);
ret = register_joint_state_handle(&js3);
if (ret != hardware_interface::HW_RET_OK) {
RCUTILS_LOG_WARN("can't register joint state handle %s", joint_name3.c_str());
RCLCPP_WARN(logger, "can't register joint state handle %s", joint_name3.c_str());
return ret;
}

jcmd1 = hardware_interface::JointCommandHandle(joint_name1, &cmd1);
ret = register_joint_command_handle(&jcmd1);
if (ret != hardware_interface::HW_RET_OK) {
RCUTILS_LOG_WARN("can't register joint command handle %s", joint_name1.c_str());
RCLCPP_WARN(logger, "can't register joint command handle %s", joint_name1.c_str());
return ret;
}

jcmd2 = hardware_interface::JointCommandHandle(joint_name2, &cmd2);
ret = register_joint_command_handle(&jcmd2);
if (ret != hardware_interface::HW_RET_OK) {
RCUTILS_LOG_WARN("can't register joint command handle %s", joint_name2.c_str());
RCLCPP_WARN(logger, "can't register joint command handle %s", joint_name2.c_str());
return ret;
}

jcmd3 = hardware_interface::JointCommandHandle(joint_name3, &cmd3);
ret = register_joint_command_handle(&jcmd3);
if (ret != hardware_interface::HW_RET_OK) {
RCUTILS_LOG_WARN("can't register joint command handle %s", joint_name3.c_str());
RCLCPP_WARN(logger, "can't register joint command handle %s", joint_name3.c_str());
return ret;
}

Expand All @@ -77,7 +75,7 @@ TestRobotHardware::init()
reinterpret_cast<hardware_interface::OperationMode *>(&read1));
ret = register_operation_mode_handle(&read_op_handle1);
if (ret != hardware_interface::HW_RET_OK) {
RCUTILS_LOG_WARN("can't register operation mode handle %s", read_op_handle_name1.c_str());
RCLCPP_WARN(logger, "can't register operation mode handle %s", read_op_handle_name1.c_str());
return ret;
}

Expand All @@ -86,7 +84,7 @@ TestRobotHardware::init()
reinterpret_cast<hardware_interface::OperationMode *>(&read2));
ret = register_operation_mode_handle(&read_op_handle2);
if (ret != hardware_interface::HW_RET_OK) {
RCUTILS_LOG_WARN("can't register operation mode handle %s", read_op_handle_name2.c_str());
RCLCPP_WARN(logger, "can't register operation mode handle %s", read_op_handle_name2.c_str());
return ret;
}

Expand All @@ -95,7 +93,7 @@ TestRobotHardware::init()
reinterpret_cast<hardware_interface::OperationMode *>(&write1));
ret = register_operation_mode_handle(&write_op_handle1);
if (ret != hardware_interface::HW_RET_OK) {
RCUTILS_LOG_WARN("can't register operation mode handle %s", write_op_handle_name1.c_str());
RCLCPP_WARN(logger, "can't register operation mode handle %s", write_op_handle_name1.c_str());
return ret;
}

Expand All @@ -104,7 +102,7 @@ TestRobotHardware::init()
reinterpret_cast<hardware_interface::OperationMode *>(&write2));
ret = register_operation_mode_handle(&write_op_handle2);
if (ret != hardware_interface::HW_RET_OK) {
RCUTILS_LOG_WARN("can't register operation mode handle %s", write_op_handle_name2.c_str());
RCLCPP_WARN(logger, "can't register operation mode handle %s", write_op_handle_name2.c_str());
return ret;
}

Expand Down

0 comments on commit 55105d2

Please sign in to comment.