PositionIKRequest.h
Go to the documentation of this file.
00001 #ifndef _ROS_moveit_msgs_PositionIKRequest_h
00002 #define _ROS_moveit_msgs_PositionIKRequest_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "moveit_msgs/RobotState.h"
00009 #include "moveit_msgs/Constraints.h"
00010 #include "geometry_msgs/PoseStamped.h"
00011 #include "ros/duration.h"
00012 
00013 namespace moveit_msgs
00014 {
00015 
00016   class PositionIKRequest : public ros::Msg
00017   {
00018     public:
00019       const char* group_name;
00020       moveit_msgs::RobotState robot_state;
00021       moveit_msgs::Constraints constraints;
00022       bool avoid_collisions;
00023       const char* ik_link_name;
00024       geometry_msgs::PoseStamped pose_stamped;
00025       uint8_t ik_link_names_length;
00026       char* st_ik_link_names;
00027       char* * ik_link_names;
00028       uint8_t pose_stamped_vector_length;
00029       geometry_msgs::PoseStamped st_pose_stamped_vector;
00030       geometry_msgs::PoseStamped * pose_stamped_vector;
00031       ros::Duration timeout;
00032       int32_t attempts;
00033 
00034     virtual int serialize(unsigned char *outbuffer) const
00035     {
00036       int offset = 0;
00037       uint32_t length_group_name = strlen(this->group_name);
00038       memcpy(outbuffer + offset, &length_group_name, sizeof(uint32_t));
00039       offset += 4;
00040       memcpy(outbuffer + offset, this->group_name, length_group_name);
00041       offset += length_group_name;
00042       offset += this->robot_state.serialize(outbuffer + offset);
00043       offset += this->constraints.serialize(outbuffer + offset);
00044       union {
00045         bool real;
00046         uint8_t base;
00047       } u_avoid_collisions;
00048       u_avoid_collisions.real = this->avoid_collisions;
00049       *(outbuffer + offset + 0) = (u_avoid_collisions.base >> (8 * 0)) & 0xFF;
00050       offset += sizeof(this->avoid_collisions);
00051       uint32_t length_ik_link_name = strlen(this->ik_link_name);
00052       memcpy(outbuffer + offset, &length_ik_link_name, sizeof(uint32_t));
00053       offset += 4;
00054       memcpy(outbuffer + offset, this->ik_link_name, length_ik_link_name);
00055       offset += length_ik_link_name;
00056       offset += this->pose_stamped.serialize(outbuffer + offset);
00057       *(outbuffer + offset++) = ik_link_names_length;
00058       *(outbuffer + offset++) = 0;
00059       *(outbuffer + offset++) = 0;
00060       *(outbuffer + offset++) = 0;
00061       for( uint8_t i = 0; i < ik_link_names_length; i++){
00062       uint32_t length_ik_link_namesi = strlen(this->ik_link_names[i]);
00063       memcpy(outbuffer + offset, &length_ik_link_namesi, sizeof(uint32_t));
00064       offset += 4;
00065       memcpy(outbuffer + offset, this->ik_link_names[i], length_ik_link_namesi);
00066       offset += length_ik_link_namesi;
00067       }
00068       *(outbuffer + offset++) = pose_stamped_vector_length;
00069       *(outbuffer + offset++) = 0;
00070       *(outbuffer + offset++) = 0;
00071       *(outbuffer + offset++) = 0;
00072       for( uint8_t i = 0; i < pose_stamped_vector_length; i++){
00073       offset += this->pose_stamped_vector[i].serialize(outbuffer + offset);
00074       }
00075       *(outbuffer + offset + 0) = (this->timeout.sec >> (8 * 0)) & 0xFF;
00076       *(outbuffer + offset + 1) = (this->timeout.sec >> (8 * 1)) & 0xFF;
00077       *(outbuffer + offset + 2) = (this->timeout.sec >> (8 * 2)) & 0xFF;
00078       *(outbuffer + offset + 3) = (this->timeout.sec >> (8 * 3)) & 0xFF;
00079       offset += sizeof(this->timeout.sec);
00080       *(outbuffer + offset + 0) = (this->timeout.nsec >> (8 * 0)) & 0xFF;
00081       *(outbuffer + offset + 1) = (this->timeout.nsec >> (8 * 1)) & 0xFF;
00082       *(outbuffer + offset + 2) = (this->timeout.nsec >> (8 * 2)) & 0xFF;
00083       *(outbuffer + offset + 3) = (this->timeout.nsec >> (8 * 3)) & 0xFF;
00084       offset += sizeof(this->timeout.nsec);
00085       union {
00086         int32_t real;
00087         uint32_t base;
00088       } u_attempts;
00089       u_attempts.real = this->attempts;
00090       *(outbuffer + offset + 0) = (u_attempts.base >> (8 * 0)) & 0xFF;
00091       *(outbuffer + offset + 1) = (u_attempts.base >> (8 * 1)) & 0xFF;
00092       *(outbuffer + offset + 2) = (u_attempts.base >> (8 * 2)) & 0xFF;
00093       *(outbuffer + offset + 3) = (u_attempts.base >> (8 * 3)) & 0xFF;
00094       offset += sizeof(this->attempts);
00095       return offset;
00096     }
00097 
00098     virtual int deserialize(unsigned char *inbuffer)
00099     {
00100       int offset = 0;
00101       uint32_t length_group_name;
00102       memcpy(&length_group_name, (inbuffer + offset), sizeof(uint32_t));
00103       offset += 4;
00104       for(unsigned int k= offset; k< offset+length_group_name; ++k){
00105           inbuffer[k-1]=inbuffer[k];
00106       }
00107       inbuffer[offset+length_group_name-1]=0;
00108       this->group_name = (char *)(inbuffer + offset-1);
00109       offset += length_group_name;
00110       offset += this->robot_state.deserialize(inbuffer + offset);
00111       offset += this->constraints.deserialize(inbuffer + offset);
00112       union {
00113         bool real;
00114         uint8_t base;
00115       } u_avoid_collisions;
00116       u_avoid_collisions.base = 0;
00117       u_avoid_collisions.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00118       this->avoid_collisions = u_avoid_collisions.real;
00119       offset += sizeof(this->avoid_collisions);
00120       uint32_t length_ik_link_name;
00121       memcpy(&length_ik_link_name, (inbuffer + offset), sizeof(uint32_t));
00122       offset += 4;
00123       for(unsigned int k= offset; k< offset+length_ik_link_name; ++k){
00124           inbuffer[k-1]=inbuffer[k];
00125       }
00126       inbuffer[offset+length_ik_link_name-1]=0;
00127       this->ik_link_name = (char *)(inbuffer + offset-1);
00128       offset += length_ik_link_name;
00129       offset += this->pose_stamped.deserialize(inbuffer + offset);
00130       uint8_t ik_link_names_lengthT = *(inbuffer + offset++);
00131       if(ik_link_names_lengthT > ik_link_names_length)
00132         this->ik_link_names = (char**)realloc(this->ik_link_names, ik_link_names_lengthT * sizeof(char*));
00133       offset += 3;
00134       ik_link_names_length = ik_link_names_lengthT;
00135       for( uint8_t i = 0; i < ik_link_names_length; i++){
00136       uint32_t length_st_ik_link_names;
00137       memcpy(&length_st_ik_link_names, (inbuffer + offset), sizeof(uint32_t));
00138       offset += 4;
00139       for(unsigned int k= offset; k< offset+length_st_ik_link_names; ++k){
00140           inbuffer[k-1]=inbuffer[k];
00141       }
00142       inbuffer[offset+length_st_ik_link_names-1]=0;
00143       this->st_ik_link_names = (char *)(inbuffer + offset-1);
00144       offset += length_st_ik_link_names;
00145         memcpy( &(this->ik_link_names[i]), &(this->st_ik_link_names), sizeof(char*));
00146       }
00147       uint8_t pose_stamped_vector_lengthT = *(inbuffer + offset++);
00148       if(pose_stamped_vector_lengthT > pose_stamped_vector_length)
00149         this->pose_stamped_vector = (geometry_msgs::PoseStamped*)realloc(this->pose_stamped_vector, pose_stamped_vector_lengthT * sizeof(geometry_msgs::PoseStamped));
00150       offset += 3;
00151       pose_stamped_vector_length = pose_stamped_vector_lengthT;
00152       for( uint8_t i = 0; i < pose_stamped_vector_length; i++){
00153       offset += this->st_pose_stamped_vector.deserialize(inbuffer + offset);
00154         memcpy( &(this->pose_stamped_vector[i]), &(this->st_pose_stamped_vector), sizeof(geometry_msgs::PoseStamped));
00155       }
00156       this->timeout.sec =  ((uint32_t) (*(inbuffer + offset)));
00157       this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00158       this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00159       this->timeout.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00160       offset += sizeof(this->timeout.sec);
00161       this->timeout.nsec =  ((uint32_t) (*(inbuffer + offset)));
00162       this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00163       this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00164       this->timeout.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00165       offset += sizeof(this->timeout.nsec);
00166       union {
00167         int32_t real;
00168         uint32_t base;
00169       } u_attempts;
00170       u_attempts.base = 0;
00171       u_attempts.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00172       u_attempts.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00173       u_attempts.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00174       u_attempts.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00175       this->attempts = u_attempts.real;
00176       offset += sizeof(this->attempts);
00177      return offset;
00178     }
00179 
00180     const char * getType(){ return "moveit_msgs/PositionIKRequest"; };
00181     const char * getMD5(){ return "9936dc239c90af180ec94a51596c96f2"; };
00182 
00183   };
00184 
00185 }
00186 #endif


ric_mc
Author(s): RoboTiCan
autogenerated on Thu Aug 27 2015 14:39:50