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

Extract Header from ShapeShifter

asked 2016-02-11 19:23:28 -0500

solb22 gravatar image

updated 2018-07-30 09:08:34 -0500

lucasw gravatar image

I'm trying to implement something similar to rospy.anymessage via roscpp. I am using Shapeshifter to extract the data. I only need the Header.stamp (I want to compare received time from the time the topic was published).

I'm running into a wall trying to extract the header stamp. I know rosbag imeplement something like this, but I could only find they use SubscriptionCallbackHelperT, but not how.

How can I extract the Header.stamp from a generic ros topic message?

void PerformanceTracker::topicCallback(const ShapeShifter::ConstPtr topicType){
   ros::Time begin = ros::Time::now();
   unsigned char* data = ShapeShifterGetData(topicType);
}

unsigned char* ShapeShifterGetData(const ShapeShifter::ConstPtr message){
  unsigned char* data = new unsigned char[message->size()];
  std::OStream stream(data, message->size());
  message->write(stream);
  return data;
}
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
1

answered 2016-02-12 01:29:37 -0500

Here's easily understandable way that has to drawback of always serializing messages and interpreting the serialized result: topic_buffer_client.

It looks like a more efficient way using SFINAE seems to be implemented here: timeextractor.h With the template magic it's a bit harder to understand though ;)

edit flag offensive delete link more

Comments

Thanks Stefan, I will try both and get back to you. What do you means the drawback of always serializing messages? Are you saying serializing the messages wastes computation time? I can set the received time to before the serialization starts, so it wont affect the measurement of published-received

solb22 gravatar image solb22  ( 2016-02-12 01:49:54 -0500 )edit
1

Yes, serialization can take up some CPU time (and it seems the second approach can do it without serialization).

Stefan Kohlbrecher gravatar image Stefan Kohlbrecher  ( 2016-02-12 02:02:59 -0500 )edit

Ok thanks. Yes the SFINAE is much less clear. Would I just include that file and user timewarp.extractTime() ? Thank you very much for the help !

solb22 gravatar image solb22  ( 2016-02-12 02:51:16 -0500 )edit

Might be possible, but you could also copy parts and make your own minimal version of it (You're not really using it for "timewarping" for instance).

Stefan Kohlbrecher gravatar image Stefan Kohlbrecher  ( 2016-02-12 03:20:14 -0500 )edit

Yeah, I'm going to port that to C++11

solb22 gravatar image solb22  ( 2016-02-12 03:35:42 -0500 )edit

One last question. Why in the SFINAE, is it static yes& test(typename C::_header_type); ? What does C::_header_type mean? Type has a data member named _header_type? Does that match the current ros header data member name? And not just plain C::_header*?

solb22 gravatar image solb22  ( 2016-02-12 04:08:26 -0500 )edit
0

answered 2019-10-24 02:26:52 -0500

dllu gravatar image

If you are sure that the shapeshifter contains a message with a std_msgs::Header, you can try temporarily morphing the shapeshifter into a Header and then instantiating it. This is essentially the same as always serializing it, but because you don't have to have raw uint8_t buffers floating around, it may be more understandable:

ros::Time readStamp(
    const topic_tools::ShapeShifter::ConstPtr& shapeshifter) {
    topic_tools::ShapeShifter* ss_tmp =
        const_cast<topic_tools::ShapeShifter*>(shapeshifter.get());
    auto md5sum = ss_tmp->getMD5Sum();
    auto datatype = ss_tmp->getDataType();
    auto msgdef = ss_tmp->getMessageDefinition();
    ss_tmp->morph(ros::message_traits::md5sum<std_msgs::Header>(),
                  ros::message_traits::datatype<std_msgs::Header>(), "",
                  "");
    auto tmp = ss_tmp->instantiate<std_msgs::Header>();
    ss_tmp->morph(md5sum, datatype, msgdef, "");

    return tmp->stamp;
}

Please note that if you make a copy of ShapeShifter then your code will crash. This is because the ShapeShifter class has a pointer free in its destructor but it does not have a deep copy constructor. So, copying it will result in a double pointer free bug when both instances go out of scope.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2016-02-11 19:23:28 -0500

Seen: 947 times

Last updated: Oct 24 '19