GetConstraintAwarePositionIK.h
Go to the documentation of this file.
00001 #ifndef _ROS_SERVICE_GetConstraintAwarePositionIK_h
00002 #define _ROS_SERVICE_GetConstraintAwarePositionIK_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 "moveit_msgs/PositionIKRequest.h"
00009 #include "moveit_msgs/RobotState.h"
00010 #include "moveit_msgs/Constraints.h"
00011 
00012 namespace moveit_msgs
00013 {
00014 
00015 static const char GETCONSTRAINTAWAREPOSITIONIK[] = "moveit_msgs/GetConstraintAwarePositionIK";
00016 
00017   class GetConstraintAwarePositionIKRequest : public ros::Msg
00018   {
00019     public:
00020       moveit_msgs::PositionIKRequest ik_request;
00021       moveit_msgs::Constraints constraints;
00022 
00023     virtual int serialize(unsigned char *outbuffer) const
00024     {
00025       int offset = 0;
00026       offset += this->ik_request.serialize(outbuffer + offset);
00027       offset += this->constraints.serialize(outbuffer + offset);
00028       return offset;
00029     }
00030 
00031     virtual int deserialize(unsigned char *inbuffer)
00032     {
00033       int offset = 0;
00034       offset += this->ik_request.deserialize(inbuffer + offset);
00035       offset += this->constraints.deserialize(inbuffer + offset);
00036      return offset;
00037     }
00038 
00039     const char * getType(){ return GETCONSTRAINTAWAREPOSITIONIK; };
00040     const char * getMD5(){ return "7397fbef2589fd33df21251c96c43f11"; };
00041 
00042   };
00043 
00044   class GetConstraintAwarePositionIKResponse : public ros::Msg
00045   {
00046     public:
00047       moveit_msgs::RobotState solution;
00048       moveit_msgs::MoveItErrorCodes error_code;
00049 
00050     virtual int serialize(unsigned char *outbuffer) const
00051     {
00052       int offset = 0;
00053       offset += this->solution.serialize(outbuffer + offset);
00054       offset += this->error_code.serialize(outbuffer + offset);
00055       return offset;
00056     }
00057 
00058     virtual int deserialize(unsigned char *inbuffer)
00059     {
00060       int offset = 0;
00061       offset += this->solution.deserialize(inbuffer + offset);
00062       offset += this->error_code.deserialize(inbuffer + offset);
00063      return offset;
00064     }
00065 
00066     const char * getType(){ return GETCONSTRAINTAWAREPOSITIONIK; };
00067     const char * getMD5(){ return "ad50fe5fa0ddb482909be313121ea148"; };
00068 
00069   };
00070 
00071   class GetConstraintAwarePositionIK {
00072     public:
00073     typedef GetConstraintAwarePositionIKRequest Request;
00074     typedef GetConstraintAwarePositionIKResponse Response;
00075   };
00076 
00077 }
00078 #endif


ric_mc
Author(s): RoboTiCan
autogenerated on Fri May 20 2016 03:48:55