Go to the documentation of this file.00001 #ifndef _ROS_SERVICE_GetPositionFK_h
00002 #define _ROS_SERVICE_GetPositionFK_h
00003 #include <stdint.h>
00004 #include <string.h>
00005 #include <stdlib.h>
00006 #include "ros/msg.h"
00007 #include "moveit_msgs/MoveItErrorCodes.h"
00008 #include "geometry_msgs/PoseStamped.h"
00009 #include "std_msgs/Header.h"
00010 #include "moveit_msgs/RobotState.h"
00011
00012 namespace moveit_msgs
00013 {
00014
00015 static const char GETPOSITIONFK[] = "moveit_msgs/GetPositionFK";
00016
00017 class GetPositionFKRequest : public ros::Msg
00018 {
00019 public:
00020 std_msgs::Header header;
00021 uint8_t fk_link_names_length;
00022 char* st_fk_link_names;
00023 char* * fk_link_names;
00024 moveit_msgs::RobotState robot_state;
00025
00026 virtual int serialize(unsigned char *outbuffer) const
00027 {
00028 int offset = 0;
00029 offset += this->header.serialize(outbuffer + offset);
00030 *(outbuffer + offset++) = fk_link_names_length;
00031 *(outbuffer + offset++) = 0;
00032 *(outbuffer + offset++) = 0;
00033 *(outbuffer + offset++) = 0;
00034 for( uint8_t i = 0; i < fk_link_names_length; i++){
00035 uint32_t length_fk_link_namesi = strlen(this->fk_link_names[i]);
00036 memcpy(outbuffer + offset, &length_fk_link_namesi, sizeof(uint32_t));
00037 offset += 4;
00038 memcpy(outbuffer + offset, this->fk_link_names[i], length_fk_link_namesi);
00039 offset += length_fk_link_namesi;
00040 }
00041 offset += this->robot_state.serialize(outbuffer + offset);
00042 return offset;
00043 }
00044
00045 virtual int deserialize(unsigned char *inbuffer)
00046 {
00047 int offset = 0;
00048 offset += this->header.deserialize(inbuffer + offset);
00049 uint8_t fk_link_names_lengthT = *(inbuffer + offset++);
00050 if(fk_link_names_lengthT > fk_link_names_length)
00051 this->fk_link_names = (char**)realloc(this->fk_link_names, fk_link_names_lengthT * sizeof(char*));
00052 offset += 3;
00053 fk_link_names_length = fk_link_names_lengthT;
00054 for( uint8_t i = 0; i < fk_link_names_length; i++){
00055 uint32_t length_st_fk_link_names;
00056 memcpy(&length_st_fk_link_names, (inbuffer + offset), sizeof(uint32_t));
00057 offset += 4;
00058 for(unsigned int k= offset; k< offset+length_st_fk_link_names; ++k){
00059 inbuffer[k-1]=inbuffer[k];
00060 }
00061 inbuffer[offset+length_st_fk_link_names-1]=0;
00062 this->st_fk_link_names = (char *)(inbuffer + offset-1);
00063 offset += length_st_fk_link_names;
00064 memcpy( &(this->fk_link_names[i]), &(this->st_fk_link_names), sizeof(char*));
00065 }
00066 offset += this->robot_state.deserialize(inbuffer + offset);
00067 return offset;
00068 }
00069
00070 const char * getType(){ return GETPOSITIONFK; };
00071 const char * getMD5(){ return "1d1ed72044ed56f6246c31b522781797"; };
00072
00073 };
00074
00075 class GetPositionFKResponse : public ros::Msg
00076 {
00077 public:
00078 uint8_t pose_stamped_length;
00079 geometry_msgs::PoseStamped st_pose_stamped;
00080 geometry_msgs::PoseStamped * pose_stamped;
00081 uint8_t fk_link_names_length;
00082 char* st_fk_link_names;
00083 char* * fk_link_names;
00084 moveit_msgs::MoveItErrorCodes error_code;
00085
00086 virtual int serialize(unsigned char *outbuffer) const
00087 {
00088 int offset = 0;
00089 *(outbuffer + offset++) = pose_stamped_length;
00090 *(outbuffer + offset++) = 0;
00091 *(outbuffer + offset++) = 0;
00092 *(outbuffer + offset++) = 0;
00093 for( uint8_t i = 0; i < pose_stamped_length; i++){
00094 offset += this->pose_stamped[i].serialize(outbuffer + offset);
00095 }
00096 *(outbuffer + offset++) = fk_link_names_length;
00097 *(outbuffer + offset++) = 0;
00098 *(outbuffer + offset++) = 0;
00099 *(outbuffer + offset++) = 0;
00100 for( uint8_t i = 0; i < fk_link_names_length; i++){
00101 uint32_t length_fk_link_namesi = strlen(this->fk_link_names[i]);
00102 memcpy(outbuffer + offset, &length_fk_link_namesi, sizeof(uint32_t));
00103 offset += 4;
00104 memcpy(outbuffer + offset, this->fk_link_names[i], length_fk_link_namesi);
00105 offset += length_fk_link_namesi;
00106 }
00107 offset += this->error_code.serialize(outbuffer + offset);
00108 return offset;
00109 }
00110
00111 virtual int deserialize(unsigned char *inbuffer)
00112 {
00113 int offset = 0;
00114 uint8_t pose_stamped_lengthT = *(inbuffer + offset++);
00115 if(pose_stamped_lengthT > pose_stamped_length)
00116 this->pose_stamped = (geometry_msgs::PoseStamped*)realloc(this->pose_stamped, pose_stamped_lengthT * sizeof(geometry_msgs::PoseStamped));
00117 offset += 3;
00118 pose_stamped_length = pose_stamped_lengthT;
00119 for( uint8_t i = 0; i < pose_stamped_length; i++){
00120 offset += this->st_pose_stamped.deserialize(inbuffer + offset);
00121 memcpy( &(this->pose_stamped[i]), &(this->st_pose_stamped), sizeof(geometry_msgs::PoseStamped));
00122 }
00123 uint8_t fk_link_names_lengthT = *(inbuffer + offset++);
00124 if(fk_link_names_lengthT > fk_link_names_length)
00125 this->fk_link_names = (char**)realloc(this->fk_link_names, fk_link_names_lengthT * sizeof(char*));
00126 offset += 3;
00127 fk_link_names_length = fk_link_names_lengthT;
00128 for( uint8_t i = 0; i < fk_link_names_length; i++){
00129 uint32_t length_st_fk_link_names;
00130 memcpy(&length_st_fk_link_names, (inbuffer + offset), sizeof(uint32_t));
00131 offset += 4;
00132 for(unsigned int k= offset; k< offset+length_st_fk_link_names; ++k){
00133 inbuffer[k-1]=inbuffer[k];
00134 }
00135 inbuffer[offset+length_st_fk_link_names-1]=0;
00136 this->st_fk_link_names = (char *)(inbuffer + offset-1);
00137 offset += length_st_fk_link_names;
00138 memcpy( &(this->fk_link_names[i]), &(this->st_fk_link_names), sizeof(char*));
00139 }
00140 offset += this->error_code.deserialize(inbuffer + offset);
00141 return offset;
00142 }
00143
00144 const char * getType(){ return GETPOSITIONFK; };
00145 const char * getMD5(){ return "297215cf4fdfe0008356995ae621dae6"; };
00146
00147 };
00148
00149 class GetPositionFK {
00150 public:
00151 typedef GetPositionFKRequest Request;
00152 typedef GetPositionFKResponse Response;
00153 };
00154
00155 }
00156 #endif