ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

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       const char* child_frame_id;
00020       geometry_msgs::PoseWithCovariance pose;
00021       geometry_msgs::TwistWithCovariance twist;
00022 
00023     Odometry():
00024       header(),
00025       child_frame_id(""),
00026       pose(),
00027       twist()
00028     {
00029     }
00030 
00031     virtual int serialize(unsigned char *outbuffer) const
00032     {
00033       int offset = 0;
00034       offset += this->header.serialize(outbuffer + offset);
00035       uint32_t length_child_frame_id = strlen(this->child_frame_id);
00036       memcpy(outbuffer + offset, &length_child_frame_id, sizeof(uint32_t));
00037       offset += 4;
00038       memcpy(outbuffer + offset, this->child_frame_id, length_child_frame_id);
00039       offset += length_child_frame_id;
00040       offset += this->pose.serialize(outbuffer + offset);
00041       offset += this->twist.serialize(outbuffer + offset);
00042       return offset;
00043     }
00044 
00045     virtual int deserialize(unsigned char *inbuffer)
00046     {
00047       int offset = 0;
00048       offset += this->header.deserialize(inbuffer + offset);
00049       uint32_t length_child_frame_id;
00050       memcpy(&length_child_frame_id, (inbuffer + offset), sizeof(uint32_t));
00051       offset += 4;
00052       for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){
00053           inbuffer[k-1]=inbuffer[k];
00054       }
00055       inbuffer[offset+length_child_frame_id-1]=0;
00056       this->child_frame_id = (char *)(inbuffer + offset-1);
00057       offset += length_child_frame_id;
00058       offset += this->pose.deserialize(inbuffer + offset);
00059       offset += this->twist.deserialize(inbuffer + offset);
00060      return offset;
00061     }
00062 
00063     const char * getType(){ return "nav_msgs/Odometry"; };
00064     const char * getMD5(){ return "cd5e73d190d741a2f92e81eda573aca7"; };
00065 
00066   };
00067 
00068 }
00069 #endif