Go to the documentation of this file.00001 #ifndef _ROS_moveit_msgs_Constraints_h
00002 #define _ROS_moveit_msgs_Constraints_h
00003
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "moveit_msgs/JointConstraint.h"
00009 #include "moveit_msgs/PositionConstraint.h"
00010 #include "moveit_msgs/OrientationConstraint.h"
00011 #include "moveit_msgs/VisibilityConstraint.h"
00012
00013 namespace moveit_msgs
00014 {
00015
00016 class Constraints : public ros::Msg
00017 {
00018 public:
00019 const char* name;
00020 uint8_t joint_constraints_length;
00021 moveit_msgs::JointConstraint st_joint_constraints;
00022 moveit_msgs::JointConstraint * joint_constraints;
00023 uint8_t position_constraints_length;
00024 moveit_msgs::PositionConstraint st_position_constraints;
00025 moveit_msgs::PositionConstraint * position_constraints;
00026 uint8_t orientation_constraints_length;
00027 moveit_msgs::OrientationConstraint st_orientation_constraints;
00028 moveit_msgs::OrientationConstraint * orientation_constraints;
00029 uint8_t visibility_constraints_length;
00030 moveit_msgs::VisibilityConstraint st_visibility_constraints;
00031 moveit_msgs::VisibilityConstraint * visibility_constraints;
00032
00033 virtual int serialize(unsigned char *outbuffer) const
00034 {
00035 int offset = 0;
00036 uint32_t length_name = strlen(this->name);
00037 memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
00038 offset += 4;
00039 memcpy(outbuffer + offset, this->name, length_name);
00040 offset += length_name;
00041 *(outbuffer + offset++) = joint_constraints_length;
00042 *(outbuffer + offset++) = 0;
00043 *(outbuffer + offset++) = 0;
00044 *(outbuffer + offset++) = 0;
00045 for( uint8_t i = 0; i < joint_constraints_length; i++){
00046 offset += this->joint_constraints[i].serialize(outbuffer + offset);
00047 }
00048 *(outbuffer + offset++) = position_constraints_length;
00049 *(outbuffer + offset++) = 0;
00050 *(outbuffer + offset++) = 0;
00051 *(outbuffer + offset++) = 0;
00052 for( uint8_t i = 0; i < position_constraints_length; i++){
00053 offset += this->position_constraints[i].serialize(outbuffer + offset);
00054 }
00055 *(outbuffer + offset++) = orientation_constraints_length;
00056 *(outbuffer + offset++) = 0;
00057 *(outbuffer + offset++) = 0;
00058 *(outbuffer + offset++) = 0;
00059 for( uint8_t i = 0; i < orientation_constraints_length; i++){
00060 offset += this->orientation_constraints[i].serialize(outbuffer + offset);
00061 }
00062 *(outbuffer + offset++) = visibility_constraints_length;
00063 *(outbuffer + offset++) = 0;
00064 *(outbuffer + offset++) = 0;
00065 *(outbuffer + offset++) = 0;
00066 for( uint8_t i = 0; i < visibility_constraints_length; i++){
00067 offset += this->visibility_constraints[i].serialize(outbuffer + offset);
00068 }
00069 return offset;
00070 }
00071
00072 virtual int deserialize(unsigned char *inbuffer)
00073 {
00074 int offset = 0;
00075 uint32_t length_name;
00076 memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
00077 offset += 4;
00078 for(unsigned int k= offset; k< offset+length_name; ++k){
00079 inbuffer[k-1]=inbuffer[k];
00080 }
00081 inbuffer[offset+length_name-1]=0;
00082 this->name = (char *)(inbuffer + offset-1);
00083 offset += length_name;
00084 uint8_t joint_constraints_lengthT = *(inbuffer + offset++);
00085 if(joint_constraints_lengthT > joint_constraints_length)
00086 this->joint_constraints = (moveit_msgs::JointConstraint*)realloc(this->joint_constraints, joint_constraints_lengthT * sizeof(moveit_msgs::JointConstraint));
00087 offset += 3;
00088 joint_constraints_length = joint_constraints_lengthT;
00089 for( uint8_t i = 0; i < joint_constraints_length; i++){
00090 offset += this->st_joint_constraints.deserialize(inbuffer + offset);
00091 memcpy( &(this->joint_constraints[i]), &(this->st_joint_constraints), sizeof(moveit_msgs::JointConstraint));
00092 }
00093 uint8_t position_constraints_lengthT = *(inbuffer + offset++);
00094 if(position_constraints_lengthT > position_constraints_length)
00095 this->position_constraints = (moveit_msgs::PositionConstraint*)realloc(this->position_constraints, position_constraints_lengthT * sizeof(moveit_msgs::PositionConstraint));
00096 offset += 3;
00097 position_constraints_length = position_constraints_lengthT;
00098 for( uint8_t i = 0; i < position_constraints_length; i++){
00099 offset += this->st_position_constraints.deserialize(inbuffer + offset);
00100 memcpy( &(this->position_constraints[i]), &(this->st_position_constraints), sizeof(moveit_msgs::PositionConstraint));
00101 }
00102 uint8_t orientation_constraints_lengthT = *(inbuffer + offset++);
00103 if(orientation_constraints_lengthT > orientation_constraints_length)
00104 this->orientation_constraints = (moveit_msgs::OrientationConstraint*)realloc(this->orientation_constraints, orientation_constraints_lengthT * sizeof(moveit_msgs::OrientationConstraint));
00105 offset += 3;
00106 orientation_constraints_length = orientation_constraints_lengthT;
00107 for( uint8_t i = 0; i < orientation_constraints_length; i++){
00108 offset += this->st_orientation_constraints.deserialize(inbuffer + offset);
00109 memcpy( &(this->orientation_constraints[i]), &(this->st_orientation_constraints), sizeof(moveit_msgs::OrientationConstraint));
00110 }
00111 uint8_t visibility_constraints_lengthT = *(inbuffer + offset++);
00112 if(visibility_constraints_lengthT > visibility_constraints_length)
00113 this->visibility_constraints = (moveit_msgs::VisibilityConstraint*)realloc(this->visibility_constraints, visibility_constraints_lengthT * sizeof(moveit_msgs::VisibilityConstraint));
00114 offset += 3;
00115 visibility_constraints_length = visibility_constraints_lengthT;
00116 for( uint8_t i = 0; i < visibility_constraints_length; i++){
00117 offset += this->st_visibility_constraints.deserialize(inbuffer + offset);
00118 memcpy( &(this->visibility_constraints[i]), &(this->st_visibility_constraints), sizeof(moveit_msgs::VisibilityConstraint));
00119 }
00120 return offset;
00121 }
00122
00123 const char * getType(){ return "moveit_msgs/Constraints"; };
00124 const char * getMD5(){ return "8d5ce8d34ef26c65fb5d43c9e99bf6e0"; };
00125
00126 };
00127
00128 }
00129 #endif