00001 #ifndef _ROS_SERVICE_GetRecoveryInfo_h 00002 #define _ROS_SERVICE_GetRecoveryInfo_h 00003 #include <stdint.h> 00004 #include <string.h> 00005 #include <stdlib.h> 00006 #include "ros/msg.h" 00007 #include "geometry_msgs/PoseStamped.h" 00008 #include "ros/time.h" 00009 #include "nav_msgs/Path.h" 00010 00011 namespace hector_nav_msgs 00012 { 00013 00014 static const char GETRECOVERYINFO[] = "hector_nav_msgs/GetRecoveryInfo"; 00015 00016 class GetRecoveryInfoRequest : public ros::Msg 00017 { 00018 public: 00019 ros::Time request_time; 00020 float request_radius; 00021 00022 virtual int serialize(unsigned char *outbuffer) const 00023 { 00024 int offset = 0; 00025 *(outbuffer + offset + 0) = (this->request_time.sec >> (8 * 0)) & 0xFF; 00026 *(outbuffer + offset + 1) = (this->request_time.sec >> (8 * 1)) & 0xFF; 00027 *(outbuffer + offset + 2) = (this->request_time.sec >> (8 * 2)) & 0xFF; 00028 *(outbuffer + offset + 3) = (this->request_time.sec >> (8 * 3)) & 0xFF; 00029 offset += sizeof(this->request_time.sec); 00030 *(outbuffer + offset + 0) = (this->request_time.nsec >> (8 * 0)) & 0xFF; 00031 *(outbuffer + offset + 1) = (this->request_time.nsec >> (8 * 1)) & 0xFF; 00032 *(outbuffer + offset + 2) = (this->request_time.nsec >> (8 * 2)) & 0xFF; 00033 *(outbuffer + offset + 3) = (this->request_time.nsec >> (8 * 3)) & 0xFF; 00034 offset += sizeof(this->request_time.nsec); 00035 int32_t * val_request_radius = (int32_t *) &(this->request_radius); 00036 int32_t exp_request_radius = (((*val_request_radius)>>23)&255); 00037 if(exp_request_radius != 0) 00038 exp_request_radius += 1023-127; 00039 int32_t sig_request_radius = *val_request_radius; 00040 *(outbuffer + offset++) = 0; 00041 *(outbuffer + offset++) = 0; 00042 *(outbuffer + offset++) = 0; 00043 *(outbuffer + offset++) = (sig_request_radius<<5) & 0xff; 00044 *(outbuffer + offset++) = (sig_request_radius>>3) & 0xff; 00045 *(outbuffer + offset++) = (sig_request_radius>>11) & 0xff; 00046 *(outbuffer + offset++) = ((exp_request_radius<<4) & 0xF0) | ((sig_request_radius>>19)&0x0F); 00047 *(outbuffer + offset++) = (exp_request_radius>>4) & 0x7F; 00048 if(this->request_radius < 0) *(outbuffer + offset -1) |= 0x80; 00049 return offset; 00050 } 00051 00052 virtual int deserialize(unsigned char *inbuffer) 00053 { 00054 int offset = 0; 00055 this->request_time.sec = ((uint32_t) (*(inbuffer + offset))); 00056 this->request_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00057 this->request_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00058 this->request_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00059 offset += sizeof(this->request_time.sec); 00060 this->request_time.nsec = ((uint32_t) (*(inbuffer + offset))); 00061 this->request_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00062 this->request_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00063 this->request_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00064 offset += sizeof(this->request_time.nsec); 00065 uint32_t * val_request_radius = (uint32_t*) &(this->request_radius); 00066 offset += 3; 00067 *val_request_radius = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07); 00068 *val_request_radius |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3; 00069 *val_request_radius |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11; 00070 *val_request_radius |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19; 00071 uint32_t exp_request_radius = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4; 00072 exp_request_radius |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4; 00073 if(exp_request_radius !=0) 00074 *val_request_radius |= ((exp_request_radius)-1023+127)<<23; 00075 if( ((*(inbuffer+offset++)) & 0x80) > 0) this->request_radius = -this->request_radius; 00076 return offset; 00077 } 00078 00079 const char * getType(){ return GETRECOVERYINFO; }; 00080 const char * getMD5(){ return "3916a0c55958d5dd43204cd2fe5608f6"; }; 00081 00082 }; 00083 00084 class GetRecoveryInfoResponse : public ros::Msg 00085 { 00086 public: 00087 nav_msgs::Path trajectory_radius_entry_pose_to_req_pose; 00088 geometry_msgs::PoseStamped radius_entry_pose; 00089 geometry_msgs::PoseStamped req_pose; 00090 00091 virtual int serialize(unsigned char *outbuffer) const 00092 { 00093 int offset = 0; 00094 offset += this->trajectory_radius_entry_pose_to_req_pose.serialize(outbuffer + offset); 00095 offset += this->radius_entry_pose.serialize(outbuffer + offset); 00096 offset += this->req_pose.serialize(outbuffer + offset); 00097 return offset; 00098 } 00099 00100 virtual int deserialize(unsigned char *inbuffer) 00101 { 00102 int offset = 0; 00103 offset += this->trajectory_radius_entry_pose_to_req_pose.deserialize(inbuffer + offset); 00104 offset += this->radius_entry_pose.deserialize(inbuffer + offset); 00105 offset += this->req_pose.deserialize(inbuffer + offset); 00106 return offset; 00107 } 00108 00109 const char * getType(){ return GETRECOVERYINFO; }; 00110 const char * getMD5(){ return "a93581be8e34e3c09aeafc6b9b990ad5"; }; 00111 00112 }; 00113 00114 class GetRecoveryInfo { 00115 public: 00116 typedef GetRecoveryInfoRequest Request; 00117 typedef GetRecoveryInfoResponse Response; 00118 }; 00119 00120 } 00121 #endif