Go to the documentation of this file.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 const char* name;
00018 geometry_msgs::Quaternion orientation;
00019 uint8_t orientation_mode;
00020 uint8_t interaction_mode;
00021 bool always_visible;
00022 uint8_t markers_length;
00023 visualization_msgs::Marker st_markers;
00024 visualization_msgs::Marker * markers;
00025 bool independent_marker_orientation;
00026 const char* description;
00027 enum { INHERIT = 0 };
00028 enum { FIXED = 1 };
00029 enum { VIEW_FACING = 2 };
00030 enum { NONE = 0 };
00031 enum { MENU = 1 };
00032 enum { BUTTON = 2 };
00033 enum { MOVE_AXIS = 3 };
00034 enum { MOVE_PLANE = 4 };
00035 enum { ROTATE_AXIS = 5 };
00036 enum { MOVE_ROTATE = 6 };
00037 enum { MOVE_3D = 7 };
00038 enum { ROTATE_3D = 8 };
00039 enum { MOVE_ROTATE_3D = 9 };
00040
00041 virtual int serialize(unsigned char *outbuffer) const
00042 {
00043 int offset = 0;
00044 uint32_t length_name = strlen(this->name);
00045 memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
00046 offset += 4;
00047 memcpy(outbuffer + offset, this->name, length_name);
00048 offset += length_name;
00049 offset += this->orientation.serialize(outbuffer + offset);
00050 *(outbuffer + offset + 0) = (this->orientation_mode >> (8 * 0)) & 0xFF;
00051 offset += sizeof(this->orientation_mode);
00052 *(outbuffer + offset + 0) = (this->interaction_mode >> (8 * 0)) & 0xFF;
00053 offset += sizeof(this->interaction_mode);
00054 union {
00055 bool real;
00056 uint8_t base;
00057 } u_always_visible;
00058 u_always_visible.real = this->always_visible;
00059 *(outbuffer + offset + 0) = (u_always_visible.base >> (8 * 0)) & 0xFF;
00060 offset += sizeof(this->always_visible);
00061 *(outbuffer + offset++) = markers_length;
00062 *(outbuffer + offset++) = 0;
00063 *(outbuffer + offset++) = 0;
00064 *(outbuffer + offset++) = 0;
00065 for( uint8_t i = 0; i < markers_length; i++){
00066 offset += this->markers[i].serialize(outbuffer + offset);
00067 }
00068 union {
00069 bool real;
00070 uint8_t base;
00071 } u_independent_marker_orientation;
00072 u_independent_marker_orientation.real = this->independent_marker_orientation;
00073 *(outbuffer + offset + 0) = (u_independent_marker_orientation.base >> (8 * 0)) & 0xFF;
00074 offset += sizeof(this->independent_marker_orientation);
00075 uint32_t length_description = strlen(this->description);
00076 memcpy(outbuffer + offset, &length_description, sizeof(uint32_t));
00077 offset += 4;
00078 memcpy(outbuffer + offset, this->description, length_description);
00079 offset += length_description;
00080 return offset;
00081 }
00082
00083 virtual int deserialize(unsigned char *inbuffer)
00084 {
00085 int offset = 0;
00086 uint32_t length_name;
00087 memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
00088 offset += 4;
00089 for(unsigned int k= offset; k< offset+length_name; ++k){
00090 inbuffer[k-1]=inbuffer[k];
00091 }
00092 inbuffer[offset+length_name-1]=0;
00093 this->name = (char *)(inbuffer + offset-1);
00094 offset += length_name;
00095 offset += this->orientation.deserialize(inbuffer + offset);
00096 this->orientation_mode = ((uint8_t) (*(inbuffer + offset)));
00097 offset += sizeof(this->orientation_mode);
00098 this->interaction_mode = ((uint8_t) (*(inbuffer + offset)));
00099 offset += sizeof(this->interaction_mode);
00100 union {
00101 bool real;
00102 uint8_t base;
00103 } u_always_visible;
00104 u_always_visible.base = 0;
00105 u_always_visible.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00106 this->always_visible = u_always_visible.real;
00107 offset += sizeof(this->always_visible);
00108 uint8_t markers_lengthT = *(inbuffer + offset++);
00109 if(markers_lengthT > markers_length)
00110 this->markers = (visualization_msgs::Marker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::Marker));
00111 offset += 3;
00112 markers_length = markers_lengthT;
00113 for( uint8_t i = 0; i < markers_length; i++){
00114 offset += this->st_markers.deserialize(inbuffer + offset);
00115 memcpy( &(this->markers[i]), &(this->st_markers), sizeof(visualization_msgs::Marker));
00116 }
00117 union {
00118 bool real;
00119 uint8_t base;
00120 } u_independent_marker_orientation;
00121 u_independent_marker_orientation.base = 0;
00122 u_independent_marker_orientation.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00123 this->independent_marker_orientation = u_independent_marker_orientation.real;
00124 offset += sizeof(this->independent_marker_orientation);
00125 uint32_t length_description;
00126 memcpy(&length_description, (inbuffer + offset), sizeof(uint32_t));
00127 offset += 4;
00128 for(unsigned int k= offset; k< offset+length_description; ++k){
00129 inbuffer[k-1]=inbuffer[k];
00130 }
00131 inbuffer[offset+length_description-1]=0;
00132 this->description = (char *)(inbuffer + offset-1);
00133 offset += length_description;
00134 return offset;
00135 }
00136
00137 const char * getType(){ return "visualization_msgs/InteractiveMarkerControl"; };
00138 const char * getMD5(){ return "e3a939c98cdd4f709d8e1dec2a9c3f37"; };
00139
00140 };
00141
00142 }
00143 #endif