Go to the documentation of this file.00001 #ifndef _ROS_moveit_msgs_MotionPlanRequest_h
00002 #define _ROS_moveit_msgs_MotionPlanRequest_h
00003
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "moveit_msgs/WorkspaceParameters.h"
00009 #include "moveit_msgs/RobotState.h"
00010 #include "moveit_msgs/Constraints.h"
00011 #include "moveit_msgs/TrajectoryConstraints.h"
00012
00013 namespace moveit_msgs
00014 {
00015
00016 class MotionPlanRequest : public ros::Msg
00017 {
00018 public:
00019 moveit_msgs::WorkspaceParameters workspace_parameters;
00020 moveit_msgs::RobotState start_state;
00021 uint8_t goal_constraints_length;
00022 moveit_msgs::Constraints st_goal_constraints;
00023 moveit_msgs::Constraints * goal_constraints;
00024 moveit_msgs::Constraints path_constraints;
00025 moveit_msgs::TrajectoryConstraints trajectory_constraints;
00026 const char* planner_id;
00027 const char* group_name;
00028 int32_t num_planning_attempts;
00029 float allowed_planning_time;
00030
00031 virtual int serialize(unsigned char *outbuffer) const
00032 {
00033 int offset = 0;
00034 offset += this->workspace_parameters.serialize(outbuffer + offset);
00035 offset += this->start_state.serialize(outbuffer + offset);
00036 *(outbuffer + offset++) = goal_constraints_length;
00037 *(outbuffer + offset++) = 0;
00038 *(outbuffer + offset++) = 0;
00039 *(outbuffer + offset++) = 0;
00040 for( uint8_t i = 0; i < goal_constraints_length; i++){
00041 offset += this->goal_constraints[i].serialize(outbuffer + offset);
00042 }
00043 offset += this->path_constraints.serialize(outbuffer + offset);
00044 offset += this->trajectory_constraints.serialize(outbuffer + offset);
00045 uint32_t length_planner_id = strlen(this->planner_id);
00046 memcpy(outbuffer + offset, &length_planner_id, sizeof(uint32_t));
00047 offset += 4;
00048 memcpy(outbuffer + offset, this->planner_id, length_planner_id);
00049 offset += length_planner_id;
00050 uint32_t length_group_name = strlen(this->group_name);
00051 memcpy(outbuffer + offset, &length_group_name, sizeof(uint32_t));
00052 offset += 4;
00053 memcpy(outbuffer + offset, this->group_name, length_group_name);
00054 offset += length_group_name;
00055 union {
00056 int32_t real;
00057 uint32_t base;
00058 } u_num_planning_attempts;
00059 u_num_planning_attempts.real = this->num_planning_attempts;
00060 *(outbuffer + offset + 0) = (u_num_planning_attempts.base >> (8 * 0)) & 0xFF;
00061 *(outbuffer + offset + 1) = (u_num_planning_attempts.base >> (8 * 1)) & 0xFF;
00062 *(outbuffer + offset + 2) = (u_num_planning_attempts.base >> (8 * 2)) & 0xFF;
00063 *(outbuffer + offset + 3) = (u_num_planning_attempts.base >> (8 * 3)) & 0xFF;
00064 offset += sizeof(this->num_planning_attempts);
00065 int32_t * val_allowed_planning_time = (int32_t *) &(this->allowed_planning_time);
00066 int32_t exp_allowed_planning_time = (((*val_allowed_planning_time)>>23)&255);
00067 if(exp_allowed_planning_time != 0)
00068 exp_allowed_planning_time += 1023-127;
00069 int32_t sig_allowed_planning_time = *val_allowed_planning_time;
00070 *(outbuffer + offset++) = 0;
00071 *(outbuffer + offset++) = 0;
00072 *(outbuffer + offset++) = 0;
00073 *(outbuffer + offset++) = (sig_allowed_planning_time<<5) & 0xff;
00074 *(outbuffer + offset++) = (sig_allowed_planning_time>>3) & 0xff;
00075 *(outbuffer + offset++) = (sig_allowed_planning_time>>11) & 0xff;
00076 *(outbuffer + offset++) = ((exp_allowed_planning_time<<4) & 0xF0) | ((sig_allowed_planning_time>>19)&0x0F);
00077 *(outbuffer + offset++) = (exp_allowed_planning_time>>4) & 0x7F;
00078 if(this->allowed_planning_time < 0) *(outbuffer + offset -1) |= 0x80;
00079 return offset;
00080 }
00081
00082 virtual int deserialize(unsigned char *inbuffer)
00083 {
00084 int offset = 0;
00085 offset += this->workspace_parameters.deserialize(inbuffer + offset);
00086 offset += this->start_state.deserialize(inbuffer + offset);
00087 uint8_t goal_constraints_lengthT = *(inbuffer + offset++);
00088 if(goal_constraints_lengthT > goal_constraints_length)
00089 this->goal_constraints = (moveit_msgs::Constraints*)realloc(this->goal_constraints, goal_constraints_lengthT * sizeof(moveit_msgs::Constraints));
00090 offset += 3;
00091 goal_constraints_length = goal_constraints_lengthT;
00092 for( uint8_t i = 0; i < goal_constraints_length; i++){
00093 offset += this->st_goal_constraints.deserialize(inbuffer + offset);
00094 memcpy( &(this->goal_constraints[i]), &(this->st_goal_constraints), sizeof(moveit_msgs::Constraints));
00095 }
00096 offset += this->path_constraints.deserialize(inbuffer + offset);
00097 offset += this->trajectory_constraints.deserialize(inbuffer + offset);
00098 uint32_t length_planner_id;
00099 memcpy(&length_planner_id, (inbuffer + offset), sizeof(uint32_t));
00100 offset += 4;
00101 for(unsigned int k= offset; k< offset+length_planner_id; ++k){
00102 inbuffer[k-1]=inbuffer[k];
00103 }
00104 inbuffer[offset+length_planner_id-1]=0;
00105 this->planner_id = (char *)(inbuffer + offset-1);
00106 offset += length_planner_id;
00107 uint32_t length_group_name;
00108 memcpy(&length_group_name, (inbuffer + offset), sizeof(uint32_t));
00109 offset += 4;
00110 for(unsigned int k= offset; k< offset+length_group_name; ++k){
00111 inbuffer[k-1]=inbuffer[k];
00112 }
00113 inbuffer[offset+length_group_name-1]=0;
00114 this->group_name = (char *)(inbuffer + offset-1);
00115 offset += length_group_name;
00116 union {
00117 int32_t real;
00118 uint32_t base;
00119 } u_num_planning_attempts;
00120 u_num_planning_attempts.base = 0;
00121 u_num_planning_attempts.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00122 u_num_planning_attempts.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00123 u_num_planning_attempts.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00124 u_num_planning_attempts.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00125 this->num_planning_attempts = u_num_planning_attempts.real;
00126 offset += sizeof(this->num_planning_attempts);
00127 uint32_t * val_allowed_planning_time = (uint32_t*) &(this->allowed_planning_time);
00128 offset += 3;
00129 *val_allowed_planning_time = ((uint32_t)(*(inbuffer + offset++))>>5 & 0x07);
00130 *val_allowed_planning_time |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<3;
00131 *val_allowed_planning_time |= ((uint32_t)(*(inbuffer + offset++)) & 0xff)<<11;
00132 *val_allowed_planning_time |= ((uint32_t)(*(inbuffer + offset)) & 0x0f)<<19;
00133 uint32_t exp_allowed_planning_time = ((uint32_t)(*(inbuffer + offset++))&0xf0)>>4;
00134 exp_allowed_planning_time |= ((uint32_t)(*(inbuffer + offset)) & 0x7f)<<4;
00135 if(exp_allowed_planning_time !=0)
00136 *val_allowed_planning_time |= ((exp_allowed_planning_time)-1023+127)<<23;
00137 if( ((*(inbuffer+offset++)) & 0x80) > 0) this->allowed_planning_time = -this->allowed_planning_time;
00138 return offset;
00139 }
00140
00141 const char * getType(){ return "moveit_msgs/MotionPlanRequest"; };
00142 const char * getMD5(){ return "7cd790e04c3a55f6742ec387a72a02d6"; };
00143
00144 };
00145
00146 }
00147 #endif