36 #ifndef ROS_INTROPSECTION_SHAPE_SHIFTER2_H 37 #define ROS_INTROPSECTION_SHAPE_SHIFTER2_H 43 #include <boost/flyweight.hpp> 81 template<
typename Stream>
82 void write(Stream& stream)
const;
86 template<
typename Stream>
87 void read(Stream& stream);
90 template<
typename Message>
94 uint32_t
size()
const;
100 boost::flyweight<std::string>
md5_;
114 namespace message_traits {
125 static const char*
value() {
return "*"; }
134 static const char*
value() {
return "*"; }
146 namespace serialization
152 template<
typename Stream>
157 template<
typename Stream>
178 params.
message->morph(md5, datatype, msg_def);
193 template<
class M>
inline 197 throw std::runtime_error(
"Tried to instantiate message from an untyped ShapeShifter2.");
199 if (ros::message_traits::datatype<M>() !=
getDataType())
200 throw std::runtime_error(
"Tried to instantiate message without matching datatype.");
202 if (ros::message_traits::md5sum<M>() !=
getMD5Sum())
203 throw std::runtime_error(
"Tried to instantiate message without matching md5sum.");
210 template<
typename Stream>
inline 225 template<
typename Stream>
inline 229 msgBuf_.resize( stream.getLength() );
231 memcpy(
msgBuf_.data(), stream.getData(), stream.getLength());
234 template<
typename Message>
inline 276 inline void ShapeShifter::morph(
const std::string& _md5sum,
const std::string& _datatype,
const std::string& _msg_def)
boost::flyweight< std::string > md5_
void direct_read(const Message &msg, bool morph)
! Directly serialize the contentof a message into this ShapeShifter.
const uint8_t * raw_data() const
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
static const char * value(const RosIntrospection::ShapeShifter &m)
static const char * value()
std::vector< uint8_t > msgBuf_
The ShapeShifter class is a type erased container for ROS Messages. It can be used also to create gen...
static const char * value()
static void notify(const PreDeserializeParams< RosIntrospection::ShapeShifter > ¶ms)
boost::flyweight< std::string > datatype_
void instantiate(M &destination) const
Call to try instantiating as a particular type.
void morph(const std::string &md5sum, const std::string &datatype_, const std::string &msg_def_)
std::string const & getMD5Sum() const
static void read(Stream &stream, RosIntrospection::ShapeShifter &m)
void read(Stream &stream)
uint32_t size() const
Return the size of the serialized message.
void serialize(Stream &stream, const T &t)
ros::Publisher advertise(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, bool latch=false, const ros::SubscriberStatusCallback &connect_cb=ros::SubscriberStatusCallback()) const
boost::shared_ptr< M > message
static uint32_t serializedLength(const RosIntrospection::ShapeShifter &m)
static const char * value(const RosIntrospection::ShapeShifter &m)
std::string const & getDataType() const
void write(Stream &stream) const
Write serialized message contents out to a stream.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
boost::shared_ptr< ShapeShifter > Ptr
boost::shared_ptr< ShapeShifter const > ConstPtr
std::string const & getMessageDefinition() const
uint32_t serializationLength(const T &t)
static bool uses_old_API_
boost::shared_ptr< std::map< std::string, std::string > > connection_header
boost::flyweight< std::string > msg_def_
void deserialize(Stream &stream, T &t)
static const char * value(const RosIntrospection::ShapeShifter &m)
static void write(Stream &stream, const RosIntrospection::ShapeShifter &m)