Just changed OUTPUT_SIZE and INPUT_SIZE in ros/node_handle.h
Dependents: WRS2020_mecanum_node
Marker.h
00001 #ifndef _ROS_visualization_msgs_Marker_h 00002 #define _ROS_visualization_msgs_Marker_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "std_msgs/Header.h" 00009 #include "geometry_msgs/Pose.h" 00010 #include "geometry_msgs/Vector3.h" 00011 #include "std_msgs/ColorRGBA.h" 00012 #include "ros/duration.h" 00013 #include "geometry_msgs/Point.h" 00014 00015 namespace visualization_msgs 00016 { 00017 00018 class Marker : public ros::Msg 00019 { 00020 public: 00021 typedef std_msgs::Header _header_type; 00022 _header_type header; 00023 typedef const char* _ns_type; 00024 _ns_type ns; 00025 typedef int32_t _id_type; 00026 _id_type id; 00027 typedef int32_t _type_type; 00028 _type_type type; 00029 typedef int32_t _action_type; 00030 _action_type action; 00031 typedef geometry_msgs::Pose _pose_type; 00032 _pose_type pose; 00033 typedef geometry_msgs::Vector3 _scale_type; 00034 _scale_type scale; 00035 typedef std_msgs::ColorRGBA _color_type; 00036 _color_type color; 00037 typedef ros::Duration _lifetime_type; 00038 _lifetime_type lifetime; 00039 typedef bool _frame_locked_type; 00040 _frame_locked_type frame_locked; 00041 uint32_t points_length; 00042 typedef geometry_msgs::Point _points_type; 00043 _points_type st_points; 00044 _points_type * points; 00045 uint32_t colors_length; 00046 typedef std_msgs::ColorRGBA _colors_type; 00047 _colors_type st_colors; 00048 _colors_type * colors; 00049 typedef const char* _text_type; 00050 _text_type text; 00051 typedef const char* _mesh_resource_type; 00052 _mesh_resource_type mesh_resource; 00053 typedef bool _mesh_use_embedded_materials_type; 00054 _mesh_use_embedded_materials_type mesh_use_embedded_materials; 00055 enum { ARROW = 0 }; 00056 enum { CUBE = 1 }; 00057 enum { SPHERE = 2 }; 00058 enum { CYLINDER = 3 }; 00059 enum { LINE_STRIP = 4 }; 00060 enum { LINE_LIST = 5 }; 00061 enum { CUBE_LIST = 6 }; 00062 enum { SPHERE_LIST = 7 }; 00063 enum { POINTS = 8 }; 00064 enum { TEXT_VIEW_FACING = 9 }; 00065 enum { MESH_RESOURCE = 10 }; 00066 enum { TRIANGLE_LIST = 11 }; 00067 enum { ADD = 0 }; 00068 enum { MODIFY = 0 }; 00069 enum { DELETE = 2 }; 00070 enum { DELETEALL = 3 }; 00071 00072 Marker(): 00073 header(), 00074 ns(""), 00075 id(0), 00076 type(0), 00077 action(0), 00078 pose(), 00079 scale(), 00080 color(), 00081 lifetime(), 00082 frame_locked(0), 00083 points_length(0), points(NULL), 00084 colors_length(0), colors(NULL), 00085 text(""), 00086 mesh_resource(""), 00087 mesh_use_embedded_materials(0) 00088 { 00089 } 00090 00091 virtual int serialize(unsigned char *outbuffer) const 00092 { 00093 int offset = 0; 00094 offset += this->header.serialize(outbuffer + offset); 00095 uint32_t length_ns = strlen(this->ns); 00096 varToArr(outbuffer + offset, length_ns); 00097 offset += 4; 00098 memcpy(outbuffer + offset, this->ns, length_ns); 00099 offset += length_ns; 00100 union { 00101 int32_t real; 00102 uint32_t base; 00103 } u_id; 00104 u_id.real = this->id; 00105 *(outbuffer + offset + 0) = (u_id.base >> (8 * 0)) & 0xFF; 00106 *(outbuffer + offset + 1) = (u_id.base >> (8 * 1)) & 0xFF; 00107 *(outbuffer + offset + 2) = (u_id.base >> (8 * 2)) & 0xFF; 00108 *(outbuffer + offset + 3) = (u_id.base >> (8 * 3)) & 0xFF; 00109 offset += sizeof(this->id); 00110 union { 00111 int32_t real; 00112 uint32_t base; 00113 } u_type; 00114 u_type.real = this->type; 00115 *(outbuffer + offset + 0) = (u_type.base >> (8 * 0)) & 0xFF; 00116 *(outbuffer + offset + 1) = (u_type.base >> (8 * 1)) & 0xFF; 00117 *(outbuffer + offset + 2) = (u_type.base >> (8 * 2)) & 0xFF; 00118 *(outbuffer + offset + 3) = (u_type.base >> (8 * 3)) & 0xFF; 00119 offset += sizeof(this->type); 00120 union { 00121 int32_t real; 00122 uint32_t base; 00123 } u_action; 00124 u_action.real = this->action; 00125 *(outbuffer + offset + 0) = (u_action.base >> (8 * 0)) & 0xFF; 00126 *(outbuffer + offset + 1) = (u_action.base >> (8 * 1)) & 0xFF; 00127 *(outbuffer + offset + 2) = (u_action.base >> (8 * 2)) & 0xFF; 00128 *(outbuffer + offset + 3) = (u_action.base >> (8 * 3)) & 0xFF; 00129 offset += sizeof(this->action); 00130 offset += this->pose.serialize(outbuffer + offset); 00131 offset += this->scale.serialize(outbuffer + offset); 00132 offset += this->color.serialize(outbuffer + offset); 00133 *(outbuffer + offset + 0) = (this->lifetime.sec >> (8 * 0)) & 0xFF; 00134 *(outbuffer + offset + 1) = (this->lifetime.sec >> (8 * 1)) & 0xFF; 00135 *(outbuffer + offset + 2) = (this->lifetime.sec >> (8 * 2)) & 0xFF; 00136 *(outbuffer + offset + 3) = (this->lifetime.sec >> (8 * 3)) & 0xFF; 00137 offset += sizeof(this->lifetime.sec); 00138 *(outbuffer + offset + 0) = (this->lifetime.nsec >> (8 * 0)) & 0xFF; 00139 *(outbuffer + offset + 1) = (this->lifetime.nsec >> (8 * 1)) & 0xFF; 00140 *(outbuffer + offset + 2) = (this->lifetime.nsec >> (8 * 2)) & 0xFF; 00141 *(outbuffer + offset + 3) = (this->lifetime.nsec >> (8 * 3)) & 0xFF; 00142 offset += sizeof(this->lifetime.nsec); 00143 union { 00144 bool real; 00145 uint8_t base; 00146 } u_frame_locked; 00147 u_frame_locked.real = this->frame_locked; 00148 *(outbuffer + offset + 0) = (u_frame_locked.base >> (8 * 0)) & 0xFF; 00149 offset += sizeof(this->frame_locked); 00150 *(outbuffer + offset + 0) = (this->points_length >> (8 * 0)) & 0xFF; 00151 *(outbuffer + offset + 1) = (this->points_length >> (8 * 1)) & 0xFF; 00152 *(outbuffer + offset + 2) = (this->points_length >> (8 * 2)) & 0xFF; 00153 *(outbuffer + offset + 3) = (this->points_length >> (8 * 3)) & 0xFF; 00154 offset += sizeof(this->points_length); 00155 for( uint32_t i = 0; i < points_length; i++){ 00156 offset += this->points[i].serialize(outbuffer + offset); 00157 } 00158 *(outbuffer + offset + 0) = (this->colors_length >> (8 * 0)) & 0xFF; 00159 *(outbuffer + offset + 1) = (this->colors_length >> (8 * 1)) & 0xFF; 00160 *(outbuffer + offset + 2) = (this->colors_length >> (8 * 2)) & 0xFF; 00161 *(outbuffer + offset + 3) = (this->colors_length >> (8 * 3)) & 0xFF; 00162 offset += sizeof(this->colors_length); 00163 for( uint32_t i = 0; i < colors_length; i++){ 00164 offset += this->colors[i].serialize(outbuffer + offset); 00165 } 00166 uint32_t length_text = strlen(this->text); 00167 varToArr(outbuffer + offset, length_text); 00168 offset += 4; 00169 memcpy(outbuffer + offset, this->text, length_text); 00170 offset += length_text; 00171 uint32_t length_mesh_resource = strlen(this->mesh_resource); 00172 varToArr(outbuffer + offset, length_mesh_resource); 00173 offset += 4; 00174 memcpy(outbuffer + offset, this->mesh_resource, length_mesh_resource); 00175 offset += length_mesh_resource; 00176 union { 00177 bool real; 00178 uint8_t base; 00179 } u_mesh_use_embedded_materials; 00180 u_mesh_use_embedded_materials.real = this->mesh_use_embedded_materials; 00181 *(outbuffer + offset + 0) = (u_mesh_use_embedded_materials.base >> (8 * 0)) & 0xFF; 00182 offset += sizeof(this->mesh_use_embedded_materials); 00183 return offset; 00184 } 00185 00186 virtual int deserialize(unsigned char *inbuffer) 00187 { 00188 int offset = 0; 00189 offset += this->header.deserialize(inbuffer + offset); 00190 uint32_t length_ns; 00191 arrToVar(length_ns, (inbuffer + offset)); 00192 offset += 4; 00193 for(unsigned int k= offset; k< offset+length_ns; ++k){ 00194 inbuffer[k-1]=inbuffer[k]; 00195 } 00196 inbuffer[offset+length_ns-1]=0; 00197 this->ns = (char *)(inbuffer + offset-1); 00198 offset += length_ns; 00199 union { 00200 int32_t real; 00201 uint32_t base; 00202 } u_id; 00203 u_id.base = 0; 00204 u_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00205 u_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00206 u_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00207 u_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00208 this->id = u_id.real; 00209 offset += sizeof(this->id); 00210 union { 00211 int32_t real; 00212 uint32_t base; 00213 } u_type; 00214 u_type.base = 0; 00215 u_type.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00216 u_type.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00217 u_type.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00218 u_type.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00219 this->type = u_type.real; 00220 offset += sizeof(this->type); 00221 union { 00222 int32_t real; 00223 uint32_t base; 00224 } u_action; 00225 u_action.base = 0; 00226 u_action.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00227 u_action.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00228 u_action.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00229 u_action.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00230 this->action = u_action.real; 00231 offset += sizeof(this->action); 00232 offset += this->pose.deserialize(inbuffer + offset); 00233 offset += this->scale.deserialize(inbuffer + offset); 00234 offset += this->color.deserialize(inbuffer + offset); 00235 this->lifetime.sec = ((uint32_t) (*(inbuffer + offset))); 00236 this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00237 this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00238 this->lifetime.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00239 offset += sizeof(this->lifetime.sec); 00240 this->lifetime.nsec = ((uint32_t) (*(inbuffer + offset))); 00241 this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00242 this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00243 this->lifetime.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00244 offset += sizeof(this->lifetime.nsec); 00245 union { 00246 bool real; 00247 uint8_t base; 00248 } u_frame_locked; 00249 u_frame_locked.base = 0; 00250 u_frame_locked.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00251 this->frame_locked = u_frame_locked.real; 00252 offset += sizeof(this->frame_locked); 00253 uint32_t points_lengthT = ((uint32_t) (*(inbuffer + offset))); 00254 points_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00255 points_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00256 points_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00257 offset += sizeof(this->points_length); 00258 if(points_lengthT > points_length) 00259 this->points = (geometry_msgs::Point*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point)); 00260 points_length = points_lengthT; 00261 for( uint32_t i = 0; i < points_length; i++){ 00262 offset += this->st_points.deserialize(inbuffer + offset); 00263 memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point)); 00264 } 00265 uint32_t colors_lengthT = ((uint32_t) (*(inbuffer + offset))); 00266 colors_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00267 colors_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00268 colors_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00269 offset += sizeof(this->colors_length); 00270 if(colors_lengthT > colors_length) 00271 this->colors = (std_msgs::ColorRGBA*)realloc(this->colors, colors_lengthT * sizeof(std_msgs::ColorRGBA)); 00272 colors_length = colors_lengthT; 00273 for( uint32_t i = 0; i < colors_length; i++){ 00274 offset += this->st_colors.deserialize(inbuffer + offset); 00275 memcpy( &(this->colors[i]), &(this->st_colors), sizeof(std_msgs::ColorRGBA)); 00276 } 00277 uint32_t length_text; 00278 arrToVar(length_text, (inbuffer + offset)); 00279 offset += 4; 00280 for(unsigned int k= offset; k< offset+length_text; ++k){ 00281 inbuffer[k-1]=inbuffer[k]; 00282 } 00283 inbuffer[offset+length_text-1]=0; 00284 this->text = (char *)(inbuffer + offset-1); 00285 offset += length_text; 00286 uint32_t length_mesh_resource; 00287 arrToVar(length_mesh_resource, (inbuffer + offset)); 00288 offset += 4; 00289 for(unsigned int k= offset; k< offset+length_mesh_resource; ++k){ 00290 inbuffer[k-1]=inbuffer[k]; 00291 } 00292 inbuffer[offset+length_mesh_resource-1]=0; 00293 this->mesh_resource = (char *)(inbuffer + offset-1); 00294 offset += length_mesh_resource; 00295 union { 00296 bool real; 00297 uint8_t base; 00298 } u_mesh_use_embedded_materials; 00299 u_mesh_use_embedded_materials.base = 0; 00300 u_mesh_use_embedded_materials.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00301 this->mesh_use_embedded_materials = u_mesh_use_embedded_materials.real; 00302 offset += sizeof(this->mesh_use_embedded_materials); 00303 return offset; 00304 } 00305 00306 const char * getType(){ return "visualization_msgs/Marker"; }; 00307 const char * getMD5(){ return "4048c9de2a16f4ae8e0538085ebf1b97"; }; 00308 00309 }; 00310 00311 } 00312 #endif
Generated on Tue Jul 12 2022 18:49:19 by 1.7.2