Skip to content

Commit

Permalink
implement custom converter for rcl_interfaces/Log
Browse files Browse the repository at this point in the history
  • Loading branch information
hoffmann-stefan committed Oct 30, 2024
1 parent 7efc9cb commit 3f86127
Show file tree
Hide file tree
Showing 6 changed files with 164 additions and 1 deletion.
3 changes: 2 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,8 @@ set(actionlib_msgs_DEPRECATED_QUIET TRUE)
foreach(package_name ${ros2_interface_packages})
find_package(${package_name} QUIET REQUIRED)
message(STATUS "Found ${package_name}: ${${package_name}_VERSION} (${${package_name}_DIR})")
if(NOT "${package_name}" STREQUAL "builtin_interfaces")
if(NOT "${package_name}" STREQUAL "builtin_interfaces" AND
NOT "${package_name}" STREQUAL "rcl_interfaces")
list(APPEND generated_files "${generated_path}/${package_name}_factories.cpp")
list(APPEND generated_files "${generated_path}/${package_name}_factories.hpp")
foreach(interface_file ${${package_name}_IDL_FILES})
Expand Down
20 changes: 20 additions & 0 deletions include/ros1_bridge/builtin_interfaces_factories.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,14 @@
#define ROS1_BRIDGE__BUILTIN_INTERFACES_FACTORIES_HPP_

// include ROS 1 messages
#include <rosgraph_msgs/Log.h>
#include <std_msgs/Duration.h>
#include <std_msgs/Time.h>

// include ROS 2 messages
#include <builtin_interfaces/msg/duration.hpp>
#include <builtin_interfaces/msg/time.hpp>
#include <rcl_interfaces/msg/log.hpp>

#include <memory>
#include <string>
Expand Down Expand Up @@ -74,6 +76,24 @@ Factory<
const builtin_interfaces::msg::Time & ros2_msg,
std_msgs::Time & ros1_msg);

template<>
void
Factory<
rosgraph_msgs::Log,
rcl_interfaces::msg::Log
>::convert_1_to_2(
const rosgraph_msgs::Log & ros1_msg,
rcl_interfaces::msg::Log & ros2_msg);

template<>
void
Factory<
rosgraph_msgs::Log,
rcl_interfaces::msg::Log
>::convert_2_to_1(
const rcl_interfaces::msg::Log & ros2_msg,
rosgraph_msgs::Log & ros1_msg);

} // namespace ros1_bridge

#endif // ROS1_BRIDGE__BUILTIN_INTERFACES_FACTORIES_HPP_
14 changes: 14 additions & 0 deletions include/ros1_bridge/convert_builtin_interfaces.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,14 @@
#include "ros1_bridge/convert_decl.hpp"

// include ROS 1 builtin messages
#include <rosgraph_msgs/Log.h>
#include "ros/duration.h"
#include "ros/time.h"

// include ROS 2 builtin messages
#include "builtin_interfaces/msg/duration.hpp"
#include "builtin_interfaces/msg/time.hpp"
#include <rcl_interfaces/msg/log.hpp>

namespace ros1_bridge
{
Expand Down Expand Up @@ -52,6 +54,18 @@ convert_2_to_1(
const builtin_interfaces::msg::Time & ros2_msg,
ros::Time & ros1_type);

template<>
void
convert_1_to_2(
const rosgraph_msgs::Log & ros1_msg,
rcl_interfaces::msg::Log & ros2_msg);

template<>
void
convert_2_to_1(
const rcl_interfaces::msg::Log & ros2_msg,
rosgraph_msgs::Log & ros1_msg);

} // namespace ros1_bridge

#endif // ROS1_BRIDGE__CONVERT_BUILTIN_INTERFACES_HPP_
3 changes: 3 additions & 0 deletions ros1_bridge/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,9 @@ def generate_cpp(output_path, template_dir):
data['ros2_package_names_msg'] + data['ros2_package_names_srv'])
# skip builtin_interfaces since there is a custom implementation
unique_package_names -= {'builtin_interfaces'}
# skip rcl_interfaces since there is a custom implementation
# Only for Log which is the only type that is useful to map.
unique_package_names -= {'rcl_interfaces'}
data['ros2_package_names'] = list(unique_package_names)

