rosserial icon indicating copy to clipboard operation
rosserial copied to clipboard

Some messages with nested array types yield incorrect C++ deserialization code

Open tom-f-oconnell opened this issue 7 years ago • 3 comments

A message of type

stimuli/Pulse[] pulse_seq
  uint8 pin
  stimuli/Transition[] states
    time t
    stimuli/State s
      uint64 ms_on
      uint64 ms_off

will generate code in ros_lib/stimuli/Pulse.h that has a stimuli::Transition pointer. Since each element of the dynamically allocated stimuli::Pulse array in ros_lib/stimuli/PulseSeq.h is first deserialized in the static field st_<type_name> (generated in line 221 of make_library.py), and the realloc will not typically return new addresses after the first allocation (the pointer in the states field is no longer NULL), the address in the states field is the same for each element of pulse_seq. The pin field being set correctly.

This should either be documented as a limitation, or support should be added for messages with this structural motif. The generated Python functions seem to support this specific message type for both serialization and deserialization.

I could do some work towards a PR, if you decide this should be supported, but I could use some pointers (no pun intended) about initial design choices. I (think) I realize that it would be harder to implement support for these kinds of messages while still avoiding memory issues.

Feel free to clone my repository at github.com/tom-f-oconnell/stimuli to get a copy of the offending message types. acf142967 (current HEAD) will have them if something happens to change in later commits.

P.s. in a quick look through some of the messages from other packages on my machine (i.e. std_msgs, etc), I did not see any messages fitting the criteria I described here. Is it a ROS idiom / rule not to make messages like this? I could not find documentation of this restriction, and my messages seem to work with the standard tooling, at least in rospy.

tom-f-oconnell avatar Sep 09 '17 04:09 tom-f-oconnell

There's nothing that prohibits this type of message, and it is very much supported in roscpp and rospy. There's some discussion of rosserial's Array-related limitations in this wiki page, but it doesn't seem to cover the particular case you've found:

http://wiki.ros.org/rosserial/Overview/Limitations#Arrays

I'd be delighted for that page to be updated, and I would also totally entertain a PR that lifts or revisits the limitation. Because the wire format of rosserial's serialization is identical to roscpp, the only changes required would be in the client. I don't have any particular tips or ideas on this— you'd have to give it some thought and make a proposal.

mikepurvis avatar Sep 11 '17 20:09 mikepurvis

Ok, thanks Mike. I added a bit to the end of the Wiki page, and I may work on a PR over the next few weeks when I have time.

tom-f-oconnell avatar Sep 12 '17 07:09 tom-f-oconnell

Hi, I just encountered this issue. I think this should be considered a bug rather than a limitation as the behavior is simply incorrect (without error or warning).

I was trying to create a FollowJointTrajectory action server on firmware. The Goal type includes a JointTrajectory, with a list of JointTrajectoryPoints, which in turn includes a list of float positions. With the incorrect (current) deserialization, the positions of each point were ending up all equal to the positions of the last point. I was able to assert that the pointers were equal (points[0].positions == points[1].positions == points[2].positions ...etc) to confirm this.

To fix this, I changed the generated msg code in JointTrajectory.h from:

if(points_lengthT > points_length)
    this->points = (trajectory_msgs::JointTrajectoryPoint*)realloc(this->points, points_lengthT * sizeof(trajectory_msgs::JointTrajectoryPoint));

points_length = points_lengthT;
for(uint32_t i = 0; i < points_length; i++){
    offset += this->st_points.deserialize(inbuffer + offset);
    memcpy( &(this->points[i]), &(this->st_points), sizeof(trajectory_msgs::JointTrajectoryPoint));
}

to


if(points_lengthT > points_length) {
    this->points = (trajectory_msgs::JointTrajectoryPoint*)realloc(this->points, points_lengthT * sizeof(trajectory_msgs::JointTrajectoryPoint));
  
    for (uint i = points_length; i < points_lengthT; i++) {
        // initialize all uninitialized JointTrajectoryPoints (as they contain random memory after realloc)
        // only need to do this as we are avoiding using st_points because it is broken for array msgs of array msgs
        const JointTrajectoryPoint new_p = JointTrajectoryPoint();
        memcpy(&this->points[i], &new_p, sizeof(JointTrajectoryPoint));
    }
}

points_length = points_lengthT;
for(uint i = 0; i < points_length; i++){
    offset += this->points[i].deserialize(inbuffer + offset);
}

With this fix now working, It leads me to believe that JointTrajectory.st_points and all other st_vars members are a waste of memory. I don't have time to put together a PR, but I'm hoping this might help someone down the road.

CallumJHays avatar Mar 25 '22 05:03 CallumJHays