ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information
Dependents: rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more
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 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 InteractiveMarkerControl(): 00042 name(""), 00043 orientation(), 00044 orientation_mode(0), 00045 interaction_mode(0), 00046 always_visible(0), 00047 markers_length(0), markers(NULL), 00048 independent_marker_orientation(0), 00049 description("") 00050 { 00051 } 00052 00053 virtual int serialize(unsigned char *outbuffer) const 00054 { 00055 int offset = 0; 00056 uint32_t length_name = strlen(this->name); 00057 memcpy(outbuffer + offset, &length_name, sizeof(uint32_t)); 00058 offset += 4; 00059 memcpy(outbuffer + offset, this->name, length_name); 00060 offset += length_name; 00061 offset += this->orientation.serialize(outbuffer + offset); 00062 *(outbuffer + offset + 0) = (this->orientation_mode >> (8 * 0)) & 0xFF; 00063 offset += sizeof(this->orientation_mode); 00064 *(outbuffer + offset + 0) = (this->interaction_mode >> (8 * 0)) & 0xFF; 00065 offset += sizeof(this->interaction_mode); 00066 union { 00067 bool real; 00068 uint8_t base; 00069 } u_always_visible; 00070 u_always_visible.real = this->always_visible; 00071 *(outbuffer + offset + 0) = (u_always_visible.base >> (8 * 0)) & 0xFF; 00072 offset += sizeof(this->always_visible); 00073 *(outbuffer + offset++) = markers_length; 00074 *(outbuffer + offset++) = 0; 00075 *(outbuffer + offset++) = 0; 00076 *(outbuffer + offset++) = 0; 00077 for( uint8_t i = 0; i < markers_length; i++){ 00078 offset += this->markers[i].serialize(outbuffer + offset); 00079 } 00080 union { 00081 bool real; 00082 uint8_t base; 00083 } u_independent_marker_orientation; 00084 u_independent_marker_orientation.real = this->independent_marker_orientation; 00085 *(outbuffer + offset + 0) = (u_independent_marker_orientation.base >> (8 * 0)) & 0xFF; 00086 offset += sizeof(this->independent_marker_orientation); 00087 uint32_t length_description = strlen(this->description); 00088 memcpy(outbuffer + offset, &length_description, sizeof(uint32_t)); 00089 offset += 4; 00090 memcpy(outbuffer + offset, this->description, length_description); 00091 offset += length_description; 00092 return offset; 00093 } 00094 00095 virtual int deserialize(unsigned char *inbuffer) 00096 { 00097 int offset = 0; 00098 uint32_t length_name; 00099 memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t)); 00100 offset += 4; 00101 for(unsigned int k= offset; k< offset+length_name; ++k){ 00102 inbuffer[k-1]=inbuffer[k]; 00103 } 00104 inbuffer[offset+length_name-1]=0; 00105 this->name = (char *)(inbuffer + offset-1); 00106 offset += length_name; 00107 offset += this->orientation.deserialize(inbuffer + offset); 00108 this->orientation_mode = ((uint8_t) (*(inbuffer + offset))); 00109 offset += sizeof(this->orientation_mode); 00110 this->interaction_mode = ((uint8_t) (*(inbuffer + offset))); 00111 offset += sizeof(this->interaction_mode); 00112 union { 00113 bool real; 00114 uint8_t base; 00115 } u_always_visible; 00116 u_always_visible.base = 0; 00117 u_always_visible.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00118 this->always_visible = u_always_visible.real; 00119 offset += sizeof(this->always_visible); 00120 uint8_t markers_lengthT = *(inbuffer + offset++); 00121 if(markers_lengthT > markers_length) 00122 this->markers = (visualization_msgs::Marker*)realloc(this->markers, markers_lengthT * sizeof(visualization_msgs::Marker)); 00123 offset += 3; 00124 markers_length = markers_lengthT; 00125 for( uint8_t i = 0; i < markers_length; i++){ 00126 offset += this->st_markers.deserialize(inbuffer + offset); 00127 memcpy( &(this->markers[i]), &(this->st_markers), sizeof(visualization_msgs::Marker)); 00128 } 00129 union { 00130 bool real; 00131 uint8_t base; 00132 } u_independent_marker_orientation; 00133 u_independent_marker_orientation.base = 0; 00134 u_independent_marker_orientation.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00135 this->independent_marker_orientation = u_independent_marker_orientation.real; 00136 offset += sizeof(this->independent_marker_orientation); 00137 uint32_t length_description; 00138 memcpy(&length_description, (inbuffer + offset), sizeof(uint32_t)); 00139 offset += 4; 00140 for(unsigned int k= offset; k< offset+length_description; ++k){ 00141 inbuffer[k-1]=inbuffer[k]; 00142 } 00143 inbuffer[offset+length_description-1]=0; 00144 this->description = (char *)(inbuffer + offset-1); 00145 offset += length_description; 00146 return offset; 00147 } 00148 00149 const char * getType(){ return "visualization_msgs/InteractiveMarkerControl"; }; 00150 const char * getMD5(){ return "e3a939c98cdd4f709d8e1dec2a9c3f37"; }; 00151 00152 }; 00153 00154 } 00155 #endif
Generated on Tue Jul 12 2022 18:39:39 by 1.7.2