This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial.

Dependencies:  

Dependents:   rosserial_mbed robot_S2

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers Odometry.h Source File

Odometry.h

00001 #ifndef _ROS_nav_msgs_Odometry_h
00002 #define _ROS_nav_msgs_Odometry_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "std_msgs/Header.h"
00009 #include "geometry_msgs/PoseWithCovariance.h"
00010 #include "geometry_msgs/TwistWithCovariance.h"
00011 
00012 namespace nav_msgs
00013 {
00014 
00015   class Odometry : public ros::Msg
00016   {
00017     public:
00018       std_msgs::Header header;
00019       char * child_frame_id;
00020       geometry_msgs::PoseWithCovariance pose;
00021       geometry_msgs::TwistWithCovariance twist;
00022 
00023     virtual int serialize(unsigned char *outbuffer) const
00024     {
00025       int offset = 0;
00026       offset += this->header.serialize(outbuffer + offset);
00027       uint32_t * length_child_frame_id = (uint32_t *)(outbuffer + offset);
00028       *length_child_frame_id = strlen( (const char*) this->child_frame_id);
00029       offset += 4;
00030       memcpy(outbuffer + offset, this->child_frame_id, *length_child_frame_id);
00031       offset += *length_child_frame_id;
00032       offset += this->pose.serialize(outbuffer + offset);
00033       offset += this->twist.serialize(outbuffer + offset);
00034       return offset;
00035     }
00036 
00037     virtual int deserialize(unsigned char *inbuffer)
00038     {
00039       int offset = 0;
00040       offset += this->header.deserialize(inbuffer + offset);
00041       uint32_t length_child_frame_id = *(uint32_t *)(inbuffer + offset);
00042       offset += 4;
00043       for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){
00044           inbuffer[k-1]=inbuffer[k];
00045       }
00046       inbuffer[offset+length_child_frame_id-1]=0;
00047       this->child_frame_id = (char *)(inbuffer + offset-1);
00048       offset += length_child_frame_id;
00049       offset += this->pose.deserialize(inbuffer + offset);
00050       offset += this->twist.deserialize(inbuffer + offset);
00051      return offset;
00052     }
00053 
00054     virtual const char * getType(){ return "nav_msgs/Odometry"; };
00055     virtual const char * getMD5(){ return "cd5e73d190d741a2f92e81eda573aca7"; };
00056 
00057   };
00058 
00059 }
00060 #endif