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_gazebo_msgs_LinkState_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_gazebo_msgs_LinkState_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/Pose.h"
akashvibhute 0:30537dec6e0b 9 #include "geometry_msgs/Twist.h"
akashvibhute 0:30537dec6e0b 10
akashvibhute 0:30537dec6e0b 11 namespace gazebo_msgs
akashvibhute 0:30537dec6e0b 12 {
akashvibhute 0:30537dec6e0b 13
akashvibhute 0:30537dec6e0b 14 class LinkState : public ros::Msg
akashvibhute 0:30537dec6e0b 15 {
akashvibhute 0:30537dec6e0b 16 public:
akashvibhute 0:30537dec6e0b 17 const char* link_name;
akashvibhute 0:30537dec6e0b 18 geometry_msgs::Pose pose;
akashvibhute 0:30537dec6e0b 19 geometry_msgs::Twist twist;
akashvibhute 0:30537dec6e0b 20 const char* reference_frame;
akashvibhute 0:30537dec6e0b 21
akashvibhute 0:30537dec6e0b 22 LinkState():
akashvibhute 0:30537dec6e0b 23 link_name(""),
akashvibhute 0:30537dec6e0b 24 pose(),
akashvibhute 0:30537dec6e0b 25 twist(),
akashvibhute 0:30537dec6e0b 26 reference_frame("")
akashvibhute 0:30537dec6e0b 27 {
akashvibhute 0:30537dec6e0b 28 }
akashvibhute 0:30537dec6e0b 29
akashvibhute 0:30537dec6e0b 30 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 31 {
akashvibhute 0:30537dec6e0b 32 int offset = 0;
akashvibhute 0:30537dec6e0b 33 uint32_t length_link_name = strlen(this->link_name);
akashvibhute 0:30537dec6e0b 34 memcpy(outbuffer + offset, &length_link_name, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 35 offset += 4;
akashvibhute 0:30537dec6e0b 36 memcpy(outbuffer + offset, this->link_name, length_link_name);
akashvibhute 0:30537dec6e0b 37 offset += length_link_name;
akashvibhute 0:30537dec6e0b 38 offset += this->pose.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 39 offset += this->twist.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 40 uint32_t length_reference_frame = strlen(this->reference_frame);
akashvibhute 0:30537dec6e0b 41 memcpy(outbuffer + offset, &length_reference_frame, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 42 offset += 4;
akashvibhute 0:30537dec6e0b 43 memcpy(outbuffer + offset, this->reference_frame, length_reference_frame);
akashvibhute 0:30537dec6e0b 44 offset += length_reference_frame;
akashvibhute 0:30537dec6e0b 45 return offset;
akashvibhute 0:30537dec6e0b 46 }
akashvibhute 0:30537dec6e0b 47
akashvibhute 0:30537dec6e0b 48 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 49 {
akashvibhute 0:30537dec6e0b 50 int offset = 0;
akashvibhute 0:30537dec6e0b 51 uint32_t length_link_name;
akashvibhute 0:30537dec6e0b 52 memcpy(&length_link_name, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 53 offset += 4;
akashvibhute 0:30537dec6e0b 54 for(unsigned int k= offset; k< offset+length_link_name; ++k){
akashvibhute 0:30537dec6e0b 55 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 56 }
akashvibhute 0:30537dec6e0b 57 inbuffer[offset+length_link_name-1]=0;
akashvibhute 0:30537dec6e0b 58 this->link_name = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 59 offset += length_link_name;
akashvibhute 0:30537dec6e0b 60 offset += this->pose.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 61 offset += this->twist.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 62 uint32_t length_reference_frame;
akashvibhute 0:30537dec6e0b 63 memcpy(&length_reference_frame, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 64 offset += 4;
akashvibhute 0:30537dec6e0b 65 for(unsigned int k= offset; k< offset+length_reference_frame; ++k){
akashvibhute 0:30537dec6e0b 66 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 67 }
akashvibhute 0:30537dec6e0b 68 inbuffer[offset+length_reference_frame-1]=0;
akashvibhute 0:30537dec6e0b 69 this->reference_frame = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 70 offset += length_reference_frame;
akashvibhute 0:30537dec6e0b 71 return offset;
akashvibhute 0:30537dec6e0b 72 }
akashvibhute 0:30537dec6e0b 73
akashvibhute 0:30537dec6e0b 74 const char * getType(){ return "gazebo_msgs/LinkState"; };
akashvibhute 0:30537dec6e0b 75 const char * getMD5(){ return "0818ebbf28ce3a08d48ab1eaa7309ebe"; };
akashvibhute 0:30537dec6e0b 76
akashvibhute 0:30537dec6e0b 77 };
akashvibhute 0:30537dec6e0b 78
akashvibhute 0:30537dec6e0b 79 }
akashvibhute 0:30537dec6e0b 80 #endif