Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Warnings] rosidl_cmake is deprecated, rclcpp::get_typesupport_handle as well #434

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion include/ros1_bridge/factory.hpp
Original file line number Diff line number Diff line change
@@ -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_);
}
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
@@ -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>
63 changes: 45 additions & 18 deletions resource/interface_factories.cpp.em
Original file line number Diff line number Diff line change
@@ -306,26 +306,18 @@ void ServiceFactory<
@[ for field in service["fields"][type.lower()]]@
@[ if field["array"]]@
req@(to).@(field["ros" + to]["name"]).resize(req@(frm).@(field["ros" + frm]["name"]).size());
auto @(field["ros1"]["name"])1_it = req1.@(field["ros1"]["name"]).begin();
auto @(field["ros2"]["name"])2_it = req2.@(field["ros2"]["name"]).begin();
while (
@(field["ros1"]["name"])1_it != req1.@(field["ros1"]["name"]).end() &&
@(field["ros2"]["name"])2_it != req2.@(field["ros2"]["name"]).end()
) {
auto & @(field["ros1"]["name"])1 = *(@(field["ros1"]["name"])1_it++);
auto & @(field["ros2"]["name"])2 = *(@(field["ros2"]["name"])2_it++);
@[ else]@
auto & @(field["ros1"]["name"])1 = req1.@(field["ros1"]["name"]);
auto & @(field["ros2"]["name"])2 = req2.@(field["ros2"]["name"]);
@[ end if]@
@[ if field["basic"]]@
@(field["ros2"]["name"])@(to) = @(field["ros1"]["name"])@(frm);
for ( size_t i = 0; i < req1.@(field["ros1"]["name"]).size(); ++i)
@[ if field["basic"]]@
req@(to).@(field["ros" + to]["name"])[i] = req@(frm).@(field["ros" + frm]["name"])[i];
@[ else]@
Factory<@(field["ros1"]["cpptype"]),@(field["ros2"]["cpptype"])>::convert_@(frm)_to_@(to)(@
req@(frm).@(field["ros" + frm]["name"])[i], req@(to).@(field["ros" + to]["name"])[i]);
@[ end if]@
@[ elif field["basic"]]@
req@(to).@(field["ros" + to]["name"]) = req@(frm).@(field["ros" + frm]["name"]);
@[ else]@
Factory<@(field["ros1"]["cpptype"]),@(field["ros2"]["cpptype"])>::convert_@(frm)_to_@(to)(@
@(field["ros2"]["name"])@(frm), @(field["ros1"]["name"])@(to));
@[ end if]@
@[ if field["array"]]@
}
req@(frm).@(field["ros" + frm]["name"]), req@(to).@(field["ros" + to]["name"]));
@[ end if]@
@[ end for]@
}
@@ -368,6 +360,18 @@ static void streamPrimitiveVector(ros::serialization::OStream & stream, const VE
memcpy(stream.advance(data_len), &vec.front(), data_len);
}

// This version is for write vector<bool>
template<typename VEC_PRIMITIVE_T>
static void streamPrimitiveVectorBool(ros::serialization::OStream & stream, const VEC_PRIMITIVE_T& vec)
{
const uint32_t step = sizeof(bool);
const uint32_t data_len = vec.size() * sizeof(bool);
// element-wise copy because of vector<bool>
for(uint i = 0; i < vec.size(); ++i)
*(stream.getData()+i*step) = vec[i];
stream.advance(data_len);
}

// This version is for length
template<typename VEC_PRIMITIVE_T>
static void streamPrimitiveVector(ros::serialization::LStream & stream, const VEC_PRIMITIVE_T& vec)
@@ -376,6 +380,14 @@ static void streamPrimitiveVector(ros::serialization::LStream & stream, const VE
stream.advance(data_len);
}

// This version is for length
template<typename VEC_PRIMITIVE_T>
static void streamPrimitiveVectorBool(ros::serialization::LStream & stream, const VEC_PRIMITIVE_T& vec)
{
const uint32_t data_len = vec.size() * sizeof(typename VEC_PRIMITIVE_T::value_type);
stream.advance(data_len);
}

// This version is for read
template<typename VEC_PRIMITIVE_T>
static void streamPrimitiveVector(ros::serialization::IStream & stream, VEC_PRIMITIVE_T& vec)
@@ -385,6 +397,18 @@ static void streamPrimitiveVector(ros::serialization::IStream & stream, VEC_PRIM
memcpy(&vec.front(), stream.advance(data_len), data_len);
}

// This version is for read sector<bool>
template<typename VEC_PRIMITIVE_T>
static void streamPrimitiveVectorBool(ros::serialization::IStream & stream, VEC_PRIMITIVE_T& vec)
{
const uint32_t step = sizeof(bool);
const uint32_t data_len = vec.size() * sizeof(bool);
// element-wise copy because of vector<bool>
for(uint i = 0; i < vec.size(); ++i)
vec[i] = *(stream.getData() + i*step);
stream.advance(data_len);
}

@[for m in mapped_msgs]@

@[ if m.ros2_msg.package_name=="std_msgs" and m.ros2_msg.message_name=="Header"]
@@ -466,6 +490,9 @@ if isinstance(ros2_fields[-1].type, NamespacedType):
{
ros1_bridge::internal_stream_translate_helper(stream, *ros2_it);
}
@[ elif ros2_fields[-1].type.value_type.typename == 'boolean']@
// write primitive type, specialized
streamPrimitiveVectorBool(stream, ros2_msg.@(ros2_field_selection));
@[ else]@
// write primitive type
streamPrimitiveVector(stream, ros2_msg.@(ros2_field_selection));
2 changes: 1 addition & 1 deletion ros1_bridge/__init__.py
Original file line number Diff line number Diff line change
@@ -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

Loading