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

GenericPublisher using ShapeShifter and SerializedMessage

asked 2011-12-11 22:40:20 -0600

Felix Messmer gravatar image

Hi there,

I want to write a generic publisher that is able to publish ros-topics where each instance of this class publishes topics of different message types (e.g. pub_1 publishes std_msg::Int32, pub_2 publishes sensor_msgs::PointCloud2,...).

I work with serialized messages, i.e.:

ros::serialization::IStream i_stream((u_int8_t*) testArray.data(), m_genericRosTopic.SerializedMessageSize);

contains my serialized message which I want to publish. I also know the message type and the topic_name, that I want to publish on.

How can I do this in a generic way? I saw that the ros::Publisher class has a publish() function that is able to publish a ros::SerializedMessage.

Thus, I made a SerializedMessage from the IStream:

boost::shared_array<uint8_t> buf(i_stream.getData());
ros::SerializedMessage msg(buf, i_stream.getLength());

My generic publisher class has a ros::Publisher as a member. For advertising, I found:

m_genericRosTopic_publisher = m_shapeShifter.advertise(n, m_genericRosTopic.TopicName, 10);

After that I would like to publish the topic somehow:

m_genericRosTopic_publisher.publish(msg);

Publishing like this doesn't work. I guess there is still something missing. But it seems that everything I need is already there (somewhere in roscpp), but I am not able to put the puzzle together.

Can someone help me out here, by clarifying the correct usage of topic_tools::ShapeShifter, ros::SerializedMessage and ros::Publisher?

Thanks for your help!

edit retag flag offensive close merge delete

6 Answers

Sort by » oldest newest most voted
1

answered 2011-12-19 02:35:55 -0600

Felix Messmer gravatar image

I solved the problem:

The ByteArrayMessage::serialize function is called as soon as a subscriber subscribes to the topic published by the GenericPublisher. The publisher than has to write the data from buffer_ to the write_ptr given by the subscriber.

Thus the function looks like this:

const uint8_t* ByteArrayMessage::serialize(uint8_t *write_ptr, uint32_t seq) const
{
    ros::serialization::OStream stream(write_ptr, 1000000000);
    for (size_t i = 0; i < length_; i++) 
    {
      stream.next(buffer_[i]);
    }

    return stream.getData();
}

I don't need the Serializer struct.

Thanks for your help!

edit flag offensive delete link more

Comments

Don't forget that the interface you are implementing is already deprecated. Your code will not work under electric and newer ROS releases.
Lorenz gravatar image Lorenz  ( 2011-12-19 03:30:07 -0600 )edit
Hmm. It works under electric! So what is the deprecated part? The functions of the Serializer are not used. What am I missing?
Felix Messmer gravatar image Felix Messmer  ( 2011-12-19 17:12:26 -0600 )edit

Hey Lorenz, do you have that code anywhere? I couldn't find it on your Github

Mehdi. gravatar image Mehdi.  ( 2017-09-11 08:07:30 -0600 )edit
1

answered 2011-12-12 03:38:20 -0600

Felix Messmer gravatar image

Thanks for the reply, Lorenz.

Maybe, I didn't say it clear enough: Each generic publisher is only publishing on one single topic. The type, the topic_name, message_definition and md5sum does not change once advertised. But each instance of this generic publisher class publishes a topic of a different type. (instance pub_1 of GenericPublisher publishes only messages of type std::Int32, instance pub_2 of GenericPublisher publishes messages of type sensor_msgs::PointCloud2,...)

In the meantime, I also know the md5sum and the message definition within GenericPublisher.

Thus I can advertise as followed:

ros::AdvertiseOptions opts( "/generic_topic_opc_client"+m_genericRosTopic.TopicName, 10, m_genericRosTopic.MD5Sum, m_genericRosTopic.MessageDataType, m_genericRosTopic.MessageDefinition);
m_genericRosTopic_publisher = n.advertise(opts);

Still, I don't know what

m_genericRosTopic_publisher.publish()

expects as a parameter and how I can get this parameter from

ros::serialization::IStream i_stream((u_int8_t*) testArray.data(), m_genericRosTopic.SerializedMessageSize);
edit flag offensive delete link more

Comments

Sorry. I guess it was my fault, I didn't read your post careful enough. I updated my answer. Hopefully this time it helps :)
Lorenz gravatar image Lorenz  ( 2011-12-12 04:30:04 -0600 )edit
1

answered 2011-12-17 10:27:04 -0600

abdullah gravatar image

I am doing the same work. I am publishing topic_tools::ShapeShifter msg. And I have got some help from rosbag package. Try to compare your class ByteArrayMessage with the class MessageInstance class in rosbag package. Its look very similar. But you will get much info from messgae_instance.h in rosbag package. In my code I have used that MessageInstance class by changing it a little.

