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_SERVICE_GetMapROI_h
garyservin 0:9e9b7db60fd5 2 #define _ROS_SERVICE_GetMapROI_h
garyservin 0:9e9b7db60fd5 3 #include <stdint.h>
garyservin 0:9e9b7db60fd5 4 #include <string.h>
garyservin 0:9e9b7db60fd5 5 #include <stdlib.h>
garyservin 0:9e9b7db60fd5 6 #include "ros/msg.h"
garyservin 0:9e9b7db60fd5 7 #include "nav_msgs/OccupancyGrid.h"
garyservin 0:9e9b7db60fd5 8
garyservin 0:9e9b7db60fd5 9 namespace map_msgs
garyservin 0:9e9b7db60fd5 10 {
garyservin 0:9e9b7db60fd5 11
garyservin 0:9e9b7db60fd5 12 static const char GETMAPROI[] = "map_msgs/GetMapROI";
garyservin 0:9e9b7db60fd5 13
garyservin 0:9e9b7db60fd5 14 class GetMapROIRequest : public ros::Msg
garyservin 0:9e9b7db60fd5 15 {
garyservin 0:9e9b7db60fd5 16 public:
garyservin 0:9e9b7db60fd5 17 typedef double _x_type;
garyservin 0:9e9b7db60fd5 18 _x_type x;
garyservin 0:9e9b7db60fd5 19 typedef double _y_type;
garyservin 0:9e9b7db60fd5 20 _y_type y;
garyservin 0:9e9b7db60fd5 21 typedef double _l_x_type;
garyservin 0:9e9b7db60fd5 22 _l_x_type l_x;
garyservin 0:9e9b7db60fd5 23 typedef double _l_y_type;
garyservin 0:9e9b7db60fd5 24 _l_y_type l_y;
garyservin 0:9e9b7db60fd5 25
garyservin 0:9e9b7db60fd5 26 GetMapROIRequest():
garyservin 0:9e9b7db60fd5 27 x(0),
garyservin 0:9e9b7db60fd5 28 y(0),
garyservin 0:9e9b7db60fd5 29 l_x(0),
garyservin 0:9e9b7db60fd5 30 l_y(0)
garyservin 0:9e9b7db60fd5 31 {
garyservin 0:9e9b7db60fd5 32 }
garyservin 0:9e9b7db60fd5 33
garyservin 0:9e9b7db60fd5 34 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 35 {
garyservin 0:9e9b7db60fd5 36 int offset = 0;
garyservin 0:9e9b7db60fd5 37 union {
garyservin 0:9e9b7db60fd5 38 double real;
garyservin 0:9e9b7db60fd5 39 uint64_t base;
garyservin 0:9e9b7db60fd5 40 } u_x;
garyservin 0:9e9b7db60fd5 41 u_x.real = this->x;
garyservin 0:9e9b7db60fd5 42 *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 43 *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 44 *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 45 *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 46 *(outbuffer + offset + 4) = (u_x.base >> (8 * 4)) & 0xFF;
garyservin 0:9e9b7db60fd5 47 *(outbuffer + offset + 5) = (u_x.base >> (8 * 5)) & 0xFF;
garyservin 0:9e9b7db60fd5 48 *(outbuffer + offset + 6) = (u_x.base >> (8 * 6)) & 0xFF;
garyservin 0:9e9b7db60fd5 49 *(outbuffer + offset + 7) = (u_x.base >> (8 * 7)) & 0xFF;
garyservin 0:9e9b7db60fd5 50 offset += sizeof(this->x);
garyservin 0:9e9b7db60fd5 51 union {
garyservin 0:9e9b7db60fd5 52 double real;
garyservin 0:9e9b7db60fd5 53 uint64_t base;
garyservin 0:9e9b7db60fd5 54 } u_y;
garyservin 0:9e9b7db60fd5 55 u_y.real = this->y;
garyservin 0:9e9b7db60fd5 56 *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 57 *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 58 *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 59 *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 60 *(outbuffer + offset + 4) = (u_y.base >> (8 * 4)) & 0xFF;
garyservin 0:9e9b7db60fd5 61 *(outbuffer + offset + 5) = (u_y.base >> (8 * 5)) & 0xFF;
garyservin 0:9e9b7db60fd5 62 *(outbuffer + offset + 6) = (u_y.base >> (8 * 6)) & 0xFF;
garyservin 0:9e9b7db60fd5 63 *(outbuffer + offset + 7) = (u_y.base >> (8 * 7)) & 0xFF;
garyservin 0:9e9b7db60fd5 64 offset += sizeof(this->y);
garyservin 0:9e9b7db60fd5 65 union {
garyservin 0:9e9b7db60fd5 66 double real;
garyservin 0:9e9b7db60fd5 67 uint64_t base;
garyservin 0:9e9b7db60fd5 68 } u_l_x;
garyservin 0:9e9b7db60fd5 69 u_l_x.real = this->l_x;
garyservin 0:9e9b7db60fd5 70 *(outbuffer + offset + 0) = (u_l_x.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 71 *(outbuffer + offset + 1) = (u_l_x.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 72 *(outbuffer + offset + 2) = (u_l_x.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 73 *(outbuffer + offset + 3) = (u_l_x.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 74 *(outbuffer + offset + 4) = (u_l_x.base >> (8 * 4)) & 0xFF;
garyservin 0:9e9b7db60fd5 75 *(outbuffer + offset + 5) = (u_l_x.base >> (8 * 5)) & 0xFF;
garyservin 0:9e9b7db60fd5 76 *(outbuffer + offset + 6) = (u_l_x.base >> (8 * 6)) & 0xFF;
garyservin 0:9e9b7db60fd5 77 *(outbuffer + offset + 7) = (u_l_x.base >> (8 * 7)) & 0xFF;
garyservin 0:9e9b7db60fd5 78 offset += sizeof(this->l_x);
garyservin 0:9e9b7db60fd5 79 union {
garyservin 0:9e9b7db60fd5 80 double real;
garyservin 0:9e9b7db60fd5 81 uint64_t base;
garyservin 0:9e9b7db60fd5 82 } u_l_y;
garyservin 0:9e9b7db60fd5 83 u_l_y.real = this->l_y;
garyservin 0:9e9b7db60fd5 84 *(outbuffer + offset + 0) = (u_l_y.base >> (8 * 0)) & 0xFF;
garyservin 0:9e9b7db60fd5 85 *(outbuffer + offset + 1) = (u_l_y.base >> (8 * 1)) & 0xFF;
garyservin 0:9e9b7db60fd5 86 *(outbuffer + offset + 2) = (u_l_y.base >> (8 * 2)) & 0xFF;
garyservin 0:9e9b7db60fd5 87 *(outbuffer + offset + 3) = (u_l_y.base >> (8 * 3)) & 0xFF;
garyservin 0:9e9b7db60fd5 88 *(outbuffer + offset + 4) = (u_l_y.base >> (8 * 4)) & 0xFF;
garyservin 0:9e9b7db60fd5 89 *(outbuffer + offset + 5) = (u_l_y.base >> (8 * 5)) & 0xFF;
garyservin 0:9e9b7db60fd5 90 *(outbuffer + offset + 6) = (u_l_y.base >> (8 * 6)) & 0xFF;
garyservin 0:9e9b7db60fd5 91 *(outbuffer + offset + 7) = (u_l_y.base >> (8 * 7)) & 0xFF;
garyservin 0:9e9b7db60fd5 92 offset += sizeof(this->l_y);
garyservin 0:9e9b7db60fd5 93 return offset;
garyservin 0:9e9b7db60fd5 94 }
garyservin 0:9e9b7db60fd5 95
garyservin 0:9e9b7db60fd5 96 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 97 {
garyservin 0:9e9b7db60fd5 98 int offset = 0;
garyservin 0:9e9b7db60fd5 99 union {
garyservin 0:9e9b7db60fd5 100 double real;
garyservin 0:9e9b7db60fd5 101 uint64_t base;
garyservin 0:9e9b7db60fd5 102 } u_x;
garyservin 0:9e9b7db60fd5 103 u_x.base = 0;
garyservin 0:9e9b7db60fd5 104 u_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 105 u_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 106 u_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 107 u_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 108 u_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:9e9b7db60fd5 109 u_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:9e9b7db60fd5 110 u_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:9e9b7db60fd5 111 u_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:9e9b7db60fd5 112 this->x = u_x.real;
garyservin 0:9e9b7db60fd5 113 offset += sizeof(this->x);
garyservin 0:9e9b7db60fd5 114 union {
garyservin 0:9e9b7db60fd5 115 double real;
garyservin 0:9e9b7db60fd5 116 uint64_t base;
garyservin 0:9e9b7db60fd5 117 } u_y;
garyservin 0:9e9b7db60fd5 118 u_y.base = 0;
garyservin 0:9e9b7db60fd5 119 u_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 120 u_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 121 u_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 122 u_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 123 u_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:9e9b7db60fd5 124 u_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:9e9b7db60fd5 125 u_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:9e9b7db60fd5 126 u_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:9e9b7db60fd5 127 this->y = u_y.real;
garyservin 0:9e9b7db60fd5 128 offset += sizeof(this->y);
garyservin 0:9e9b7db60fd5 129 union {
garyservin 0:9e9b7db60fd5 130 double real;
garyservin 0:9e9b7db60fd5 131 uint64_t base;
garyservin 0:9e9b7db60fd5 132 } u_l_x;
garyservin 0:9e9b7db60fd5 133 u_l_x.base = 0;
garyservin 0:9e9b7db60fd5 134 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 135 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 136 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 137 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 138 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:9e9b7db60fd5 139 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:9e9b7db60fd5 140 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:9e9b7db60fd5 141 u_l_x.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:9e9b7db60fd5 142 this->l_x = u_l_x.real;
garyservin 0:9e9b7db60fd5 143 offset += sizeof(this->l_x);
garyservin 0:9e9b7db60fd5 144 union {
garyservin 0:9e9b7db60fd5 145 double real;
garyservin 0:9e9b7db60fd5 146 uint64_t base;
garyservin 0:9e9b7db60fd5 147 } u_l_y;
garyservin 0:9e9b7db60fd5 148 u_l_y.base = 0;
garyservin 0:9e9b7db60fd5 149 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:9e9b7db60fd5 150 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:9e9b7db60fd5 151 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:9e9b7db60fd5 152 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:9e9b7db60fd5 153 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:9e9b7db60fd5 154 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:9e9b7db60fd5 155 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:9e9b7db60fd5 156 u_l_y.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:9e9b7db60fd5 157 this->l_y = u_l_y.real;
garyservin 0:9e9b7db60fd5 158 offset += sizeof(this->l_y);
garyservin 0:9e9b7db60fd5 159 return offset;
garyservin 0:9e9b7db60fd5 160 }
garyservin 0:9e9b7db60fd5 161
garyservin 0:9e9b7db60fd5 162 const char * getType(){ return GETMAPROI; };
garyservin 0:9e9b7db60fd5 163 const char * getMD5(){ return "43c2ff8f45af555c0eaf070c401e9a47"; };
garyservin 0:9e9b7db60fd5 164
garyservin 0:9e9b7db60fd5 165 };
garyservin 0:9e9b7db60fd5 166
garyservin 0:9e9b7db60fd5 167 class GetMapROIResponse : public ros::Msg
garyservin 0:9e9b7db60fd5 168 {
garyservin 0:9e9b7db60fd5 169 public:
garyservin 0:9e9b7db60fd5 170 typedef nav_msgs::OccupancyGrid _sub_map_type;
garyservin 0:9e9b7db60fd5 171 _sub_map_type sub_map;
garyservin 0:9e9b7db60fd5 172
garyservin 0:9e9b7db60fd5 173 GetMapROIResponse():
garyservin 0:9e9b7db60fd5 174 sub_map()
garyservin 0:9e9b7db60fd5 175 {
garyservin 0:9e9b7db60fd5 176 }
garyservin 0:9e9b7db60fd5 177
garyservin 0:9e9b7db60fd5 178 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:9e9b7db60fd5 179 {
garyservin 0:9e9b7db60fd5 180 int offset = 0;
garyservin 0:9e9b7db60fd5 181 offset += this->sub_map.serialize(outbuffer + offset);
garyservin 0:9e9b7db60fd5 182 return offset;
garyservin 0:9e9b7db60fd5 183 }
garyservin 0:9e9b7db60fd5 184
garyservin 0:9e9b7db60fd5 185 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:9e9b7db60fd5 186 {
garyservin 0:9e9b7db60fd5 187 int offset = 0;
garyservin 0:9e9b7db60fd5 188 offset += this->sub_map.deserialize(inbuffer + offset);
garyservin 0:9e9b7db60fd5 189 return offset;
garyservin 0:9e9b7db60fd5 190 }
garyservin 0:9e9b7db60fd5 191
garyservin 0:9e9b7db60fd5 192 const char * getType(){ return GETMAPROI; };
garyservin 0:9e9b7db60fd5 193 const char * getMD5(){ return "4d1986519c00d81967d2891a606b234c"; };
garyservin 0:9e9b7db60fd5 194
garyservin 0:9e9b7db60fd5 195 };
garyservin 0:9e9b7db60fd5 196
garyservin 0:9e9b7db60fd5 197 class GetMapROI {
garyservin 0:9e9b7db60fd5 198 public:
garyservin 0:9e9b7db60fd5 199 typedef GetMapROIRequest Request;
garyservin 0:9e9b7db60fd5 200 typedef GetMapROIResponse Response;
garyservin 0:9e9b7db60fd5 201 };
garyservin 0:9e9b7db60fd5 202
garyservin 0:9e9b7db60fd5 203 }
garyservin 0:9e9b7db60fd5 204 #endif