Odometry.h
Go to the documentation of this file.
1 #ifndef _ROS_rosabridge_msgs_Odometry_h
2 #define _ROS_rosabridge_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"
9 #include "rosabridge_msgs/Pose.h"
10 #include "rosabridge_msgs/Twist.h"
11 
12 namespace rosabridge_msgs
13 {
14 
15  class Odometry : public ros::Msg
16  {
17  public:
18  std_msgs::Header header;
19  const char* child_frame_id;
21  float pose_covariance[6];
23  float twist_covariance[6];
24 
25  virtual int serialize(unsigned char *outbuffer) const
26  {
27  int offset = 0;
28  offset += this->header.serialize(outbuffer + offset);
29  uint32_t length_child_frame_id = strlen(this->child_frame_id);
30  memcpy(outbuffer + offset, &length_child_frame_id, sizeof(uint32_t));
31  offset += 4;
32  memcpy(outbuffer + offset, this->child_frame_id, length_child_frame_id);
33  offset += length_child_frame_id;
34  offset += this->pose.serialize(outbuffer + offset);
35  for( uint8_t i = 0; i < 6; i++){
36  union {
37  float real;
38  uint32_t base;
39  } u_pose_covariancei;
40  u_pose_covariancei.real = this->pose_covariance[i];
41  *(outbuffer + offset + 0) = (u_pose_covariancei.base >> (8 * 0)) & 0xFF;
42  *(outbuffer + offset + 1) = (u_pose_covariancei.base >> (8 * 1)) & 0xFF;
43  *(outbuffer + offset + 2) = (u_pose_covariancei.base >> (8 * 2)) & 0xFF;
44  *(outbuffer + offset + 3) = (u_pose_covariancei.base >> (8 * 3)) & 0xFF;
45  offset += sizeof(this->pose_covariance[i]);
46  }
47  offset += this->twist.serialize(outbuffer + offset);
48  for( uint8_t i = 0; i < 6; i++){
49  union {
50  float real;
51  uint32_t base;
52  } u_twist_covariancei;
53  u_twist_covariancei.real = this->twist_covariance[i];
54  *(outbuffer + offset + 0) = (u_twist_covariancei.base >> (8 * 0)) & 0xFF;
55  *(outbuffer + offset + 1) = (u_twist_covariancei.base >> (8 * 1)) & 0xFF;
56  *(outbuffer + offset + 2) = (u_twist_covariancei.base >> (8 * 2)) & 0xFF;
57  *(outbuffer + offset + 3) = (u_twist_covariancei.base >> (8 * 3)) & 0xFF;
58  offset += sizeof(this->twist_covariance[i]);
59  }
60  return offset;
61  }
62 
63  virtual int deserialize(unsigned char *inbuffer)
64  {
65  int offset = 0;
66  offset += this->header.deserialize(inbuffer + offset);
67  uint32_t length_child_frame_id;
68  memcpy(&length_child_frame_id, (inbuffer + offset), sizeof(uint32_t));
69  offset += 4;
70  for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){
71  inbuffer[k-1]=inbuffer[k];
72  }
73  inbuffer[offset+length_child_frame_id-1]=0;
74  this->child_frame_id = (char *)(inbuffer + offset-1);
75  offset += length_child_frame_id;
76  offset += this->pose.deserialize(inbuffer + offset);
77  for( uint8_t i = 0; i < 6; i++){
78  union {
79  float real;
80  uint32_t base;
81  } u_pose_covariancei;
82  u_pose_covariancei.base = 0;
83  u_pose_covariancei.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
84  u_pose_covariancei.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
85  u_pose_covariancei.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
86  u_pose_covariancei.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
87  this->pose_covariance[i] = u_pose_covariancei.real;
88  offset += sizeof(this->pose_covariance[i]);
89  }
90  offset += this->twist.deserialize(inbuffer + offset);
91  for( uint8_t i = 0; i < 6; i++){
92  union {
93  float real;
94  uint32_t base;
95  } u_twist_covariancei;
96  u_twist_covariancei.base = 0;
97  u_twist_covariancei.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
98  u_twist_covariancei.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
99  u_twist_covariancei.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
100  u_twist_covariancei.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
101  this->twist_covariance[i] = u_twist_covariancei.real;
102  offset += sizeof(this->twist_covariance[i]);
103  }
104  return offset;
105  }
106 
107  const char * getType(){ return "rosabridge_msgs/Odometry"; };
108  const char * getMD5(){ return "3c88d21ba93f27fc21da1718473d3e4e"; };
109 
110  };
111 
112 }
113 #endif
virtual int serialize(unsigned char *outbuffer) const
Definition: Odometry.h:25
std_msgs::Header header
Definition: Odometry.h:18
virtual int deserialize(unsigned char *inbuffer)
Definition: Twist.h:27
rosabridge_msgs::Twist twist
Definition: Odometry.h:22
const char * getType()
Definition: Odometry.h:107
virtual int deserialize(unsigned char *inbuffer)
Definition: Pose.h:28
rosabridge_msgs::Pose pose
Definition: Odometry.h:20
const char * child_frame_id
Definition: Odometry.h:19
virtual int deserialize(unsigned char *inbuffer)
Definition: Odometry.h:63
virtual int serialize(unsigned char *outbuffer) const
Definition: Pose.h:20
const char * getMD5()
Definition: Odometry.h:108
virtual int serialize(unsigned char *outbuffer) const
Definition: Twist.h:19


rosabridge_arduino
Author(s): Chad Attermann
autogenerated on Sat Apr 10 2021 02:37:49