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_control_msgs_PointHeadGoal_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_control_msgs_PointHeadGoal_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 "geometry_msgs/PointStamped.h"
akashvibhute 0:30537dec6e0b 9 #include "geometry_msgs/Vector3.h"
akashvibhute 0:30537dec6e0b 10 #include "ros/duration.h"
akashvibhute 0:30537dec6e0b 11
akashvibhute 0:30537dec6e0b 12 namespace control_msgs
akashvibhute 0:30537dec6e0b 13 {
akashvibhute 0:30537dec6e0b 14
akashvibhute 0:30537dec6e0b 15 class PointHeadGoal : public ros::Msg
akashvibhute 0:30537dec6e0b 16 {
akashvibhute 0:30537dec6e0b 17 public:
akashvibhute 0:30537dec6e0b 18 geometry_msgs::PointStamped target;
akashvibhute 0:30537dec6e0b 19 geometry_msgs::Vector3 pointing_axis;
akashvibhute 0:30537dec6e0b 20 const char* pointing_frame;
akashvibhute 0:30537dec6e0b 21 ros::Duration min_duration;
akashvibhute 0:30537dec6e0b 22 float max_velocity;
akashvibhute 0:30537dec6e0b 23
akashvibhute 0:30537dec6e0b 24 PointHeadGoal():
akashvibhute 0:30537dec6e0b 25 target(),
akashvibhute 0:30537dec6e0b 26 pointing_axis(),
akashvibhute 0:30537dec6e0b 27 pointing_frame(""),
akashvibhute 0:30537dec6e0b 28 min_duration(),
akashvibhute 0:30537dec6e0b 29 max_velocity(0)
akashvibhute 0:30537dec6e0b 30 {
akashvibhute 0:30537dec6e0b 31 }
akashvibhute 0:30537dec6e0b 32
akashvibhute 0:30537dec6e0b 33 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 34 {
akashvibhute 0:30537dec6e0b 35 int offset = 0;
akashvibhute 0:30537dec6e0b 36 offset += this->target.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 37 offset += this->pointing_axis.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 38 uint32_t length_pointing_frame = strlen(this->pointing_frame);
akashvibhute 0:30537dec6e0b 39 memcpy(outbuffer + offset, &length_pointing_frame, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 40 offset += 4;
akashvibhute 0:30537dec6e0b 41 memcpy(outbuffer + offset, this->pointing_frame, length_pointing_frame);
akashvibhute 0:30537dec6e0b 42 offset += length_pointing_frame;
akashvibhute 0:30537dec6e0b 43 *(outbuffer + offset + 0) = (this->min_duration.sec >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 44 *(outbuffer + offset + 1) = (this->min_duration.sec >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 45 *(outbuffer + offset + 2) = (this->min_duration.sec >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 46 *(outbuffer + offset + 3) = (this->min_duration.sec >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 47 offset += sizeof(this->min_duration.sec);
akashvibhute 0:30537dec6e0b 48 *(outbuffer + offset + 0) = (this->min_duration.nsec >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 49 *(outbuffer + offset + 1) = (this->min_duration.nsec >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 50 *(outbuffer + offset + 2) = (this->min_duration.nsec >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 51 *(outbuffer + offset + 3) = (this->min_duration.nsec >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 52 offset += sizeof(this->min_duration.nsec);
akashvibhute 0:30537dec6e0b 53 offset += serializeAvrFloat64(outbuffer + offset, this->max_velocity);
akashvibhute 0:30537dec6e0b 54 return offset;
akashvibhute 0:30537dec6e0b 55 }
akashvibhute 0:30537dec6e0b 56
akashvibhute 0:30537dec6e0b 57 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 58 {
akashvibhute 0:30537dec6e0b 59 int offset = 0;
akashvibhute 0:30537dec6e0b 60 offset += this->target.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 61 offset += this->pointing_axis.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 62 uint32_t length_pointing_frame;
akashvibhute 0:30537dec6e0b 63 memcpy(&length_pointing_frame, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 64 offset += 4;
akashvibhute 0:30537dec6e0b 65 for(unsigned int k= offset; k< offset+length_pointing_frame; ++k){
akashvibhute 0:30537dec6e0b 66 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 67 }
akashvibhute 0:30537dec6e0b 68 inbuffer[offset+length_pointing_frame-1]=0;
akashvibhute 0:30537dec6e0b 69 this->pointing_frame = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 70 offset += length_pointing_frame;
akashvibhute 0:30537dec6e0b 71 this->min_duration.sec = ((uint32_t) (*(inbuffer + offset)));
akashvibhute 0:30537dec6e0b 72 this->min_duration.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 73 this->min_duration.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 74 this->min_duration.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 75 offset += sizeof(this->min_duration.sec);
akashvibhute 0:30537dec6e0b 76 this->min_duration.nsec = ((uint32_t) (*(inbuffer + offset)));
akashvibhute 0:30537dec6e0b 77 this->min_duration.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 78 this->min_duration.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 79 this->min_duration.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 80 offset += sizeof(this->min_duration.nsec);
akashvibhute 0:30537dec6e0b 81 offset += deserializeAvrFloat64(inbuffer + offset, &(this->max_velocity));
akashvibhute 0:30537dec6e0b 82 return offset;
akashvibhute 0:30537dec6e0b 83 }
akashvibhute 0:30537dec6e0b 84
akashvibhute 0:30537dec6e0b 85 const char * getType(){ return "control_msgs/PointHeadGoal"; };
akashvibhute 0:30537dec6e0b 86 const char * getMD5(){ return "8b92b1cd5e06c8a94c917dc3209a4c1d"; };
akashvibhute 0:30537dec6e0b 87
akashvibhute 0:30537dec6e0b 88 };
akashvibhute 0:30537dec6e0b 89
akashvibhute 0:30537dec6e0b 90 }
akashvibhute 0:30537dec6e0b 91 #endif