This is a fork from the original, including a small change in the buffer size of the hardware interface (increased to 2048) and decreasing the number of publishers and subscribers to 5. Besides, the library about the message Adc.h was modified so as to increase the number of available Adc channels to be read ( from 6 to 7 ) For this modification, a change in checksum was required

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Committer:
jacobepfl1692
Date:
Tue Oct 17 18:49:03 2017 +0000
Revision:
2:9114cc24ddcf
Parent:
0:9e9b7db60fd5
I increased the channels of the ADC to 6 (hence change in checksum) because my application needed it (STM32f407V6)

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:9e9b7db60fd5 1 #ifndef _ROS_geometry_msgs_Point32_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_geometry_msgs_Point32_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
garyservin 0:9e9b7db60fd5 9 namespace geometry_msgs
garyservin 0:9e9b7db60fd5 10 {
garyservin 0:9e9b7db60fd5 11
garyservin 0:9e9b7db60fd5 12 class Point32 : public ros::Msg
garyservin 0:9e9b7db60fd5 13 {
garyservin 0:9e9b7db60fd5 14 public:
garyservin 0:9e9b7db60fd5 15 typedef float _x_type;
garyservin 0:9e9b7db60fd5 16 _x_type x;
garyservin 0:9e9b7db60fd5 17 typedef float _y_type;
garyservin 0:9e9b7db60fd5 18 _y_type y;
garyservin 0:9e9b7db60fd5 19 typedef float _z_type;
garyservin 0:9e9b7db60fd5 20 _z_type z;
garyservin 0:9e9b7db60fd5 21
garyservin 0:9e9b7db60fd5 22 Point32():
garyservin 0:9e9b7db60fd5 23 x(0),
garyservin 0:9e9b7db60fd5 24 y(0),
garyservin 0:9e9b7db60fd5 25 z(0)
garyservin 0:9e9b7db60fd5 26 {
garyservin 0:9e9b7db60fd5 27 }
garyservin 0:9e9b7db60fd5 28
garyservin 0:9e9b7db60fd5 29 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 30 {
garyservin 0:9e9b7db60fd5 31 int offset = 0;
garyservin 0:9e9b7db60fd5 32 union {
garyservin 0:9e9b7db60fd5 33 float real;
garyservin 0:9e9b7db60fd5 34 uint32_t base;
garyservin 0:9e9b7db60fd5 35 } u_x;
garyservin 0:9e9b7db60fd5 36 u_x.real = this->x;
garyservin 0:9e9b7db60fd5 37 *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 38 *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 39 *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 40 *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 41 offset += sizeof(this->x);
garyservin 0:9e9b7db60fd5 42 union {
garyservin 0:9e9b7db60fd5 43 float real;
garyservin 0:9e9b7db60fd5 44 uint32_t base;
garyservin 0:9e9b7db60fd5 45 } u_y;
garyservin 0:9e9b7db60fd5 46 u_y.real = this->y;
garyservin 0:9e9b7db60fd5 47 *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 48 *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 49 *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 50 *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 51 offset += sizeof(this->y);
garyservin 0:9e9b7db60fd5 52 union {
garyservin 0:9e9b7db60fd5 53 float real;
garyservin 0:9e9b7db60fd5 54 uint32_t base;
garyservin 0:9e9b7db60fd5 55 } u_z;
garyservin 0:9e9b7db60fd5 56 u_z.real = this->z;
garyservin 0:9e9b7db60fd5 57 *(outbuffer + offset + 0) = (u_z.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 58 *(outbuffer + offset + 1) = (u_z.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 59 *(outbuffer + offset + 2) = (u_z.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 60 *(outbuffer + offset + 3) = (u_z.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 61 offset += sizeof(this->z);
garyservin 0:9e9b7db60fd5 62 return offset;
garyservin 0:9e9b7db60fd5 63 }
garyservin 0:9e9b7db60fd5 64
garyservin 0:9e9b7db60fd5 65 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 66 {
garyservin 0:9e9b7db60fd5 67 int offset = 0;
garyservin 0:9e9b7db60fd5 68 union {
garyservin 0:9e9b7db60fd5 69 float real;
garyservin 0:9e9b7db60fd5 70 uint32_t base;
garyservin 0:9e9b7db60fd5 71 } u_x;
garyservin 0:9e9b7db60fd5 72 u_x.base = 0;
garyservin 0:9e9b7db60fd5 73 u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 74 u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 75 u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 76 u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 77 this->x = u_x.real;
garyservin 0:9e9b7db60fd5 78 offset += sizeof(this->x);
garyservin 0:9e9b7db60fd5 79 union {
garyservin 0:9e9b7db60fd5 80 float real;
garyservin 0:9e9b7db60fd5 81 uint32_t base;
garyservin 0:9e9b7db60fd5 82 } u_y;
garyservin 0:9e9b7db60fd5 83 u_y.base = 0;
garyservin 0:9e9b7db60fd5 84 u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 85 u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 86 u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 87 u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 88 this->y = u_y.real;
garyservin 0:9e9b7db60fd5 89 offset += sizeof(this->y);
garyservin 0:9e9b7db60fd5 90 union {
garyservin 0:9e9b7db60fd5 91 float real;
garyservin 0:9e9b7db60fd5 92 uint32_t base;
garyservin 0:9e9b7db60fd5 93 } u_z;
garyservin 0:9e9b7db60fd5 94 u_z.base = 0;
garyservin 0:9e9b7db60fd5 95 u_z.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 96 u_z.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 97 u_z.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 98 u_z.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 99 this->z = u_z.real;
garyservin 0:9e9b7db60fd5 100 offset += sizeof(this->z);
garyservin 0:9e9b7db60fd5 101 return offset;
garyservin 0:9e9b7db60fd5 102 }
garyservin 0:9e9b7db60fd5 103
garyservin 0:9e9b7db60fd5 104 const char * getType(){ return "geometry_msgs/Point32"; };
garyservin 0:9e9b7db60fd5 105 const char * getMD5(){ return "cc153912f1453b708d221682bc23d9ac"; };
garyservin 0:9e9b7db60fd5 106
garyservin 0:9e9b7db60fd5 107 };
garyservin 0:9e9b7db60fd5 108
garyservin 0:9e9b7db60fd5 109 }
garyservin 0:9e9b7db60fd5 110 #endif