Working towards recieving twists

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers InteractiveMarkerControl.h Source File

InteractiveMarkerControl.h

00001 #ifndef _ROS_visualization_msgs_InteractiveMarkerControl_h
00002 #define _ROS_visualization_msgs_InteractiveMarkerControl_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "geometry_msgs/Quaternion.h"
00009 #include "visualization_msgs/Marker.h"
00010 
00011 namespace visualization_msgs
00012 {
00013 
00014   class InteractiveMarkerControl : public ros::Msg
00015   {
00016     public:
00017       typedef const char* _name_type;
00018       _name_type name;
00019       typedef geometry_msgs::Quaternion _orientation_type;
00020       _orientation_type orientation;
00021       typedef uint8_t _orientation_mode_type;
00022       _orientation_mode_type orientation_mode;
00023       typedef uint8_t _interaction_mode_type;
00024       _interaction_mode_type interaction_mode;
00025       typedef bool _always_visible_type;
00026       _always_visible_type always_visible;
00027       uint32_t markers_length;
00028       typedef visualization_msgs::Marker _markers_type;
00029       _markers_type st_markers;
00030       _markers_type * markers;
00031       typedef bool _independent_marker_orientation_type;
00032       _independent_marker_orientation_type independent_marker_orientation;
00033       typedef const char* _description_type;
00034       _description_type description;
00035       enum { INHERIT =  0 };
00036       enum { FIXED =  1 };
00037       enum { VIEW_FACING =  2 };
00038       enum { NONE =  0 };
00039       enum { MENU =  1 };
00040       enum { BUTTON =  2 };
00041       enum { MOVE_AXIS =  3 };
00042       enum { MOVE_PLANE =  4 };
00043       enum { ROTATE_AXIS =  5 };
00044       enum { MOVE_ROTATE =  6 };
00045       enum { MOVE_3D =  7 };
00046       enum { ROTATE_3D =  8 };
00047       enum { MOVE_ROTATE_3D =  9 };
00048 
00049     InteractiveMarkerControl():
00050       name(""),
00051       orientation(),
00052       orientation_mode(0),
00053       interaction_mode(0),
00054       always_visible(0),
00055       markers_length(0), markers(NULL),
00056       independent_marker_orientation(0),
00057       description("")
00058     {
00059     }
00060 
00061     virtual int serialize(unsigned char *outbuffer) const
00062     {
00063       int offset = 0;
00064       uint32_t length_name = strlen(this->name);
00065       varToArr(outbuffer + offset, length_name);
00066       offset += 4;
00067       memcpy(outbuffer + offset, this->name, length_name);
00068       offset += length_name;
00069       offset += this->orientation.serialize(outbuffer + offset);
00070       *(outbuffer + offset + 0) = (this->orientation_mode >> (8 * 0)) & 0xFF;
00071       offset += sizeof(this->orientation_mode);
00072       *(outbuffer + offset + 0) = (this->interaction_mode >> (8 * 0)) & 0xFF;
00073       offset += sizeof(this->interaction_mode);
00074       union {
00075         bool real;
00076         uint8_t base;
00077       } u_always_visible;
00078       u_always_visible.real = this->always_visible;
00079       *(outbuffer + offset + 0) = (u_always_visible.base >> (8 * 0)) & 0xFF;
00080       offset += sizeof(this->always_visible);
00081       *(outbuffer + offset + 0) = (this->markers_length >> (8 * 0)) & 0xFF;
00082       *(outbuffer + offset + 1) = (this->markers_length >> (8 * 1)) & 0xFF;
00083       *(outbuffer + offset + 2) = (this->markers_length >> (8 * 2)) & 0xFF;
00084       *(outbuffer + offset + 3) = (this->markers_length >> (8 * 3)) & 0xFF;
00085       offset += sizeof(this->markers_length);
00086       for( uint32_t i = 0; i < markers_length; i++){
00087       offset += this->markers[i].serialize(outbuffer + offset);
00088       }
00089       union {
00090         bool real;
00091         uint8_t base;
00092       } u_independent_marker_orientation;
00093       u_independent_marker_orientation.real = this->independent_marker_orientation;
00094       *(outbuffer + offset + 0) = (u_independent_marker_orientation.base >> (8 * 0)) & 0xFF;
00095       offset += sizeof(this->independent_marker_orientation);
00096       uint32_t length_description = strlen(this->description);
00097       varToArr(outbuffer + offset, length_description);
00098       offset += 4;
00099       memcpy(outbuffer + offset, this->description, length_description);
00100       offset += length_description;
00101       return offset;
00102     }
00103 
00104     virtual int deserialize(unsigned char *inbuffer)
00105     {
00106       int offset = 0;
00107       uint32_t length_name;
00108       arrToVar(length_name, (inbuffer + offset));
00109       offset += 4;
00110       for(unsigned int k= offset; k< offset+length_name; ++k){
00111           inbuffer[k-1]=inbuffer[k];
00112       }
00113       inbuffer[offset+length_name-1]=0;
00114       this->name = (char *)(inbuffer + offset-1);
00115       offset += length_name;
00116       offset += this->orientation.deserialize(inbuffer + offset);
00117       this->orientation_mode =  ((uint8_t) (*(inbuffer + offset)));
00118       offset += sizeof(this->orientation_mode);
00119       this->interaction_mode =  ((uint8_t) (*(inbuffer + offset)));
00120       offset += sizeof(this->interaction_mode);
00121       union {
00122         bool real;
00123         uint8_t base;
00124       } u_always_visible;
00125       u_always_visible.base = 0;
00126       u_always_visible.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00127       this->always_visible = u_always_visible.real;
00128       offset += sizeof(this->always_visible);
00129       uint32_t markers_lengthT = ((uint32_t) (*(inbuffer + offset))); 
00130       markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 
00131       markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 
00132       markers_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 
00133       offset += sizeof(this->markers_length);
00134       if(markers_lengthT > markers_length)
00135         this->markers = (visualization_msgs::Marker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::Marker));
00136       markers_length = markers_lengthT;
00137       for( uint32_t i = 0; i < markers_length; i++){
00138       offset += this->st_markers.deserialize(inbuffer + offset);
00139         memcpy( &(this->markers[i]), &(this->st_markers), sizeof(visualization_msgs::Marker));
00140       }
00141       union {
00142         bool real;
00143         uint8_t base;
00144       } u_independent_marker_orientation;
00145       u_independent_marker_orientation.base = 0;
00146       u_independent_marker_orientation.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00147       this->independent_marker_orientation = u_independent_marker_orientation.real;
00148       offset += sizeof(this->independent_marker_orientation);
00149       uint32_t length_description;
00150       arrToVar(length_description, (inbuffer + offset));
00151       offset += 4;
00152       for(unsigned int k= offset; k< offset+length_description; ++k){
00153           inbuffer[k-1]=inbuffer[k];
00154       }
00155       inbuffer[offset+length_description-1]=0;
00156       this->description = (char *)(inbuffer + offset-1);
00157       offset += length_description;
00158      return offset;
00159     }
00160 
00161     const char * getType(){ return "visualization_msgs/InteractiveMarkerControl"; };
00162     const char * getMD5(){ return "b3c81e785788195d1840b86c28da1aac"; };
00163 
00164   };
00165 
00166 }
00167 #endif