Go to the documentation of this file.00001 #ifndef _ROS_SERVICE_GetModelState_h
00002 #define _ROS_SERVICE_GetModelState_h
00003 #include <stdint.h>
00004 #include <string.h>
00005 #include <stdlib.h>
00006 #include "ros/msg.h"
00007 #include "geometry_msgs/Pose.h"
00008 #include "geometry_msgs/Twist.h"
00009
00010 namespace gazebo_msgs
00011 {
00012
00013 static const char GETMODELSTATE[] = "gazebo_msgs/GetModelState";
00014
00015 class GetModelStateRequest : public ros::Msg
00016 {
00017 public:
00018 const char* model_name;
00019 const char* relative_entity_name;
00020
00021 virtual int serialize(unsigned char *outbuffer) const
00022 {
00023 int offset = 0;
00024 uint32_t length_model_name = strlen(this->model_name);
00025 memcpy(outbuffer + offset, &length_model_name, sizeof(uint32_t));
00026 offset += 4;
00027 memcpy(outbuffer + offset, this->model_name, length_model_name);
00028 offset += length_model_name;
00029 uint32_t length_relative_entity_name = strlen(this->relative_entity_name);
00030 memcpy(outbuffer + offset, &length_relative_entity_name, sizeof(uint32_t));
00031 offset += 4;
00032 memcpy(outbuffer + offset, this->relative_entity_name, length_relative_entity_name);
00033 offset += length_relative_entity_name;
00034 return offset;
00035 }
00036
00037 virtual int deserialize(unsigned char *inbuffer)
00038 {
00039 int offset = 0;
00040 uint32_t length_model_name;
00041 memcpy(&length_model_name, (inbuffer + offset), sizeof(uint32_t));
00042 offset += 4;
00043 for(unsigned int k= offset; k< offset+length_model_name; ++k){
00044 inbuffer[k-1]=inbuffer[k];
00045 }
00046 inbuffer[offset+length_model_name-1]=0;
00047 this->model_name = (char *)(inbuffer + offset-1);
00048 offset += length_model_name;
00049 uint32_t length_relative_entity_name;
00050 memcpy(&length_relative_entity_name, (inbuffer + offset), sizeof(uint32_t));
00051 offset += 4;
00052 for(unsigned int k= offset; k< offset+length_relative_entity_name; ++k){
00053 inbuffer[k-1]=inbuffer[k];
00054 }
00055 inbuffer[offset+length_relative_entity_name-1]=0;
00056 this->relative_entity_name = (char *)(inbuffer + offset-1);
00057 offset += length_relative_entity_name;
00058 return offset;
00059 }
00060
00061 const char * getType(){ return GETMODELSTATE; };
00062 const char * getMD5(){ return "19d412713cefe4a67437e17a951e759e"; };
00063
00064 };
00065
00066 class GetModelStateResponse : public ros::Msg
00067 {
00068 public:
00069 geometry_msgs::Pose pose;
00070 geometry_msgs::Twist twist;
00071 bool success;
00072 const char* status_message;
00073
00074 virtual int serialize(unsigned char *outbuffer) const
00075 {
00076 int offset = 0;
00077 offset += this->pose.serialize(outbuffer + offset);
00078 offset += this->twist.serialize(outbuffer + offset);
00079 union {
00080 bool real;
00081 uint8_t base;
00082 } u_success;
00083 u_success.real = this->success;
00084 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
00085 offset += sizeof(this->success);
00086 uint32_t length_status_message = strlen(this->status_message);
00087 memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
00088 offset += 4;
00089 memcpy(outbuffer + offset, this->status_message, length_status_message);
00090 offset += length_status_message;
00091 return offset;
00092 }
00093
00094 virtual int deserialize(unsigned char *inbuffer)
00095 {
00096 int offset = 0;
00097 offset += this->pose.deserialize(inbuffer + offset);
00098 offset += this->twist.deserialize(inbuffer + offset);
00099 union {
00100 bool real;
00101 uint8_t base;
00102 } u_success;
00103 u_success.base = 0;
00104 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00105 this->success = u_success.real;
00106 offset += sizeof(this->success);
00107 uint32_t length_status_message;
00108 memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
00109 offset += 4;
00110 for(unsigned int k= offset; k< offset+length_status_message; ++k){
00111 inbuffer[k-1]=inbuffer[k];
00112 }
00113 inbuffer[offset+length_status_message-1]=0;
00114 this->status_message = (char *)(inbuffer + offset-1);
00115 offset += length_status_message;
00116 return offset;
00117 }
00118
00119 const char * getType(){ return GETMODELSTATE; };
00120 const char * getMD5(){ return "1f8f991dc94e0cb27fe61383e0f576bb"; };
00121
00122 };
00123
00124 class GetModelState {
00125 public:
00126 typedef GetModelStateRequest Request;
00127 typedef GetModelStateResponse Response;
00128 };
00129
00130 }
00131 #endif