Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
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 typedef std_msgs::Header _header_type; 00019 _header_type header; 00020 typedef const char* _child_frame_id_type; 00021 _child_frame_id_type child_frame_id; 00022 typedef geometry_msgs::PoseWithCovariance _pose_type; 00023 _pose_type pose; 00024 typedef geometry_msgs::TwistWithCovariance _twist_type; 00025 _twist_type twist; 00026 00027 Odometry(): 00028 header(), 00029 child_frame_id(""), 00030 pose(), 00031 twist() 00032 { 00033 } 00034 00035 virtual int serialize(unsigned char *outbuffer) const 00036 { 00037 int offset = 0; 00038 offset += this->header.serialize(outbuffer + offset); 00039 uint32_t length_child_frame_id = strlen(this->child_frame_id); 00040 varToArr(outbuffer + offset, length_child_frame_id); 00041 offset += 4; 00042 memcpy(outbuffer + offset, this->child_frame_id, length_child_frame_id); 00043 offset += length_child_frame_id; 00044 offset += this->pose.serialize(outbuffer + offset); 00045 offset += this->twist.serialize(outbuffer + offset); 00046 return offset; 00047 } 00048 00049 virtual int deserialize(unsigned char *inbuffer) 00050 { 00051 int offset = 0; 00052 offset += this->header.deserialize(inbuffer + offset); 00053 uint32_t length_child_frame_id; 00054 arrToVar(length_child_frame_id, (inbuffer + offset)); 00055 offset += 4; 00056 for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){ 00057 inbuffer[k-1]=inbuffer[k]; 00058 } 00059 inbuffer[offset+length_child_frame_id-1]=0; 00060 this->child_frame_id = (char *)(inbuffer + offset-1); 00061 offset += length_child_frame_id; 00062 offset += this->pose.deserialize(inbuffer + offset); 00063 offset += this->twist.deserialize(inbuffer + offset); 00064 return offset; 00065 } 00066 00067 const char * getType(){ return "nav_msgs/Odometry"; }; 00068 const char * getMD5(){ return "cd5e73d190d741a2f92e81eda573aca7"; }; 00069 00070 }; 00071 00072 } 00073 #endif
Generated on Wed Jul 13 2022 23:30:18 by
