Skip to content

Commit

Permalink
rosidl_cmake is deprecated, rclcpp::get_typesupport_handle as well
Browse files Browse the repository at this point in the history
Signed-off-by: Mikael Arguedas <[email protected]>
  • Loading branch information
mikaelarguedas committed May 2, 2024
1 parent 77bdc4c commit 75e91bd
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 3 deletions.
2 changes: 1 addition & 1 deletion include/ros1_bridge/factory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class Factory : public FactoryInterface
{
ts_lib_ = rclcpp::get_typesupport_library(ros2_type_name, "rosidl_typesupport_cpp");
if (static_cast<bool>(ts_lib_)) {
type_support_ = rclcpp::get_typesupport_handle(
type_support_ = rclcpp::get_message_typesupport_handle(
ros2_type_name, "rosidl_typesupport_cpp",
*ts_lib_);
}
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@
<buildtool_depend>ament_index_python</buildtool_depend>
<buildtool_depend>python3</buildtool_depend>
<buildtool_depend>python3-catkin-pkg-modules</buildtool_depend>
<buildtool_depend>rosidl_cmake</buildtool_depend>
<buildtool_depend>rosidl_parser</buildtool_depend>
<buildtool_depend>rosidl_pycommon</buildtool_depend>

<build_depend>builtin_interfaces</build_depend>
<build_depend>libboost-dev</build_depend>
Expand Down
2 changes: 1 addition & 1 deletion ros1_bridge/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -24,8 +24,8 @@
import genmsg.msg_loader

import rosidl_adapter.parser
from rosidl_cmake import expand_template
import rosidl_parser.parser
from rosidl_pycommon import expand_template

import yaml

Expand Down

0 comments on commit 75e91bd

Please sign in to comment.