kitt_platform
 All Classes Namespaces Files Functions Variables Typedefs Enumerator Macros
Odometry.h
Go to the documentation of this file.
1 #ifndef _ROS_nav_msgs_Odometry_h
2 #define _ROS_nav_msgs_Odometry_h
3 
4 #include <stdint.h>
5 #include <string.h>
6 #include <stdlib.h>
7 #include "ros/msg.h"
8 #include "std_msgs/Header.h"
11 
12 namespace nav_msgs
13 {
14 
15  class Odometry : public ros::Msg
16  {
17  public:
19  const char* child_frame_id;
22 
24  header(),
25  child_frame_id(""),
26  pose(),
27  twist()
28  {
29  }
30 
31  virtual int serialize(unsigned char *outbuffer) const
32  {
33  int offset = 0;
34  offset += this->header.serialize(outbuffer + offset);
35  uint32_t length_child_frame_id = strlen(this->child_frame_id);
36  memcpy(outbuffer + offset, &length_child_frame_id, sizeof(uint32_t));
37  offset += 4;
38  memcpy(outbuffer + offset, this->child_frame_id, length_child_frame_id);
39  offset += length_child_frame_id;
40  offset += this->pose.serialize(outbuffer + offset);
41  offset += this->twist.serialize(outbuffer + offset);
42  return offset;
43  }
44 
45  virtual int deserialize(unsigned char *inbuffer)
46  {
47  int offset = 0;
48  offset += this->header.deserialize(inbuffer + offset);
49  uint32_t length_child_frame_id;
50  memcpy(&length_child_frame_id, (inbuffer + offset), sizeof(uint32_t));
51  offset += 4;
52  for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){
53  inbuffer[k-1]=inbuffer[k];
54  }
55  inbuffer[offset+length_child_frame_id-1]=0;
56  this->child_frame_id = (char *)(inbuffer + offset-1);
57  offset += length_child_frame_id;
58  offset += this->pose.deserialize(inbuffer + offset);
59  offset += this->twist.deserialize(inbuffer + offset);
60  return offset;
61  }
62 
63  const char * getType(){ return "nav_msgs/Odometry"; };
64  const char * getMD5(){ return "cd5e73d190d741a2f92e81eda573aca7"; };
65 
66  };
67 
68 }
69 #endif
virtual int deserialize(unsigned char *inbuffer)
Definition: Header.h:53
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
virtual int serialize(unsigned char *outbuffer) const
Definition: Header.h:27
Odometry()
Definition: Odometry.h:23
Definition: Header.h:13
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
Definition: msg.h:43
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