It has only one change from original one. I added robotfeedback message on it.

Dependencies:   BufferedSerial

Dependents:   RobotFeedback mobileRobotITU

Fork of ros_lib_indigo by Gary Servin

Committer:
garyservin
Date:
Thu Mar 31 14:22:59 2016 +0000
Revision:
0:fd24f7ca9688
Initial commit, generated based on a clean indigo-desktop-full

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:fd24f7ca9688 1 #ifndef _ROS_map_msgs_ProjectedMap_h
garyservin 0:fd24f7ca9688 2 #define _ROS_map_msgs_ProjectedMap_h
garyservin 0:fd24f7ca9688 3
garyservin 0:fd24f7ca9688 4 #include <stdint.h>
garyservin 0:fd24f7ca9688 5 #include <string.h>
garyservin 0:fd24f7ca9688 6 #include <stdlib.h>
garyservin 0:fd24f7ca9688 7 #include "ros/msg.h"
garyservin 0:fd24f7ca9688 8 #include "nav_msgs/OccupancyGrid.h"
garyservin 0:fd24f7ca9688 9
garyservin 0:fd24f7ca9688 10 namespace map_msgs
garyservin 0:fd24f7ca9688 11 {
garyservin 0:fd24f7ca9688 12
garyservin 0:fd24f7ca9688 13 class ProjectedMap : public ros::Msg
garyservin 0:fd24f7ca9688 14 {
garyservin 0:fd24f7ca9688 15 public:
garyservin 0:fd24f7ca9688 16 nav_msgs::OccupancyGrid map;
garyservin 0:fd24f7ca9688 17 double min_z;
garyservin 0:fd24f7ca9688 18 double max_z;
garyservin 0:fd24f7ca9688 19
garyservin 0:fd24f7ca9688 20 ProjectedMap():
garyservin 0:fd24f7ca9688 21 map(),
garyservin 0:fd24f7ca9688 22 min_z(0),
garyservin 0:fd24f7ca9688 23 max_z(0)
garyservin 0:fd24f7ca9688 24 {
garyservin 0:fd24f7ca9688 25 }
garyservin 0:fd24f7ca9688 26
garyservin 0:fd24f7ca9688 27 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 28 {
garyservin 0:fd24f7ca9688 29 int offset = 0;
garyservin 0:fd24f7ca9688 30 offset += this->map.serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 31 union {
garyservin 0:fd24f7ca9688 32 double real;
garyservin 0:fd24f7ca9688 33 uint64_t base;
garyservin 0:fd24f7ca9688 34 } u_min_z;
garyservin 0:fd24f7ca9688 35 u_min_z.real = this->min_z;
garyservin 0:fd24f7ca9688 36 *(outbuffer + offset + 0) = (u_min_z.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 37 *(outbuffer + offset + 1) = (u_min_z.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 38 *(outbuffer + offset + 2) = (u_min_z.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 39 *(outbuffer + offset + 3) = (u_min_z.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 40 *(outbuffer + offset + 4) = (u_min_z.base >> (8 * 4)) & 0xFF;
garyservin 0:fd24f7ca9688 41 *(outbuffer + offset + 5) = (u_min_z.base >> (8 * 5)) & 0xFF;
garyservin 0:fd24f7ca9688 42 *(outbuffer + offset + 6) = (u_min_z.base >> (8 * 6)) & 0xFF;
garyservin 0:fd24f7ca9688 43 *(outbuffer + offset + 7) = (u_min_z.base >> (8 * 7)) & 0xFF;
garyservin 0:fd24f7ca9688 44 offset += sizeof(this->min_z);
garyservin 0:fd24f7ca9688 45 union {
garyservin 0:fd24f7ca9688 46 double real;
garyservin 0:fd24f7ca9688 47 uint64_t base;
garyservin 0:fd24f7ca9688 48 } u_max_z;
garyservin 0:fd24f7ca9688 49 u_max_z.real = this->max_z;
garyservin 0:fd24f7ca9688 50 *(outbuffer + offset + 0) = (u_max_z.base >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 51 *(outbuffer + offset + 1) = (u_max_z.base >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 52 *(outbuffer + offset + 2) = (u_max_z.base >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 53 *(outbuffer + offset + 3) = (u_max_z.base >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 54 *(outbuffer + offset + 4) = (u_max_z.base >> (8 * 4)) & 0xFF;
garyservin 0:fd24f7ca9688 55 *(outbuffer + offset + 5) = (u_max_z.base >> (8 * 5)) & 0xFF;
garyservin 0:fd24f7ca9688 56 *(outbuffer + offset + 6) = (u_max_z.base >> (8 * 6)) & 0xFF;
garyservin 0:fd24f7ca9688 57 *(outbuffer + offset + 7) = (u_max_z.base >> (8 * 7)) & 0xFF;
garyservin 0:fd24f7ca9688 58 offset += sizeof(this->max_z);
garyservin 0:fd24f7ca9688 59 return offset;
garyservin 0:fd24f7ca9688 60 }
garyservin 0:fd24f7ca9688 61
garyservin 0:fd24f7ca9688 62 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 63 {
garyservin 0:fd24f7ca9688 64 int offset = 0;
garyservin 0:fd24f7ca9688 65 offset += this->map.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 66 union {
garyservin 0:fd24f7ca9688 67 double real;
garyservin 0:fd24f7ca9688 68 uint64_t base;
garyservin 0:fd24f7ca9688 69 } u_min_z;
garyservin 0:fd24f7ca9688 70 u_min_z.base = 0;
garyservin 0:fd24f7ca9688 71 u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 72 u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 73 u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 74 u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 75 u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:fd24f7ca9688 76 u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:fd24f7ca9688 77 u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:fd24f7ca9688 78 u_min_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:fd24f7ca9688 79 this->min_z = u_min_z.real;
garyservin 0:fd24f7ca9688 80 offset += sizeof(this->min_z);
garyservin 0:fd24f7ca9688 81 union {
garyservin 0:fd24f7ca9688 82 double real;
garyservin 0:fd24f7ca9688 83 uint64_t base;
garyservin 0:fd24f7ca9688 84 } u_max_z;
garyservin 0:fd24f7ca9688 85 u_max_z.base = 0;
garyservin 0:fd24f7ca9688 86 u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
garyservin 0:fd24f7ca9688 87 u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 88 u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 89 u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 90 u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
garyservin 0:fd24f7ca9688 91 u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
garyservin 0:fd24f7ca9688 92 u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
garyservin 0:fd24f7ca9688 93 u_max_z.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
garyservin 0:fd24f7ca9688 94 this->max_z = u_max_z.real;
garyservin 0:fd24f7ca9688 95 offset += sizeof(this->max_z);
garyservin 0:fd24f7ca9688 96 return offset;
garyservin 0:fd24f7ca9688 97 }
garyservin 0:fd24f7ca9688 98
garyservin 0:fd24f7ca9688 99 const char * getType(){ return "map_msgs/ProjectedMap"; };
garyservin 0:fd24f7ca9688 100 const char * getMD5(){ return "7bbe8f96e45089681dc1ea7d023cbfca"; };
garyservin 0:fd24f7ca9688 101
garyservin 0:fd24f7ca9688 102 };
garyservin 0:fd24f7ca9688 103
garyservin 0:fd24f7ca9688 104 }
garyservin 0:fd24f7ca9688 105 #endif