Go to the documentation of this file.00001 #ifndef _ROS_moveit_msgs_PickupResult_h
00002 #define _ROS_moveit_msgs_PickupResult_h
00003
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "moveit_msgs/MoveItErrorCodes.h"
00009 #include "moveit_msgs/RobotState.h"
00010 #include "moveit_msgs/RobotTrajectory.h"
00011 #include "moveit_msgs/Grasp.h"
00012
00013 namespace moveit_msgs
00014 {
00015
00016 class PickupResult : public ros::Msg
00017 {
00018 public:
00019 moveit_msgs::MoveItErrorCodes error_code;
00020 moveit_msgs::RobotState trajectory_start;
00021 uint8_t trajectory_stages_length;
00022 moveit_msgs::RobotTrajectory st_trajectory_stages;
00023 moveit_msgs::RobotTrajectory * trajectory_stages;
00024 uint8_t trajectory_descriptions_length;
00025 char* st_trajectory_descriptions;
00026 char* * trajectory_descriptions;
00027 moveit_msgs::Grasp grasp;
00028
00029 virtual int serialize(unsigned char *outbuffer) const
00030 {
00031 int offset = 0;
00032 offset += this->error_code.serialize(outbuffer + offset);
00033 offset += this->trajectory_start.serialize(outbuffer + offset);
00034 *(outbuffer + offset++) = trajectory_stages_length;
00035 *(outbuffer + offset++) = 0;
00036 *(outbuffer + offset++) = 0;
00037 *(outbuffer + offset++) = 0;
00038 for( uint8_t i = 0; i < trajectory_stages_length; i++){
00039 offset += this->trajectory_stages[i].serialize(outbuffer + offset);
00040 }
00041 *(outbuffer + offset++) = trajectory_descriptions_length;
00042 *(outbuffer + offset++) = 0;
00043 *(outbuffer + offset++) = 0;
00044 *(outbuffer + offset++) = 0;
00045 for( uint8_t i = 0; i < trajectory_descriptions_length; i++){
00046 uint32_t length_trajectory_descriptionsi = strlen(this->trajectory_descriptions[i]);
00047 memcpy(outbuffer + offset, &length_trajectory_descriptionsi, sizeof(uint32_t));
00048 offset += 4;
00049 memcpy(outbuffer + offset, this->trajectory_descriptions[i], length_trajectory_descriptionsi);
00050 offset += length_trajectory_descriptionsi;
00051 }
00052 offset += this->grasp.serialize(outbuffer + offset);
00053 return offset;
00054 }
00055
00056 virtual int deserialize(unsigned char *inbuffer)
00057 {
00058 int offset = 0;
00059 offset += this->error_code.deserialize(inbuffer + offset);
00060 offset += this->trajectory_start.deserialize(inbuffer + offset);
00061 uint8_t trajectory_stages_lengthT = *(inbuffer + offset++);
00062 if(trajectory_stages_lengthT > trajectory_stages_length)
00063 this->trajectory_stages = (moveit_msgs::RobotTrajectory*)realloc(this->trajectory_stages, trajectory_stages_lengthT * sizeof(moveit_msgs::RobotTrajectory));
00064 offset += 3;
00065 trajectory_stages_length = trajectory_stages_lengthT;
00066 for( uint8_t i = 0; i < trajectory_stages_length; i++){
00067 offset += this->st_trajectory_stages.deserialize(inbuffer + offset);
00068 memcpy( &(this->trajectory_stages[i]), &(this->st_trajectory_stages), sizeof(moveit_msgs::RobotTrajectory));
00069 }
00070 uint8_t trajectory_descriptions_lengthT = *(inbuffer + offset++);
00071 if(trajectory_descriptions_lengthT > trajectory_descriptions_length)
00072 this->trajectory_descriptions = (char**)realloc(this->trajectory_descriptions, trajectory_descriptions_lengthT * sizeof(char*));
00073 offset += 3;
00074 trajectory_descriptions_length = trajectory_descriptions_lengthT;
00075 for( uint8_t i = 0; i < trajectory_descriptions_length; i++){
00076 uint32_t length_st_trajectory_descriptions;
00077 memcpy(&length_st_trajectory_descriptions, (inbuffer + offset), sizeof(uint32_t));
00078 offset += 4;
00079 for(unsigned int k= offset; k< offset+length_st_trajectory_descriptions; ++k){
00080 inbuffer[k-1]=inbuffer[k];
00081 }
00082 inbuffer[offset+length_st_trajectory_descriptions-1]=0;
00083 this->st_trajectory_descriptions = (char *)(inbuffer + offset-1);
00084 offset += length_st_trajectory_descriptions;
00085 memcpy( &(this->trajectory_descriptions[i]), &(this->st_trajectory_descriptions), sizeof(char*));
00086 }
00087 offset += this->grasp.deserialize(inbuffer + offset);
00088 return offset;
00089 }
00090
00091 const char * getType(){ return "moveit_msgs/PickupResult"; };
00092 const char * getMD5(){ return "23c6d8bf0580f4bc8f7a8e1f59b4b6b7"; };
00093
00094 };
00095
00096 }
00097 #endif