ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

What happens to constants in a .msg?

asked 2021-01-23 09:26:20 -0600

Ariel gravatar image

Hello,

If I have the following message:

uint8 val
uint8 a=0
uint32 b=0
string c=this is the string

Which I publish as follows:

#include "ros/ros.h"
#include "test_types/type33.h"

int main(int argc, char **argv)
{
  ros::init(argc, argv, "test_types_publisher_type33");
  ros::NodeHandle n;
  ros::Publisher chatter_pub = n.advertise<test_types::type33>("/test_types/type33", 10);
  ros::Rate loop_rate(1);

  while (ros::ok())
  {
    test_types::type33 msg;
    msg.val=10;

    chatter_pub.publish(msg);
    ros::spinOnce();
    loop_rate.sleep();
  }
  return 0;
}

However when I echo the topic or I check with wireshark, I only see val and the length of the messages in the header is also 1 byte: 01 00 00 00 0a. So where are the constants transmitted? Thanks.

edit retag flag offensive close merge delete

Comments

1
string c=this is the string

is this a verbatim copy-paste? Because string constants should be enclosed in quotes.

gvdhoorn gravatar image gvdhoorn  ( 2021-01-23 10:35:58 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
4

answered 2021-01-23 10:35:03 -0600

gvdhoorn gravatar image

updated 2021-01-24 14:02:08 -0600

So where are the constants transmitted?

Nowhere (*).

They are compile time constants (in compiled languages such as C and C++) or predefined (constant) variables in the namespace of the message class / struct / dictionary for languages like Python. They are not part of the data that gets (de)serialised when exchanging messages.

So in your case, since you don't use test_types::type33::a or any of the other constants anywhere in your code, you'll not see their values anywhere in the serialised data stream.

It would also not be very efficient to do that for each and every message.

The assumption is that publisher and subscriber both have access to the message structure (ie: definition file or code generated from those). As the constants would be present in those representations, the receiving side can use them.

*) I wrote nowhere, but that's not exactly true. The complete message definition is exchanged between publisher and subscriber during setup of the connection, so technically the constant values are also sent to the subscriber.

But that's not as part of the actual message data exchange, hence the nowhere.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2021-01-23 09:26:20 -0600

Seen: 1,715 times

Last updated: Jan 24 '21