Comments (2)
Yeah, this limitation is because the template logic attempts to detect whether the message is of ROSMessageType or of CustomType. In this case, since both are ROSMessageType, it will almost certainly generate the wrong code.
Off-hand, I don't know of a simple way to fix this, but there may be something we can do in the templates to detect the situation and fail to compile, rather than fail at runtime. But I'm not template metaprogramming expert, so I don't exactly know how this would be done.
from rclcpp.
I get more info as follows:
# Msg2.msg
uint32 u32
uint64 u64
// rosAdapter.hpp
#ifndef ROS_ADAPTER_HPP
#define ROS_ADAPTER_HPP
#include <string>
#include <iostream>
#include "rclcpp/type_adapter.hpp"
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/byte_multi_array.hpp"
#include "std_msgs/msg/header.hpp"
#include "tutorial_interfaces/msg/test_msg.hpp"
#include "tutorial_interfaces/msg/msg2.hpp"
#define ROS_TYPE
#ifdef ROS_TYPE
using MsgT = tutorial_interfaces::msg::TestMsg;
#else
using MsgT = std::string;
#endif // ROS_TYPE
template <>
struct rclcpp::TypeAdapter<MsgT, tutorial_interfaces::msg::Msg2>
{
using is_specialized = std::true_type;
using custom_type = MsgT;
using ros_message_type = tutorial_interfaces::msg::Msg2;
static void
convert_to_ros_message(
const custom_type &source,
ros_message_type &destination)
{
std::cout << "convert_to_ros_message!!!" << std::endl;
#ifdef ROS_TYPE
destination.u32 = source.id;
destination.u64 = source.time;
#else
destination.data.resize(source.size());
memcpy(destination.data.data(), source.data(), source.size());
#endif
}
static void
convert_to_custom(
const ros_message_type &source,
custom_type &destination)
{
std::cout << "convert_to_custom!!!" << std::endl;
#ifdef ROS_TYPE
destination.id = source.u32;
destination.time = source.u64;
std::cout << "destination.id = " << destination.id << std::endl;
std::cout << "destination.time = " << destination.time << std::endl;
#else
memcpy(destination.data(), source.data.data(), source.data.size());
#endif
}
};
RCLCPP_USING_CUSTOM_TYPE_AS_ROS_MESSAGE_TYPE(MsgT, tutorial_interfaces::msg::Msg2);
#endif // ROS_ADAPTER_HPP
In subscriber:
$ ros2 run topics sub
convert_to_custom!!!
destination.id = 51
destination.time = 305419896
msg.id = 51
msg.time = 305419896
convert_to_custom!!!
destination.id = 52
destination.time = 305419896
msg.id = 52
msg.time = 305419896
convert_to_custom!!!
destination.id = 53
destination.time = 305419896
msg.id = 53
msg.time = 305419896
convert_to_custom!!!
destination.id = 54
destination.time = 305419896
msg.id = 54
msg.time = 305419896
...
It works fine from one RosMsg Type (tutorial_interfaces::msg::TestMsg) to another Type (tutorial_interfaces::msg::Msg2).
But, the ros2 topic info get wrong output:
$ ros2 topic info /topic
Type: tutorial_interfaces/msg/TestMsg
Publisher count: 1
Subscription count: 0
The Type
field above should be tutorial_interfaces::msg::Msg2.
from rclcpp.
Related Issues (20)
- TimersManager doesn't follow ROS time HOT 2
- rclcpp_action: Provide enum class return ClientGoalHandle::get_status
- Callback works on Galactic but fails on Rolling - handle_message is not implemented for GenericSubscription HOT 1
- Clang warning: ordered comparison of function pointers (Rolling) HOT 1
- `-fanalyzer` warning: possible null dereference when using TypeAdapters HOT 4
- leak due to std::shared_ptr circular reference between Context and GuardCondition HOT 3
- :farmer: `rclcpp.test_executors` failing in Rolling and Jammy CycloneDDS HOT 1
- rclcpp::Time(int64_t nanoseconds, ...) should check for negative time
- Regression : Executor::spin_some_impl is active waiting HOT 5
- Parameter service behavior is inconsistent with the documentation of rcl_interfaces HOT 9
- Lifecycle destructor calls shutdown while in shuttingdown intermediate state HOT 45
- Backport PR2063 to Humble for Windows HOT 2
- Executor callbacks are no longer in a predictable order HOT 25
- '/clock' Topic cannot change each loop step time from simulation time HOT 10
- Program exits with code -11 when using async_send_request to set parameters in ROS 2 C++ client HOT 1
- Timer callbacks can be delayed when using simulation time HOT 4
- Possible regression in rcl preshutdown callbacks - context invalid? HOT 10
- Shutdown transition on base lifecycle node dtor may lead to segaults on subclass-registered shutdown callback HOT 6
- `on_shutdown` callback not called when `shutdown` transition is triggered on dtor HOT 2
- ABI/API Compliance Checker in github workflow HOT 2
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from rclcpp.