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

Twist geometry_msg always read as all zeroes #37

Closed
ssemenova opened this issue Nov 22, 2020 · 2 comments
Closed

Twist geometry_msg always read as all zeroes #37

ssemenova opened this issue Nov 22, 2020 · 2 comments

Comments

@ssemenova
Copy link

ssemenova commented Nov 22, 2020

Hey all, let me preface the question by thanking you for working on this, it's incredibly useful for a project I am working on and exciting to see Rust being used for robotics work.

I am running into an issue with sending a Twist message, where regardless of what actual vectors I send, the publisher always reads both angular and linear velocities as all zeroes.

I publish the message like this:

let linear = geometry_msgs::msg:Vector3 {x: 10.0, y: 0.0, z: 0.0};
let angular = geometry_msgs::msg:Vector3 {x: 0.0, y: 0.0, z: 0.0};

let message = geometry_msgs::msg::Twist {linear, angular};

let result = publisher.publish(&message);
match result {
   Ok(result) => println!("Publishing: {}", message.x.linear),
   Err(result) => println!("Could not publish velocity")
}

And read it like this:

let _subscription = node.create_subscription::<geometry_msgs::msg::Twist, _>(
   "cmd_vel",
   rclrs::QOS_PROFILE_DEFAULT,
   move |msg: &geometry_msgs:msg::Twist| {
      println!("I heard: {}", msg.linear.x);
   },
);

The output of my program always has the subscriber reading a 0 in the linear x velocity. So the output of the above two print statements ends up being:

Publishing: 10
I heard: 0

I can also verify this through ros2 topic echo cmd_vel:

linear:
   x: 0.0
   y: 0.0
   z: 0.0
angular:
   x: 0.0
   y: 0.0
   z: 0.0

I wonder if this is an issue with the generator for a geometry_msg in particular, or if I'm doing something wrong with sending the message. I don't understand how the ros2-rust code works perfectly so I'm having some difficulty digging into it to figure out what the problem is.

Thank you.

Edit
Actually, this seems to be happening with a Pose message as well (but not, for example, a Vector3). I wonder if the issue is a message type that has nested within it another message type?

@ssemenova
Copy link
Author

Another update: The error is in the generated function get_native_message() and the internal C function it calls (e.g., geometry_msgs_msg_twist_get_native_message()) for any message type comprised of nested message types, in any of the generated msg.rs files. A message type that works (Vector3), has this function definition:

geometry_msgs_msg_vector3_get_native_message(
self.x,
self.y,
self.z,
) -> uintptr_t;

However, a message type that does not work (Twist), has this function definition:

geometry_msgs_msg_twist_get_native_message() -> uintptr_t;

I'm pretty sure that this function should take, as input, the data of the linear and angular velocities.

This all boils down to the msg.rs.em file, which generates these rust message files, on line 31 and line 55. Both these code blocks check for the member.type to be equal to Array, AbstractGenericString, and BasicType, but a member that is itself a message is of type NamespacedType and is never included!

I tried adding it in, but then I realized that even if I could generate Rust code that properly sends nested message contents, I have no idea how it's being handled on the C/C++ side. I started looking into rosidl message generation, but I think I'm a little in too deep here. With posts such as #27, I'm worried that there might not even be rosidl support for nested message types.

@nnmm
Copy link
Contributor

nnmm commented Mar 18, 2022

Closed by #80.

@nnmm nnmm closed this as completed Mar 18, 2022
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants