Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <topic_tools/shape_shifter.h>
00036
00037 using namespace topic_tools;
00038
00039 bool ShapeShifter::uses_old_API_ = false;
00040
00041 ShapeShifter::ShapeShifter()
00042 : typed(false),
00043 msgBuf(NULL),
00044 msgBufUsed(0),
00045 msgBufAlloc(0)
00046 {
00047 }
00048
00049
00050 ShapeShifter::~ShapeShifter()
00051 {
00052 if (msgBuf)
00053 delete[] msgBuf;
00054
00055 msgBuf = NULL;
00056 msgBufAlloc = 0;
00057 }
00058
00059
00060 std::string const& ShapeShifter::getDataType() const { return datatype; }
00061
00062
00063 std::string const& ShapeShifter::getMD5Sum() const { return md5; }
00064
00065
00066 std::string const& ShapeShifter::getMessageDefinition() const { return msg_def; }
00067
00068
00069 void ShapeShifter::morph(const std::string& _md5sum, const std::string& _datatype, const std::string& _msg_def,
00070 const std::string& _latching)
00071 {
00072 md5 = _md5sum;
00073 datatype = _datatype;
00074 msg_def = _msg_def;
00075 latching = _latching;
00076 typed = md5 != "*";
00077 }
00078
00079
00080 ros::Publisher ShapeShifter::advertise(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size_, bool latch, const ros::SubscriberStatusCallback &connect_cb) const
00081 {
00082 ros::AdvertiseOptions opts(topic, queue_size_, getMD5Sum(), getDataType(), getMessageDefinition(), connect_cb);
00083 opts.latch = latch;
00084
00085 return nh.advertise(opts);
00086 }
00087
00088
00089 uint32_t ShapeShifter::size() const
00090 {
00091 return msgBufUsed;
00092 }
00093