1 #ifndef _ROS_nav_msgs_Odometry_h
2 #define _ROS_nav_msgs_Odometry_h
31 virtual int serialize(
unsigned char *outbuffer)
const
36 memcpy(outbuffer + offset, &length_child_frame_id,
sizeof(uint32_t));
38 memcpy(outbuffer + offset, this->
child_frame_id, length_child_frame_id);
39 offset += length_child_frame_id;
49 uint32_t length_child_frame_id;
50 memcpy(&length_child_frame_id, (inbuffer + offset),
sizeof(uint32_t));
52 for(
unsigned int k= offset; k< offset+length_child_frame_id; ++k){
53 inbuffer[k-1]=inbuffer[k];
55 inbuffer[offset+length_child_frame_id-1]=0;
57 offset += length_child_frame_id;
63 const char *
getType(){
return "nav_msgs/Odometry"; };
64 const char *
getMD5(){
return "cd5e73d190d741a2f92e81eda573aca7"; };
virtual int deserialize(unsigned char *inbuffer)
Definition: TwistWithCovariance.h:35
virtual int deserialize(unsigned char *inbuffer)
Definition: Odometry.h:45
virtual int serialize(unsigned char *outbuffer) const
Definition: TwistWithCovariance.h:25
geometry_msgs::PoseWithCovariance pose
Definition: Odometry.h:20
geometry_msgs::TwistWithCovariance twist
Definition: Odometry.h:21
const char * getType()
Definition: Odometry.h:63
Definition: TwistWithCovariance.h:13
Odometry()
Definition: Odometry.h:23
Definition: PoseWithCovariance.h:13
virtual int deserialize(unsigned char *inbuffer)
Definition: PoseWithCovariance.h:35
const char * child_frame_id
Definition: Odometry.h:19
std_msgs::Header header
Definition: Odometry.h:18
const char * getMD5()
Definition: Odometry.h:64
virtual int serialize(unsigned char *outbuffer) const
Definition: PoseWithCovariance.h:25
Definition: Odometry.h:15
virtual int serialize(unsigned char *outbuffer) const
Definition: Odometry.h:31