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

Dependencies:   BufferedSerial

Committer:
gosari
Date:
Thu Jan 27 11:36:16 2022 +0000
Revision:
2:65cba0dcf634
Parent:
0:9e9b7db60fd5
for message communication with mbed

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:9e9b7db60fd5 1 #ifndef _ROS_geometry_msgs_PoseWithCovariance_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_geometry_msgs_PoseWithCovariance_h
garyservin 0:9e9b7db60fd5 3
garyservin 0:9e9b7db60fd5 4 #include <stdint.h>
garyservin 0:9e9b7db60fd5 5 #include <string.h>
garyservin 0:9e9b7db60fd5 6 #include <stdlib.h>
garyservin 0:9e9b7db60fd5 7 #include "ros/msg.h"
garyservin 0:9e9b7db60fd5 8 #include "geometry_msgs/Pose.h"
garyservin 0:9e9b7db60fd5 9
garyservin 0:9e9b7db60fd5 10 namespace geometry_msgs
garyservin 0:9e9b7db60fd5 11 {
garyservin 0:9e9b7db60fd5 12
garyservin 0:9e9b7db60fd5 13 class PoseWithCovariance : public ros::Msg
garyservin 0:9e9b7db60fd5 14 {
garyservin 0:9e9b7db60fd5 15 public:
garyservin 0:9e9b7db60fd5 16 typedef geometry_msgs::Pose _pose_type;
garyservin 0:9e9b7db60fd5 17 _pose_type pose;
garyservin 0:9e9b7db60fd5 18 double covariance[36];
garyservin 0:9e9b7db60fd5 19
garyservin 0:9e9b7db60fd5 20 PoseWithCovariance():
garyservin 0:9e9b7db60fd5 21 pose(),
garyservin 0:9e9b7db60fd5 22 covariance()
garyservin 0:9e9b7db60fd5 23 {
garyservin 0:9e9b7db60fd5 24 }
garyservin 0:9e9b7db60fd5 25
garyservin 0:9e9b7db60fd5 26 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 27 {
garyservin 0:9e9b7db60fd5 28 int offset = 0;
garyservin 0:9e9b7db60fd5 29 offset += this->pose.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 30 for( uint32_t i = 0; i < 36; i++){
garyservin 0:9e9b7db60fd5 31 union {
garyservin 0:9e9b7db60fd5 32 double real;
garyservin 0:9e9b7db60fd5 33 uint64_t base;
garyservin 0:9e9b7db60fd5 34 } u_covariancei;
garyservin 0:9e9b7db60fd5 35 u_covariancei.real = this->covariance[i];
garyservin 0:9e9b7db60fd5 36 *(outbuffer + offset + 0) = (u_covariancei.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 37 *(outbuffer + offset + 1) = (u_covariancei.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 38 *(outbuffer + offset + 2) = (u_covariancei.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 39 *(outbuffer + offset + 3) = (u_covariancei.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 40 *(outbuffer + offset + 4) = (u_covariancei.base >> (8 * 4)) & 0xFF;
garyservin 0:9e9b7db60fd5 41 *(outbuffer + offset + 5) = (u_covariancei.base >> (8 * 5)) & 0xFF;
garyservin 0:9e9b7db60fd5 42 *(outbuffer + offset + 6) = (u_covariancei.base >> (8 * 6)) & 0xFF;
garyservin 0:9e9b7db60fd5 43 *(outbuffer + offset + 7) = (u_covariancei.base >> (8 * 7)) & 0xFF;
garyservin 0:9e9b7db60fd5 44 offset += sizeof(this->covariance[i]);
garyservin 0:9e9b7db60fd5 45 }
garyservin 0:9e9b7db60fd5 46 return offset;
garyservin 0:9e9b7db60fd5 47 }
garyservin 0:9e9b7db60fd5 48
garyservin 0:9e9b7db60fd5 49 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 50 {
garyservin 0:9e9b7db60fd5 51 int offset = 0;
garyservin 0:9e9b7db60fd5 52 offset += this->pose.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 53 for( uint32_t i = 0; i < 36; i++){
garyservin 0:9e9b7db60fd5 54 union {
garyservin 0:9e9b7db60fd5 55 double real;
garyservin 0:9e9b7db60fd5 56 uint64_t base;
garyservin 0:9e9b7db60fd5 57 } u_covariancei;
garyservin 0:9e9b7db60fd5 58 u_covariancei.base = 0;
garyservin 0:9e9b7db60fd5 59 u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 60 u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 61 u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 62 u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 63 u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:9e9b7db60fd5 64 u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:9e9b7db60fd5 65 u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:9e9b7db60fd5 66 u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:9e9b7db60fd5 67 this->covariance[i] = u_covariancei.real;
garyservin 0:9e9b7db60fd5 68 offset += sizeof(this->covariance[i]);
garyservin 0:9e9b7db60fd5 69 }
garyservin 0:9e9b7db60fd5 70 return offset;
garyservin 0:9e9b7db60fd5 71 }
garyservin 0:9e9b7db60fd5 72
garyservin 0:9e9b7db60fd5 73 const char * getType(){ return "geometry_msgs/PoseWithCovariance"; };
garyservin 0:9e9b7db60fd5 74 const char * getMD5(){ return "c23e848cf1b7533a8d7c259073a97e6f"; };
garyservin 0:9e9b7db60fd5 75
garyservin 0:9e9b7db60fd5 76 };
garyservin 0:9e9b7db60fd5 77
garyservin 0:9e9b7db60fd5 78 }
garyservin 0:9e9b7db60fd5 79 #endif