Skip to content
This repository was archived by the owner on Aug 6, 2022. It is now read-only.

The Renamer

Davide Faconti edited this page Oct 17, 2016 · 7 revisions

###Or... "Key-value done right"

Who is familiar with ROS and common ROS Message Types should know one of its most common (and mybe questionable) design patterns: to use a string field as identifier of a message.

Think again about sensor_msgs::JointState.

It uses the field "name" to assign an identifier to a specific index in the other arrays (position, velocity, effort). This means of course that you have to serialize, deserialize and compare these strings in every single message...

Let's pretend this is not a problem.

What does really bother me from the point of view of ros_type_introspection is that its output is order-dependant, while the Key-Value approach in ROS is order-independent.

Let's take a look to an example similar to the one in [the deserializer|The-Deserializer]:

What would happen if the order of the identifiers is shuffled in the following message?

What if another message contains only the a single JointState with JointState.name.0 = second_joint?

// first message
JointState.header.seq >> 1234
JointState.header.stamp >> 2000.00
JointState.header.frame_id >> base_frame

JointState.position.0 >> 11
JointState.velocity.0 >> 21
JointState.effort.0 >> 31
JointState.name.0 >> first_joint

JointState.position.1 >> 12
JointState.velocity.1 >> 22
JointState.effort.1 >> 32
JointState.name.1 >> second_joint


//second message
JointState.header.seq >> 1235
JointState.header.stamp >> 2001.00
JointState.header.frame_id >> base_frame

JointState.position.0 >> 13
JointState.velocity.0 >> 23
JointState.effort.0 >> 33
JointState.name.0 >> second_joint 

If you have ever tried to visualize a tf or tf2 message in rqt_plot, you know what I am talking about.

The order in the array becomes completely irrelevant and data from different Transformation Frames will be mixed together.

What we ideally want in the JointState example is:

// first message
JointState.header.seq >> 1234
JointState.header.stamp >> 2000.00
JointState.header.frame_id >> base_frame

JointState.first_joint.pos >> 11
JointState.first_joint.vel >> 21
JointState.first_joint.eff >> 31

JointState.second_joint.pos >> 12
JointState.second_joint.vel >> 22
JointState.second_joint.eff >> 32

//second message
JointState.header.seq >> 1235
JointState.header.stamp >> 2001.00
JointState.header.frame_id >> base_frame

JointState.second_joint.pos >> 13
JointState.second_joint.vel >> 23
JointState.second_joint.eff >> 33

This can be achieved using the function:

  void applyNameTransform(const std::vector<SubstitutionRule> &rules,
                          ROSTypeFlat* container);                      

This function will use a set of rules to fill the vector ROSTypeFlat::renamed_value using the data contained in:

  • ROSTypeFlat::value and
  • ROSTypeFlat::name.

The rules used to perform the remapping in the JointState example are:

std::vector<SubstitutionRule> rules;

rules.push_back( SubstitutionRule( "position.#", "name.#", "@.pos" ));
rules.push_back( SubstitutionRule( "velocity.#", "name.#", "@.vel" ));  
rules.push_back( SubstitutionRule( "effort.#", "name.#", "@.eff" ));

These rules are pretty easy to use once they are understood. For instance, let's consider the following example:

  the rule   `SubstitutionRule( "position.#", "name.#", "@.pos" )`
  is using   `JointState.name.0 = first_joint`
  to convert `JointState.position.0 = 11`
  into       `JointState.first_joint.pos = 11`
  1. The first argument, "position.#", means: "find any element in ROSTypeFlat::value which contains the pattern [position.#] where # is a number".

    JointState.position.0 = 11

  2. The second argument, "name.#", means: "find the element in ROSTypeFlat::name which contains the pattern [name.#] where # is the same number found in the previous pattern".

    JointState.name.0 = first_joint

  3. The third argument, "@.pos", means: "substitute the pattern found in 1. with this string, where the symbol @ represents the name found in 2". The final result is therefore:

    JointState.first_joint.pos = 11

Clone this wiki locally