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 : ros::Message(),
00043 typed(false),
00044 msgBuf(NULL),
00045 msgBufUsed(0),
00046 msgBufAlloc(0)
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 {
00071 md5 = _md5sum;
00072 datatype = _datatype;
00073 msg_def = _msg_def;
00074
00075 typed = (md5 != std::string("*"));
00076 }
00077
00078
00079 ros::Publisher ShapeShifter::advertise(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size_, bool latch) const
00080 {
00081 ros::AdvertiseOptions opts(topic, queue_size_, getMD5Sum(), getDataType(), getMessageDefinition());
00082 opts.latch = latch;
00083
00084 return nh.advertise(opts);
00085 }
00086
00087
00088 uint32_t ShapeShifter::size() const
00089 {
00090 return msgBufUsed;
00091 }
00092
00093
00094
00095 const std::string ShapeShifter::__getDataType() const
00096 {
00097 uses_old_API_ = true;
00098 return getDataType();
00099 }
00100
00101 const std::string ShapeShifter::__getMD5Sum() const
00102 {
00103 uses_old_API_ = true;
00104 return getMD5Sum();
00105 }
00106
00107 const std::string ShapeShifter::__getMessageDefinition() const
00108 {
00109 uses_old_API_ = true;
00110 return getMessageDefinition();
00111 }
00112
00113
00114 const std::string ShapeShifter::__s_getDataType()
00115 {
00116 uses_old_API_ = true;
00117 return "*";
00118 }
00119
00120 const std::string ShapeShifter::__s_getMD5Sum()
00121 {
00122 uses_old_API_ = true;
00123 return "*";
00124 }
00125
00126 const std::string ShapeShifter::__s_getMessageDefinition()
00127 {
00128 uses_old_API_ = true;
00129 ROS_ASSERT_MSG(0, "Tried to get static message definition of a ShapeShifter.");
00130 return "";
00131 }
00132
00133
00134 uint8_t*
00135 ShapeShifter::serialize(uint8_t *writePtr, uint32_t) const
00136 {
00137 uses_old_API_ = true;
00138
00139
00140 memcpy(writePtr, msgBuf, msgBufUsed);
00141 return writePtr + msgBufUsed;
00142 }
00143
00144 uint8_t*
00145 ShapeShifter::deserialize(uint8_t *readPtr)
00146 {
00147 uses_old_API_ = true;
00148
00149
00150
00151 md5 = (*__connection_header)["md5sum"];
00152 datatype = (*__connection_header)["type"];
00153 msg_def = (*__connection_header)["message_definition"];
00154 typed = true;
00155
00156
00157 if (__serialized_length > msgBufAlloc)
00158 {
00159 delete[] msgBuf;
00160 msgBuf = new uint8_t[__serialized_length];
00161 msgBufAlloc = __serialized_length;
00162 }
00163 msgBufUsed = __serialized_length;
00164 memcpy(msgBuf, readPtr, __serialized_length);
00165
00166 return NULL;
00167 }
00168
00169
00170