Go to the documentation of this file.00001 #ifndef _ROS_actionlib_msgs_GoalStatus_h
00002 #define _ROS_actionlib_msgs_GoalStatus_h
00003
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "actionlib_msgs/GoalID.h"
00009
00010 namespace actionlib_msgs
00011 {
00012
00013 class GoalStatus : public ros::Msg
00014 {
00015 public:
00016 actionlib_msgs::GoalID goal_id;
00017 uint8_t status;
00018 const char* text;
00019 enum { PENDING = 0 };
00020 enum { ACTIVE = 1 };
00021 enum { PREEMPTED = 2 };
00022 enum { SUCCEEDED = 3 };
00023 enum { ABORTED = 4 };
00024 enum { REJECTED = 5 };
00025 enum { PREEMPTING = 6 };
00026 enum { RECALLING = 7 };
00027 enum { RECALLED = 8 };
00028 enum { LOST = 9 };
00029
00030 virtual int serialize(unsigned char *outbuffer) const
00031 {
00032 int offset = 0;
00033 offset += this->goal_id.serialize(outbuffer + offset);
00034 *(outbuffer + offset + 0) = (this->status >> (8 * 0)) & 0xFF;
00035 offset += sizeof(this->status);
00036 uint32_t length_text = strlen(this->text);
00037 memcpy(outbuffer + offset, &length_text, sizeof(uint32_t));
00038 offset += 4;
00039 memcpy(outbuffer + offset, this->text, length_text);
00040 offset += length_text;
00041 return offset;
00042 }
00043
00044 virtual int deserialize(unsigned char *inbuffer)
00045 {
00046 int offset = 0;
00047 offset += this->goal_id.deserialize(inbuffer + offset);
00048 this->status = ((uint8_t) (*(inbuffer + offset)));
00049 offset += sizeof(this->status);
00050 uint32_t length_text;
00051 memcpy(&length_text, (inbuffer + offset), sizeof(uint32_t));
00052 offset += 4;
00053 for(unsigned int k= offset; k< offset+length_text; ++k){
00054 inbuffer[k-1]=inbuffer[k];
00055 }
00056 inbuffer[offset+length_text-1]=0;
00057 this->text = (char *)(inbuffer + offset-1);
00058 offset += length_text;
00059 return offset;
00060 }
00061
00062 const char * getType(){ return "actionlib_msgs/GoalStatus"; };
00063 const char * getMD5(){ return "d388f9b87b3c471f784434d671988d4a"; };
00064
00065 };
00066
00067 }
00068 #endif