rmw_fastrtps: message data is wrong when nested message contains floats and booleans
Bug report
Required Info:
- Operating System:
- Ubuntu 22.04.3 LTS
- Installation type:
- Binary
- Version or commit hash:
ros-iron-fastrtps 2.10.2-1jammy.20230908.160451 amd64 ros-iron-fastrtps-cmake-module 3.0.1-1jammy.20230908.160543 amd64 ros-iron-rmw-fastrtps-cpp 7.1.1-2jammy.20230908.165835 amd64 ros-iron-rmw-fastrtps-dynamic-cpp 7.1.1-2jammy.20230908.165838 amd64 ros-iron-rmw-fastrtps-shared-cpp 7.1.1-2jammy.20230908.165115 amd64 ros-iron-rosidl-dynamic-typesupport-fastrtps 0.0.2-2jammy.20230908.162712 amd64 ros-iron-rosidl-typesupport-fastrtps-c 3.0.1-1jammy.20230908.162548 amd64 ros-iron-rosidl-typesupport-fastrtps-cpp 3.0.1-1jammy.20230908.162358 amd64
- DDS implementation:
- Fast-RTPS
- Client library (if applicable):
- rclcpp
Steps to reproduce issue
The bug can be reproduced by having a rclcpp node publish and subscribe to a custom message that has some bools as well as a nested message that has floats and bools
Outer.msg
nested_msg_pub_sub/Inner inner
bool bool_field_1
bool bool_field_2
bool bool_field_3
Inner.msg
float64 float_field
bool bool_field
Simple node that publishes and subscribes to the same topic that uses Outer.msg.
#include "rclcpp/rclcpp.hpp"
#include "nested_msg_pub_sub/msg/outer.hpp"
using namespace std::chrono_literals;
class MinimalPublisher : public rclcpp::Node
{
public:
MinimalPublisher()
: Node("minimal_publisher"), count_(0)
{
publisher_ = this->create_publisher<nested_msg_pub_sub::msg::Outer>("topic", 10);
subscription_ = this->create_subscription<nested_msg_pub_sub::msg::Outer>(
"topic", 10, std::bind(&MinimalPublisher::topic_callback, this, std::placeholders::_1));
timer_ = this->create_wall_timer(
500ms, std::bind(&MinimalPublisher::timer_callback, this));
}
private:
void timer_callback()
{
auto msg = nested_msg_pub_sub::msg::Outer();
msg.inner.float_field = 1.23456789;
msg.inner.bool_field = true;
msg.bool_field_1 = true;
msg.bool_field_2 = true;
msg.bool_field_3 = true;
std::string msg_str = nested_msg_pub_sub::msg::to_yaml(msg);
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", msg_str.c_str());
publisher_->publish(msg);
}
void topic_callback(const nested_msg_pub_sub::msg::Outer & msg) const // CHANGE
{
std::string msg_str = nested_msg_pub_sub::msg::to_yaml(msg);
RCLCPP_INFO(this->get_logger(), "Received: '%s'", msg_str.c_str());
}
rclcpp::Subscription<nested_msg_pub_sub::msg::Outer>::SharedPtr subscription_;
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<nested_msg_pub_sub::msg::Outer>::SharedPtr publisher_;
size_t count_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<MinimalPublisher>());
rclcpp::shutdown();
return 0;
}
Expected behavior
Received message should be the same as the published message.
Actual behavior
Received message have wrong values for boolean fields. This is the output that I get:
[minimal_publisher] [1696005743.235449725] [INFO] [timer_callback():32]: Publishing: 'inner:
float_field: 1.23457
bool_field: true
bool_field_1: true
bool_field_2: true
bool_field_3: true
'
[minimal_publisher] [1696005743.235686748] [INFO] [topic_callback():39]: Received: 'inner:
float_field: 1.23457
bool_field: true
bool_field_1: false
bool_field_2: false
bool_field_3: false
'
Additional information
The bug seems to only happen with fastrtps. With RMW_IMPLEMENTATION=rmw_cyclonedds_cpp things work fine.
About this issue
- Original URL
- State: closed
- Created 9 months ago
- Comments: 19 (9 by maintainers)
@asetapen thank you for the ping, i will be on it.
@asetapen @ycheng517 backport to humble and iron has been completed. i will go ahead to close this one.
@clalancette thanks for taking care of the backports and CI.
Also see https://github.com/ros2/system_tests/pull/530, which is an integration test for this problem.