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_moveit_msgs_OrientationConstraint_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_moveit_msgs_OrientationConstraint_h
akashvibhute 0:30537dec6e0b 3
akashvibhute 0:30537dec6e0b 4 #include <stdint.h>
akashvibhute 0:30537dec6e0b 5 #include <string.h>
akashvibhute 0:30537dec6e0b 6 #include <stdlib.h>
akashvibhute 0:30537dec6e0b 7 #include "ros/msg.h"
akashvibhute 0:30537dec6e0b 8 #include "std_msgs/Header.h"
akashvibhute 0:30537dec6e0b 9 #include "geometry_msgs/Quaternion.h"
akashvibhute 0:30537dec6e0b 10
akashvibhute 0:30537dec6e0b 11 namespace moveit_msgs
akashvibhute 0:30537dec6e0b 12 {
akashvibhute 0:30537dec6e0b 13
akashvibhute 0:30537dec6e0b 14 class OrientationConstraint : public ros::Msg
akashvibhute 0:30537dec6e0b 15 {
akashvibhute 0:30537dec6e0b 16 public:
akashvibhute 0:30537dec6e0b 17 std_msgs::Header header;
akashvibhute 0:30537dec6e0b 18 geometry_msgs::Quaternion orientation;
akashvibhute 0:30537dec6e0b 19 const char* link_name;
akashvibhute 0:30537dec6e0b 20 float absolute_x_axis_tolerance;
akashvibhute 0:30537dec6e0b 21 float absolute_y_axis_tolerance;
akashvibhute 0:30537dec6e0b 22 float absolute_z_axis_tolerance;
akashvibhute 0:30537dec6e0b 23 float weight;
akashvibhute 0:30537dec6e0b 24
akashvibhute 0:30537dec6e0b 25 OrientationConstraint():
akashvibhute 0:30537dec6e0b 26 header(),
akashvibhute 0:30537dec6e0b 27 orientation(),
akashvibhute 0:30537dec6e0b 28 link_name(""),
akashvibhute 0:30537dec6e0b 29 absolute_x_axis_tolerance(0),
akashvibhute 0:30537dec6e0b 30 absolute_y_axis_tolerance(0),
akashvibhute 0:30537dec6e0b 31 absolute_z_axis_tolerance(0),
akashvibhute 0:30537dec6e0b 32 weight(0)
akashvibhute 0:30537dec6e0b 33 {
akashvibhute 0:30537dec6e0b 34 }
akashvibhute 0:30537dec6e0b 35
akashvibhute 0:30537dec6e0b 36 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 37 {
akashvibhute 0:30537dec6e0b 38 int offset = 0;
akashvibhute 0:30537dec6e0b 39 offset += this->header.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 40 offset += this->orientation.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 41 uint32_t length_link_name = strlen(this->link_name);
akashvibhute 0:30537dec6e0b 42 memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 43 offset += 4;
akashvibhute 0:30537dec6e0b 44 memcpy(outbuffer + offset, this->link_name, length_link_name);
akashvibhute 0:30537dec6e0b 45 offset += length_link_name;
akashvibhute 0:30537dec6e0b 46 offset += serializeAvrFloat64(outbuffer + offset, this->absolute_x_axis_tolerance);
akashvibhute 0:30537dec6e0b 47 offset += serializeAvrFloat64(outbuffer + offset, this->absolute_y_axis_tolerance);
akashvibhute 0:30537dec6e0b 48 offset += serializeAvrFloat64(outbuffer + offset, this->absolute_z_axis_tolerance);
akashvibhute 0:30537dec6e0b 49 offset += serializeAvrFloat64(outbuffer + offset, this->weight);
akashvibhute 0:30537dec6e0b 50 return offset;
akashvibhute 0:30537dec6e0b 51 }
akashvibhute 0:30537dec6e0b 52
akashvibhute 0:30537dec6e0b 53 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 54 {
akashvibhute 0:30537dec6e0b 55 int offset = 0;
akashvibhute 0:30537dec6e0b 56 offset += this->header.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 57 offset += this->orientation.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 58 uint32_t length_link_name;
akashvibhute 0:30537dec6e0b 59 memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 60 offset += 4;
akashvibhute 0:30537dec6e0b 61 for(unsigned int k= offset; k< offset+length_link_name; ++k){
akashvibhute 0:30537dec6e0b 62 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 63 }
akashvibhute 0:30537dec6e0b 64 inbuffer[offset+length_link_name-1]=0;
akashvibhute 0:30537dec6e0b 65 this->link_name = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 66 offset += length_link_name;
akashvibhute 0:30537dec6e0b 67 offset += deserializeAvrFloat64(inbuffer + offset, &(this->absolute_x_axis_tolerance));
akashvibhute 0:30537dec6e0b 68 offset += deserializeAvrFloat64(inbuffer + offset, &(this->absolute_y_axis_tolerance));
akashvibhute 0:30537dec6e0b 69 offset += deserializeAvrFloat64(inbuffer + offset, &(this->absolute_z_axis_tolerance));
akashvibhute 0:30537dec6e0b 70 offset += deserializeAvrFloat64(inbuffer + offset, &(this->weight));
akashvibhute 0:30537dec6e0b 71 return offset;
akashvibhute 0:30537dec6e0b 72 }
akashvibhute 0:30537dec6e0b 73
akashvibhute 0:30537dec6e0b 74 const char * getType(){ return "moveit_msgs/OrientationConstraint"; };
akashvibhute 0:30537dec6e0b 75 const char * getMD5(){ return "ab5cefb9bc4c0089620f5eb4caf4e59a"; };
akashvibhute 0:30537dec6e0b 76
akashvibhute 0:30537dec6e0b 77 };
akashvibhute 0:30537dec6e0b 78
akashvibhute 0:30537dec6e0b 79 }
akashvibhute 0:30537dec6e0b 80 #endif