rosserial library for mbed Inspired by nucho's rosserial library This library is still under development
Dependents: mbed_roshydro_test
Library still under development!
Diff: moveit_msgs/GetConstraintAwarePositionIK.h
- Revision:
- 0:30537dec6e0b
diff -r 000000000000 -r 30537dec6e0b moveit_msgs/GetConstraintAwarePositionIK.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/moveit_msgs/GetConstraintAwarePositionIK.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,91 @@ +#ifndef _ROS_SERVICE_GetConstraintAwarePositionIK_h +#define _ROS_SERVICE_GetConstraintAwarePositionIK_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "moveit_msgs/MoveItErrorCodes.h" +#include "moveit_msgs/PositionIKRequest.h" +#include "moveit_msgs/RobotState.h" +#include "moveit_msgs/Constraints.h" + +namespace moveit_msgs +{ + +static const char GETCONSTRAINTAWAREPOSITIONIK[] = "moveit_msgs/GetConstraintAwarePositionIK"; + + class GetConstraintAwarePositionIKRequest : public ros::Msg + { + public: + moveit_msgs::PositionIKRequest ik_request; + moveit_msgs::Constraints constraints; + + GetConstraintAwarePositionIKRequest(): + ik_request(), + constraints() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->ik_request.serialize(outbuffer + offset); + offset += this->constraints.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->ik_request.deserialize(inbuffer + offset); + offset += this->constraints.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETCONSTRAINTAWAREPOSITIONIK; }; + const char * getMD5(){ return "7397fbef2589fd33df21251c96c43f11"; }; + + }; + + class GetConstraintAwarePositionIKResponse : public ros::Msg + { + public: + moveit_msgs::RobotState solution; + moveit_msgs::MoveItErrorCodes error_code; + + GetConstraintAwarePositionIKResponse(): + solution(), + error_code() + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->solution.serialize(outbuffer + offset); + offset += this->error_code.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->solution.deserialize(inbuffer + offset); + offset += this->error_code.deserialize(inbuffer + offset); + return offset; + } + + const char * getType(){ return GETCONSTRAINTAWAREPOSITIONIK; }; + const char * getMD5(){ return "ad50fe5fa0ddb482909be313121ea148"; }; + + }; + + class GetConstraintAwarePositionIK { + public: + typedef GetConstraintAwarePositionIKRequest Request; + typedef GetConstraintAwarePositionIKResponse Response; + }; + +} +#endif +