rosserial library for mbed Inspired by nucho's rosserial library This library is still under development

Dependencies:   MODSERIAL mbed

Dependents:   mbed_roshydro_test

Library still under development!

Committer:
akashvibhute
Date:
Sun Feb 15 10:53:43 2015 +0000
Revision:
0:30537dec6e0b
First commit; Library still need to be debugged, compilation issues with new mbed and modserial updates.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
akashvibhute 0:30537dec6e0b 1 #ifndef _ROS_SERVICE_GetConstraintAwarePositionIK_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_SERVICE_GetConstraintAwarePositionIK_h
akashvibhute 0:30537dec6e0b 3 #include <stdint.h>
akashvibhute 0:30537dec6e0b 4 #include <string.h>
akashvibhute 0:30537dec6e0b 5 #include <stdlib.h>
akashvibhute 0:30537dec6e0b 6 #include "ros/msg.h"
akashvibhute 0:30537dec6e0b 7 #include "moveit_msgs/MoveItErrorCodes.h"
akashvibhute 0:30537dec6e0b 8 #include "moveit_msgs/PositionIKRequest.h"
akashvibhute 0:30537dec6e0b 9 #include "moveit_msgs/RobotState.h"
akashvibhute 0:30537dec6e0b 10 #include "moveit_msgs/Constraints.h"
akashvibhute 0:30537dec6e0b 11
akashvibhute 0:30537dec6e0b 12 namespace moveit_msgs
akashvibhute 0:30537dec6e0b 13 {
akashvibhute 0:30537dec6e0b 14
akashvibhute 0:30537dec6e0b 15 static const char GETCONSTRAINTAWAREPOSITIONIK[] = "moveit_msgs/GetConstraintAwarePositionIK";
akashvibhute 0:30537dec6e0b 16
akashvibhute 0:30537dec6e0b 17 class GetConstraintAwarePositionIKRequest : public ros::Msg
akashvibhute 0:30537dec6e0b 18 {
akashvibhute 0:30537dec6e0b 19 public:
akashvibhute 0:30537dec6e0b 20 moveit_msgs::PositionIKRequest ik_request;
akashvibhute 0:30537dec6e0b 21 moveit_msgs::Constraints constraints;
akashvibhute 0:30537dec6e0b 22
akashvibhute 0:30537dec6e0b 23 GetConstraintAwarePositionIKRequest():
akashvibhute 0:30537dec6e0b 24 ik_request(),
akashvibhute 0:30537dec6e0b 25 constraints()
akashvibhute 0:30537dec6e0b 26 {
akashvibhute 0:30537dec6e0b 27 }
akashvibhute 0:30537dec6e0b 28
akashvibhute 0:30537dec6e0b 29 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 30 {
akashvibhute 0:30537dec6e0b 31 int offset = 0;
akashvibhute 0:30537dec6e0b 32 offset += this->ik_request.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 33 offset += this->constraints.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 34 return offset;
akashvibhute 0:30537dec6e0b 35 }
akashvibhute 0:30537dec6e0b 36
akashvibhute 0:30537dec6e0b 37 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 38 {
akashvibhute 0:30537dec6e0b 39 int offset = 0;
akashvibhute 0:30537dec6e0b 40 offset += this->ik_request.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 41 offset += this->constraints.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 42 return offset;
akashvibhute 0:30537dec6e0b 43 }
akashvibhute 0:30537dec6e0b 44
akashvibhute 0:30537dec6e0b 45 const char * getType(){ return GETCONSTRAINTAWAREPOSITIONIK; };
akashvibhute 0:30537dec6e0b 46 const char * getMD5(){ return "7397fbef2589fd33df21251c96c43f11"; };
akashvibhute 0:30537dec6e0b 47
akashvibhute 0:30537dec6e0b 48 };
akashvibhute 0:30537dec6e0b 49
akashvibhute 0:30537dec6e0b 50 class GetConstraintAwarePositionIKResponse : public ros::Msg
akashvibhute 0:30537dec6e0b 51 {
akashvibhute 0:30537dec6e0b 52 public:
akashvibhute 0:30537dec6e0b 53 moveit_msgs::RobotState solution;
akashvibhute 0:30537dec6e0b 54 moveit_msgs::MoveItErrorCodes error_code;
akashvibhute 0:30537dec6e0b 55
akashvibhute 0:30537dec6e0b 56 GetConstraintAwarePositionIKResponse():
akashvibhute 0:30537dec6e0b 57 solution(),
akashvibhute 0:30537dec6e0b 58 error_code()
akashvibhute 0:30537dec6e0b 59 {
akashvibhute 0:30537dec6e0b 60 }
akashvibhute 0:30537dec6e0b 61
akashvibhute 0:30537dec6e0b 62 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 63 {
akashvibhute 0:30537dec6e0b 64 int offset = 0;
akashvibhute 0:30537dec6e0b 65 offset += this->solution.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 66 offset += this->error_code.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 67 return offset;
akashvibhute 0:30537dec6e0b 68 }
akashvibhute 0:30537dec6e0b 69
akashvibhute 0:30537dec6e0b 70 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 71 {
akashvibhute 0:30537dec6e0b 72 int offset = 0;
akashvibhute 0:30537dec6e0b 73 offset += this->solution.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 74 offset += this->error_code.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 75 return offset;
akashvibhute 0:30537dec6e0b 76 }
akashvibhute 0:30537dec6e0b 77
akashvibhute 0:30537dec6e0b 78 const char * getType(){ return GETCONSTRAINTAWAREPOSITIONIK; };
akashvibhute 0:30537dec6e0b 79 const char * getMD5(){ return "ad50fe5fa0ddb482909be313121ea148"; };
akashvibhute 0:30537dec6e0b 80
akashvibhute 0:30537dec6e0b 81 };
akashvibhute 0:30537dec6e0b 82
akashvibhute 0:30537dec6e0b 83 class GetConstraintAwarePositionIK {
akashvibhute 0:30537dec6e0b 84 public:
akashvibhute 0:30537dec6e0b 85 typedef GetConstraintAwarePositionIKRequest Request;
akashvibhute 0:30537dec6e0b 86 typedef GetConstraintAwarePositionIKResponse Response;
akashvibhute 0:30537dec6e0b 87 };
akashvibhute 0:30537dec6e0b 88
akashvibhute 0:30537dec6e0b 89 }
akashvibhute 0:30537dec6e0b 90 #endif
akashvibhute 0:30537dec6e0b 91