Now to publish that message. get help from the following code. If we want to publish multiple topics we can use the following code. I have got help from here

std::map<std::string, ros::Publisher> mPublishers;

ros::Publisher getPublisher(const std::string& topic, MessageInstance &m)
  {
 if (mPublishers.find(topic) == mPublishers.end())
 {
ros::AdvertiseOptions opts = createAdvertiseOptions(m, 10);

ros::NodeHandle mNh;
mPublishers[topic] = mNh.advertise(opts);
  }

return mPublishers[topic];
}

use that function

ros::Publisher pub = getPublisher(connection_info->topic, m);
pub.publish(m);

I hope that it will work.

edit flag offensive delete link more
-1

answered 2011-12-18 23:07:00 -0600

Felix Messmer gravatar image

Hello,

I had a small success with my problem.

I am now able to publish messages, i.e. each instance of my GenericPublisher class is now able to publish on the correct topic with the correct type at the correct time.

But still there is no data in the message. It publishes 0 for the std_msgs::Int32 and '' for the std_msgs::String.

This is the ByteArrayMessage class:

class ByteArrayMessage 
{
public:
    ByteArrayMessage(uint8_t* buffer, uint32_t length, std::string dataType, std::string md5sum, std::string messageDefinition) 
        : __serialized_length(length),
          m_dataType(dataType),
          m_md5sum(md5sum),
          m_messageDefinition(messageDefinition),
          buffer_(buffer), length_(length)
    {}

    const std::string __getDataType() const {   return m_dataType;  }
    const std::string __getMD5Sum() const   {   return m_md5sum;    }
    const std::string __getMessageDefinition() const    {   return m_messageDefinition; }

    uint32_t serializationLength() const    {   return __serialized_length; }
    uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const;

    uint8_t byte(size_t i) {    return buffer_[i];  }
    uint32_t length() { return length_; }

    uint32_t __serialized_length;


private:
    std::string m_dataType;
    std::string m_md5sum;
    std::string m_messageDefinition;

    uint8_t *buffer_;
    uint32_t length_;
};

uint8_t* ByteArrayMessage::serialize(uint8_t *write_ptr, uint32_t seq) const
{
    ROS_INFO("call ByteArrayMessage::serialize");
    return buffer_;
}

This is the Serializer struct that I use:

namespace serialization{

template<>
struct Serializer<ByteArrayMessage>{
    template<typename Stream>
    inline static void write(Stream& stream, const ByteArrayMessage& m) {
        m.write(stream);
    }

    inline static uint32_t serializedLength(const ByteArrayMessage& m) {
        return m.length();  
    }
};

} // namespace serialization

Initialization as follows:

ByteArrayMessage msg(i_stream.getData(), i_stream.getLength(), m_genericRosTopic.MessageDataType, m_genericRosTopic.MD5Sum, m_genericRosTopic.MessageDefinition);

msg.byte() shows that buffer_ in my ByteArrayMessage it contains the desired message.

I also recognized that neither the serialize nor the write function is called during execution. Thus it seems that the Stream is still empty.

Can anyone give me a little more details on what happens when calling

m_genericRosTopic_publisher.publish(msg);

Any suggestions on how I can get the buffer_ data into the stream?

edit flag offensive delete link more
-1

answered 2011-12-13 18:51:32 -0600

Felix Messmer gravatar image

Ok, I tried to do this. But I haven't been successful yet.

Here is what I did:

class ByteArrayMessage 
{
public:
    ByteArrayMessage(const uint8_t *buffer, uint32_t length, std::string dataType, std::string md5sum, std::string messageDefinition) 
        : __serialized_length(length),
          m_dataType(dataType),
          m_md5sum(md5sum),
          m_messageDefinition(messageDefinition),
          buffer_(buffer), length_(length)
    {}

    const std::string __getDataType() const {   return m_dataType;  }
    const std::string __getMD5Sum() const   {   return m_md5sum;    }
    const std::string __getMessageDefinition() const    {   return m_messageDefinition; }

    uint32_t serializationLength() const    {   return __serialized_length; }
    uint8_t *serialize(uint8_t *write_ptr, uint32_t seq);

    const uint8_t byte(size_t i) {  return buffer_[i];  }
    uint32_t length() { return length_; }

    uint32_t __serialized_length;

private:
    std::string m_dataType;
    std::string m_md5sum;
    std::string m_messageDefinition;

    const uint8_t *buffer_;
    uint32_t length_;
};

namespace serialization {
template<typename T>
struct Serializer {
  template<typename Stream>
  inline static void write(Stream& stream, T t) 
  {
    for (size_t i = 0; i < t.length(); i++) 
    {
      stream.next(t.byte(i));
    }
  }

  inline static uint32_t serializedLength(const ByteArrayMessage &msg) 
  {
    return msg.length();
  }      
};
}  //namespace serialization