template_file = os.path.join(template_dir, 'get_factory.cpp.em')
Expand Down
36 changes: 36 additions & 0 deletions src/builtin_interfaces_factories.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,18 @@ get_factory_builtin_interfaces(
>
>("std_msgs/Time", ros2_type_name);
}
if (
(ros1_type_name == "rosgraph_msgs/Log" || ros1_type_name == "") &&
ros2_type_name == "rcl_interfaces/msg/Log")
{
return std::make_shared<
Factory<
rosgraph_msgs::Log,
rcl_interfaces::msg::Log
>
>("rosgraph_msgs/Log", ros2_type_name);
}

return std::shared_ptr<FactoryInterface>();
}

Expand Down Expand Up @@ -104,4 +116,28 @@ Factory<
ros1_bridge::convert_2_to_1(ros2_msg, ros1_msg.data);
}

template<>
void
Factory<
rosgraph_msgs::Log,
rcl_interfaces::msg::Log
>::convert_1_to_2(
const rosgraph_msgs::Log & ros1_msg,
rcl_interfaces::msg::Log & ros2_msg)
{
ros1_bridge::convert_1_to_2(ros1_msg, ros2_msg);
}

template<>
void
Factory<
rosgraph_msgs::Log,
rcl_interfaces::msg::Log
>::convert_2_to_1(
const rcl_interfaces::msg::Log & ros2_msg,
rosgraph_msgs::Log & ros1_msg)
{
ros1_bridge::convert_2_to_1(ros2_msg, ros1_msg);
}

} // namespace ros1_bridge
89 changes: 89 additions & 0 deletions src/convert_builtin_interfaces.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,4 +58,93 @@ convert_2_to_1(
ros1_type.nsec = ros2_msg.nanosec;
}


template<>
void
convert_1_to_2(
const rosgraph_msgs::Log & ros1_msg,
rcl_interfaces::msg::Log & ros2_msg)
{
ros1_bridge::convert_1_to_2(ros1_msg.header.stamp, ros2_msg.stamp);

// Explicitly map the values of the log level as they differ between
// ROS1 and ROS2.
switch (ros1_msg.level)
{
case rosgraph_msgs::Log::DEBUG:
ros2_msg.level = rcl_interfaces::msg::Log::DEBUG;
break;

case rosgraph_msgs::Log::INFO:
ros2_msg.level = rcl_interfaces::msg::Log::INFO;
break;

case rosgraph_msgs::Log::WARN:
ros2_msg.level = rcl_interfaces::msg::Log::WARN;
break;

case rosgraph_msgs::Log::ERROR:
ros2_msg.level = rcl_interfaces::msg::Log::ERROR;
break;

case rosgraph_msgs::Log::FATAL:
ros2_msg.level = rcl_interfaces::msg::Log::FATAL;
break;

default:
ros2_msg.level = ros1_msg.level;
break;
}

ros2_msg.name = ros1_msg.name;
ros2_msg.msg = ros1_msg.msg;
ros2_msg.file = ros1_msg.file;
ros2_msg.function = ros1_msg.function;
ros2_msg.line = ros1_msg.line;
}

template<>
void
convert_2_to_1(
const rcl_interfaces::msg::Log & ros2_msg,
rosgraph_msgs::Log & ros1_msg)
{
ros1_bridge::convert_2_to_1(ros2_msg.stamp, ros1_msg.header.stamp);

// Explicitly map the values of the log level as they differ between
// ROS1 and ROS2.
switch (ros2_msg.level)
{
case rcl_interfaces::msg::Log::DEBUG:
ros1_msg.level = rosgraph_msgs::Log::DEBUG;
break;

case rcl_interfaces::msg::Log::INFO:
ros1_msg.level = rosgraph_msgs::Log::INFO;
break;

case rcl_interfaces::msg::Log::WARN:
ros1_msg.level = rosgraph_msgs::Log::WARN;
break;

case rcl_interfaces::msg::Log::ERROR:
ros1_msg.level = rosgraph_msgs::Log::ERROR;
break;

case rcl_interfaces::msg::Log::FATAL:
ros1_msg.level = rosgraph_msgs::Log::FATAL;
break;

default:
ros1_msg.level = ros1_msg.level;
break;
}

ros1_msg.name = ros2_msg.name;
ros1_msg.msg = ros2_msg.msg;
ros1_msg.file = ros2_msg.file;
ros1_msg.function = ros2_msg.function;
ros1_msg.line = ros2_msg.line;
}

} // namespace ros1_bridge

0 comments on commit 3f86127

Please sign in to comment.