Go to the documentation of this file.00001 #ifndef _ROS_visualization_msgs_InteractiveMarkerFeedback_h
00002 #define _ROS_visualization_msgs_InteractiveMarkerFeedback_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/Point.h"
00011
00012 namespace visualization_msgs
00013 {
00014
00015 class InteractiveMarkerFeedback : public ros::Msg
00016 {
00017 public:
00018 std_msgs::Header header;
00019 char * client_id;
00020 char * marker_name;
00021 char * control_name;
00022 uint8_t event_type;
00023 geometry_msgs::Pose pose;
00024 uint32_t menu_entry_id;
00025 geometry_msgs::Point mouse_point;
00026 bool mouse_point_valid;
00027 enum { KEEP_ALIVE = 0 };
00028 enum { POSE_UPDATE = 1 };
00029 enum { MENU_SELECT = 2 };
00030 enum { BUTTON_CLICK = 3 };
00031 enum { MOUSE_DOWN = 4 };
00032 enum { MOUSE_UP = 5 };
00033
00034 virtual int serialize(unsigned char *outbuffer) const
00035 {
00036 int offset = 0;
00037 offset += this->header.serialize(outbuffer + offset);
00038 uint32_t length_client_id = strlen( (const char*) this->client_id);
00039 memcpy(outbuffer + offset, &length_client_id, sizeof(uint32_t));
00040 offset += 4;
00041 memcpy(outbuffer + offset, this->client_id, length_client_id);
00042 offset += length_client_id;
00043 uint32_t length_marker_name = strlen( (const char*) this->marker_name);
00044 memcpy(outbuffer + offset, &length_marker_name, sizeof(uint32_t));
00045 offset += 4;
00046 memcpy(outbuffer + offset, this->marker_name, length_marker_name);
00047 offset += length_marker_name;
00048 uint32_t length_control_name = strlen( (const char*) this->control_name);
00049 memcpy(outbuffer + offset, &length_control_name, sizeof(uint32_t));
00050 offset += 4;
00051 memcpy(outbuffer + offset, this->control_name, length_control_name);
00052 offset += length_control_name;
00053 *(outbuffer + offset + 0) = (this->event_type >> (8 * 0)) & 0xFF;
00054 offset += sizeof(this->event_type);
00055 offset += this->pose.serialize(outbuffer + offset);
00056 *(outbuffer + offset + 0) = (this->menu_entry_id >> (8 * 0)) & 0xFF;
00057 *(outbuffer + offset + 1) = (this->menu_entry_id >> (8 * 1)) & 0xFF;
00058 *(outbuffer + offset + 2) = (this->menu_entry_id >> (8 * 2)) & 0xFF;
00059 *(outbuffer + offset + 3) = (this->menu_entry_id >> (8 * 3)) & 0xFF;
00060 offset += sizeof(this->menu_entry_id);
00061 offset += this->mouse_point.serialize(outbuffer + offset);
00062 union {
00063 bool real;
00064 uint8_t base;
00065 } u_mouse_point_valid;
00066 u_mouse_point_valid.real = this->mouse_point_valid;
00067 *(outbuffer + offset + 0) = (u_mouse_point_valid.base >> (8 * 0)) & 0xFF;
00068 offset += sizeof(this->mouse_point_valid);
00069 return offset;
00070 }
00071
00072 virtual int deserialize(unsigned char *inbuffer)
00073 {
00074 int offset = 0;
00075 offset += this->header.deserialize(inbuffer + offset);
00076 uint32_t length_client_id;
00077 memcpy(&length_client_id, (inbuffer + offset), sizeof(uint32_t));
00078 offset += 4;
00079 for(unsigned int k= offset; k< offset+length_client_id; ++k){
00080 inbuffer[k-1]=inbuffer[k];
00081 }
00082 inbuffer[offset+length_client_id-1]=0;
00083 this->client_id = (char *)(inbuffer + offset-1);
00084 offset += length_client_id;
00085 uint32_t length_marker_name;
00086 memcpy(&length_marker_name, (inbuffer + offset), sizeof(uint32_t));
00087 offset += 4;
00088 for(unsigned int k= offset; k< offset+length_marker_name; ++k){
00089 inbuffer[k-1]=inbuffer[k];
00090 }
00091 inbuffer[offset+length_marker_name-1]=0;
00092 this->marker_name = (char *)(inbuffer + offset-1);
00093 offset += length_marker_name;
00094 uint32_t length_control_name;
00095 memcpy(&length_control_name, (inbuffer + offset), sizeof(uint32_t));
00096 offset += 4;
00097 for(unsigned int k= offset; k< offset+length_control_name; ++k){
00098 inbuffer[k-1]=inbuffer[k];
00099 }
00100 inbuffer[offset+length_control_name-1]=0;
00101 this->control_name = (char *)(inbuffer + offset-1);
00102 offset += length_control_name;
00103 this->event_type = ((uint8_t) (*(inbuffer + offset)));
00104 offset += sizeof(this->event_type);
00105 offset += this->pose.deserialize(inbuffer + offset);
00106 this->menu_entry_id = ((uint32_t) (*(inbuffer + offset)));
00107 this->menu_entry_id |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00108 this->menu_entry_id |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00109 this->menu_entry_id |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00110 offset += sizeof(this->menu_entry_id);
00111 offset += this->mouse_point.deserialize(inbuffer + offset);
00112 union {
00113 bool real;
00114 uint8_t base;
00115 } u_mouse_point_valid;
00116 u_mouse_point_valid.base = 0;
00117 u_mouse_point_valid.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00118 this->mouse_point_valid = u_mouse_point_valid.real;
00119 offset += sizeof(this->mouse_point_valid);
00120 return offset;
00121 }
00122
00123 const char * getType(){ return "visualization_msgs/InteractiveMarkerFeedback"; };
00124 const char * getMD5(){ return "ab0f1eee058667e28c19ff3ffc3f4b78"; };
00125
00126 };
00127
00128 }
00129 #endif