I created the new class ByteArrayMessage and the Serializer you proposed.

I also had to add the functions __get*(), *serialize(), serializationLength() since they are requested by publisher.publish() as well. It seems that ByteArrayMessage should be derived from ros::Message. True?

Well the above mentioned is my current version. I get the following compiling error message:

 40%] Building CXX object CMakeFiles/simple_opc_client.dir/ros/src/generic_publisher.o
In file included from /home/fxm/git/cob3_intern/cob_sandbox/generic_topic_opc_client/ros/src/generic_publisher.cpp:2:0:
/home/fxm/git/cob3_intern/cob_sandbox/generic_topic_opc_client//ros/include/generic_topic_opc_client/byte_array_message.h:64:29: warning: type qualifiers ignored on function return type
In file included from /opt/ros/diamondback/stacks/ros_comm/clients/cpp/roscpp/include/ros/publisher.h:34:0,
                 from /opt/ros/diamondback/stacks/ros_comm/clients/cpp/roscpp/include/ros/node_handle.h:32,
                 from /opt/ros/diamondback/stacks/ros_comm/clients/cpp/roscpp/include/ros/ros.h:45,
                 from /home/fxm/git/cob3_intern/cob_sandbox/generic_topic_opc_client//ros/include/generic_topic_opc_client/generic_publisher.h:7,
                 from /home/fxm/git/cob3_intern/cob_sandbox/generic_topic_opc_client/ros/src/generic_publisher.cpp:1:
/opt/ros/diamondback/stacks/ros_comm/clients/cpp/roscpp_serialization/include/ros/serialization.h: In static member function ‘static void ros::serialization::Serializer<T>::write(Stream&, typename boost::call_traits<T>::param_type) [with Stream = ros::serialization::OStream, T = ByteArrayMessage, typename boost::call_traits<T>::param_type = const ByteArrayMessage&]’:
/opt/ros/diamondback/stacks/ros_comm/clients/cpp/roscpp_serialization/include/ros/serialization.h:152:3:   instantiated from ‘void ros::serialization::serialize(Stream&, const T&) [with T = ByteArrayMessage, Stream = ros::serialization::OStream]’
/opt/ros/diamondback/stacks/ros_comm/clients/cpp/roscpp_serialization/include/ros/serialization.h:812:3:   instantiated from ‘ros::SerializedMessage ros::serialization::serializeMessage(const M&) [with M = ByteArrayMessage]’
/opt/ros/diamondback/stacks/ros_comm/clients/cpp/roscpp/include/ros/publisher.h:115:5:   instantiated from ‘void ros::Publisher::publish(const M&) const [with M = ByteArrayMessage]’
/home/fxm/git/cob3_intern/cob_sandbox/generic_topic_opc_client/ros/src/generic_publisher.cpp:108:41:   instantiated from here
/opt/ros/diamondback/stacks/ros_comm/clients/cpp/roscpp_serialization/include/ros/serialization.h:124:5: error: passing ‘const ByteArrayMessage’ as ‘this’ argument of ‘uint8_t* ByteArrayMessage::serialize(uint8_t*, uint32_t)’ discards qualifiers
make[3]: *** [CMakeFiles/simple_opc_client ...
(more)
edit flag offensive delete link more

Comments

I'm not sure why you had to implement the serialize method. The ros::Message base class should be deprecated nowadays. I think it would be a good idea for you to switch to electric. The compiler error you get indicates that you need to make your serialize method const.
Lorenz gravatar image Lorenz  ( 2011-12-13 21:36:54 -0600 )edit
-1

answered 2011-12-12 02:27:03 -0600

Lorenz gravatar image

updated 2011-12-12 04:29:27 -0600

You didn't say which error you actually get. I assume the problem is that you pass a SerializedMessage to publisher which actually expects something that can be serialized into a SerializedMessage. To publish a message, you need to implement a Serializer struct, specialized on your data type as explained here. For just a pure byte array, the implementation should be pretty trivial, something like the following:

class Foo {
 public:
  Foo(const char *buffer, size_t length) 
      : buffer_(buffer), length_(length) {}
  const char byte(size_t i) { 
    return buffer[i]; 
   }
   size_t length() {
     return length_;
   }
  private:
   const char *buffer_;
   size_t length_;
};

namespace serialization {
template<>
struct Serializer<Foo> {
  template<typename Stream, typename T>
  inline static void write(Stream& stream, T t) {
    for (size_t i = 0; i < t.length(); i++) {
      stream.next(t.byte(i));
    }
  }
  inline static uint32_t serializedLength(const Foo &foo) {
    return foo.length();
  }      
};
}  //namespace serialization

Note that the code doesn't implement any code for deserializing the message which is (hopefully) not necessary for publishing messages.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2011-12-11 22:40:20 -0600

Seen: 2,996 times

Last updated: Dec 19 '11