Go to the documentation of this file.00001 #ifndef _ROS_smach_msgs_SmachContainerStatus_h
00002 #define _ROS_smach_msgs_SmachContainerStatus_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
00010 namespace smach_msgs
00011 {
00012
00013 class SmachContainerStatus : public ros::Msg
00014 {
00015 public:
00016 std_msgs::Header header;
00017 const char* path;
00018 uint8_t initial_states_length;
00019 char* st_initial_states;
00020 char* * initial_states;
00021 uint8_t active_states_length;
00022 char* st_active_states;
00023 char* * active_states;
00024 const char* local_data;
00025 const char* info;
00026
00027 virtual int serialize(unsigned char *outbuffer) const
00028 {
00029 int offset = 0;
00030 offset += this->header.serialize(outbuffer + offset);
00031 uint32_t length_path = strlen(this->path);
00032 memcpy(outbuffer + offset, &length_path, sizeof(uint32_t));
00033 offset += 4;
00034 memcpy(outbuffer + offset, this->path, length_path);
00035 offset += length_path;
00036 *(outbuffer + offset++) = initial_states_length;
00037 *(outbuffer + offset++) = 0;
00038 *(outbuffer + offset++) = 0;
00039 *(outbuffer + offset++) = 0;
00040 for( uint8_t i = 0; i < initial_states_length; i++){
00041 uint32_t length_initial_statesi = strlen(this->initial_states[i]);
00042 memcpy(outbuffer + offset, &length_initial_statesi, sizeof(uint32_t));
00043 offset += 4;
00044 memcpy(outbuffer + offset, this->initial_states[i], length_initial_statesi);
00045 offset += length_initial_statesi;
00046 }
00047 *(outbuffer + offset++) = active_states_length;
00048 *(outbuffer + offset++) = 0;
00049 *(outbuffer + offset++) = 0;
00050 *(outbuffer + offset++) = 0;
00051 for( uint8_t i = 0; i < active_states_length; i++){
00052 uint32_t length_active_statesi = strlen(this->active_states[i]);
00053 memcpy(outbuffer + offset, &length_active_statesi, sizeof(uint32_t));
00054 offset += 4;
00055 memcpy(outbuffer + offset, this->active_states[i], length_active_statesi);
00056 offset += length_active_statesi;
00057 }
00058 uint32_t length_local_data = strlen(this->local_data);
00059 memcpy(outbuffer + offset, &length_local_data, sizeof(uint32_t));
00060 offset += 4;
00061 memcpy(outbuffer + offset, this->local_data, length_local_data);
00062 offset += length_local_data;
00063 uint32_t length_info = strlen(this->info);
00064 memcpy(outbuffer + offset, &length_info, sizeof(uint32_t));
00065 offset += 4;
00066 memcpy(outbuffer + offset, this->info, length_info);
00067 offset += length_info;
00068 return offset;
00069 }
00070
00071 virtual int deserialize(unsigned char *inbuffer)
00072 {
00073 int offset = 0;
00074 offset += this->header.deserialize(inbuffer + offset);
00075 uint32_t length_path;
00076 memcpy(&length_path, (inbuffer + offset), sizeof(uint32_t));
00077 offset += 4;
00078 for(unsigned int k= offset; k< offset+length_path; ++k){
00079 inbuffer[k-1]=inbuffer[k];
00080 }
00081 inbuffer[offset+length_path-1]=0;
00082 this->path = (char *)(inbuffer + offset-1);
00083 offset += length_path;
00084 uint8_t initial_states_lengthT = *(inbuffer + offset++);
00085 if(initial_states_lengthT > initial_states_length)
00086 this->initial_states = (char**)realloc(this->initial_states, initial_states_lengthT * sizeof(char*));
00087 offset += 3;
00088 initial_states_length = initial_states_lengthT;
00089 for( uint8_t i = 0; i < initial_states_length; i++){
00090 uint32_t length_st_initial_states;
00091 memcpy(&length_st_initial_states, (inbuffer + offset), sizeof(uint32_t));
00092 offset += 4;
00093 for(unsigned int k= offset; k< offset+length_st_initial_states; ++k){
00094 inbuffer[k-1]=inbuffer[k];
00095 }
00096 inbuffer[offset+length_st_initial_states-1]=0;
00097 this->st_initial_states = (char *)(inbuffer + offset-1);
00098 offset += length_st_initial_states;
00099 memcpy( &(this->initial_states[i]), &(this->st_initial_states), sizeof(char*));
00100 }
00101 uint8_t active_states_lengthT = *(inbuffer + offset++);
00102 if(active_states_lengthT > active_states_length)
00103 this->active_states = (char**)realloc(this->active_states, active_states_lengthT * sizeof(char*));
00104 offset += 3;
00105 active_states_length = active_states_lengthT;
00106 for( uint8_t i = 0; i < active_states_length; i++){
00107 uint32_t length_st_active_states;
00108 memcpy(&length_st_active_states, (inbuffer + offset), sizeof(uint32_t));
00109 offset += 4;
00110 for(unsigned int k= offset; k< offset+length_st_active_states; ++k){
00111 inbuffer[k-1]=inbuffer[k];
00112 }
00113 inbuffer[offset+length_st_active_states-1]=0;
00114 this->st_active_states = (char *)(inbuffer + offset-1);
00115 offset += length_st_active_states;
00116 memcpy( &(this->active_states[i]), &(this->st_active_states), sizeof(char*));
00117 }
00118 uint32_t length_local_data;
00119 memcpy(&length_local_data, (inbuffer + offset), sizeof(uint32_t));
00120 offset += 4;
00121 for(unsigned int k= offset; k< offset+length_local_data; ++k){
00122 inbuffer[k-1]=inbuffer[k];
00123 }
00124 inbuffer[offset+length_local_data-1]=0;
00125 this->local_data = (char *)(inbuffer + offset-1);
00126 offset += length_local_data;
00127 uint32_t length_info;
00128 memcpy(&length_info, (inbuffer + offset), sizeof(uint32_t));
00129 offset += 4;
00130 for(unsigned int k= offset; k< offset+length_info; ++k){
00131 inbuffer[k-1]=inbuffer[k];
00132 }
00133 inbuffer[offset+length_info-1]=0;
00134 this->info = (char *)(inbuffer + offset-1);
00135 offset += length_info;
00136 return offset;
00137 }
00138
00139 const char * getType(){ return "smach_msgs/SmachContainerStatus"; };
00140 const char * getMD5(){ return "5ba2bb79ac19e3842d562a191f2a675b"; };
00141
00142 };
00143
00144 }
00145 #endif