rosserial library for mbed Inspired by nucho's rosserial library This library is still under development

Dependencies:   MODSERIAL mbed

Dependents:   mbed_roshydro_test

Library still under development!

Committer:
akashvibhute
Date:
Sun Feb 15 10:53:43 2015 +0000
Revision:
0:30537dec6e0b
First commit; Library still need to be debugged, compilation issues with new mbed and modserial updates.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
akashvibhute 0:30537dec6e0b 1 #ifndef _ROS_stereo_msgs_DisparityImage_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_stereo_msgs_DisparityImage_h
akashvibhute 0:30537dec6e0b 3
akashvibhute 0:30537dec6e0b 4 #include <stdint.h>
akashvibhute 0:30537dec6e0b 5 #include <string.h>
akashvibhute 0:30537dec6e0b 6 #include <stdlib.h>
akashvibhute 0:30537dec6e0b 7 #include "ros/msg.h"
akashvibhute 0:30537dec6e0b 8 #include "std_msgs/Header.h"
akashvibhute 0:30537dec6e0b 9 #include "sensor_msgs/Image.h"
akashvibhute 0:30537dec6e0b 10 #include "sensor_msgs/RegionOfInterest.h"
akashvibhute 0:30537dec6e0b 11
akashvibhute 0:30537dec6e0b 12 namespace stereo_msgs
akashvibhute 0:30537dec6e0b 13 {
akashvibhute 0:30537dec6e0b 14
akashvibhute 0:30537dec6e0b 15 class DisparityImage : public ros::Msg
akashvibhute 0:30537dec6e0b 16 {
akashvibhute 0:30537dec6e0b 17 public:
akashvibhute 0:30537dec6e0b 18 std_msgs::Header header;
akashvibhute 0:30537dec6e0b 19 sensor_msgs::Image image;
akashvibhute 0:30537dec6e0b 20 float f;
akashvibhute 0:30537dec6e0b 21 float T;
akashvibhute 0:30537dec6e0b 22 sensor_msgs::RegionOfInterest valid_window;
akashvibhute 0:30537dec6e0b 23 float min_disparity;
akashvibhute 0:30537dec6e0b 24 float max_disparity;
akashvibhute 0:30537dec6e0b 25 float delta_d;
akashvibhute 0:30537dec6e0b 26
akashvibhute 0:30537dec6e0b 27 DisparityImage():
akashvibhute 0:30537dec6e0b 28 header(),
akashvibhute 0:30537dec6e0b 29 image(),
akashvibhute 0:30537dec6e0b 30 f(0),
akashvibhute 0:30537dec6e0b 31 T(0),
akashvibhute 0:30537dec6e0b 32 valid_window(),
akashvibhute 0:30537dec6e0b 33 min_disparity(0),
akashvibhute 0:30537dec6e0b 34 max_disparity(0),
akashvibhute 0:30537dec6e0b 35 delta_d(0)
akashvibhute 0:30537dec6e0b 36 {
akashvibhute 0:30537dec6e0b 37 }
akashvibhute 0:30537dec6e0b 38
akashvibhute 0:30537dec6e0b 39 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 40 {
akashvibhute 0:30537dec6e0b 41 int offset = 0;
akashvibhute 0:30537dec6e0b 42 offset += this->header.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 43 offset += this->image.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 44 union {
akashvibhute 0:30537dec6e0b 45 float real;
akashvibhute 0:30537dec6e0b 46 uint32_t base;
akashvibhute 0:30537dec6e0b 47 } u_f;
akashvibhute 0:30537dec6e0b 48 u_f.real = this->f;
akashvibhute 0:30537dec6e0b 49 *(outbuffer + offset + 0) = (u_f.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 50 *(outbuffer + offset + 1) = (u_f.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 51 *(outbuffer + offset + 2) = (u_f.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 52 *(outbuffer + offset + 3) = (u_f.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 53 offset += sizeof(this->f);
akashvibhute 0:30537dec6e0b 54 union {
akashvibhute 0:30537dec6e0b 55 float real;
akashvibhute 0:30537dec6e0b 56 uint32_t base;
akashvibhute 0:30537dec6e0b 57 } u_T;
akashvibhute 0:30537dec6e0b 58 u_T.real = this->T;
akashvibhute 0:30537dec6e0b 59 *(outbuffer + offset + 0) = (u_T.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 60 *(outbuffer + offset + 1) = (u_T.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 61 *(outbuffer + offset + 2) = (u_T.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 62 *(outbuffer + offset + 3) = (u_T.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 63 offset += sizeof(this->T);
akashvibhute 0:30537dec6e0b 64 offset += this->valid_window.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 65 union {
akashvibhute 0:30537dec6e0b 66 float real;
akashvibhute 0:30537dec6e0b 67 uint32_t base;
akashvibhute 0:30537dec6e0b 68 } u_min_disparity;
akashvibhute 0:30537dec6e0b 69 u_min_disparity.real = this->min_disparity;
akashvibhute 0:30537dec6e0b 70 *(outbuffer + offset + 0) = (u_min_disparity.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 71 *(outbuffer + offset + 1) = (u_min_disparity.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 72 *(outbuffer + offset + 2) = (u_min_disparity.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 73 *(outbuffer + offset + 3) = (u_min_disparity.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 74 offset += sizeof(this->min_disparity);
akashvibhute 0:30537dec6e0b 75 union {
akashvibhute 0:30537dec6e0b 76 float real;
akashvibhute 0:30537dec6e0b 77 uint32_t base;
akashvibhute 0:30537dec6e0b 78 } u_max_disparity;
akashvibhute 0:30537dec6e0b 79 u_max_disparity.real = this->max_disparity;
akashvibhute 0:30537dec6e0b 80 *(outbuffer + offset + 0) = (u_max_disparity.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 81 *(outbuffer + offset + 1) = (u_max_disparity.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 82 *(outbuffer + offset + 2) = (u_max_disparity.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 83 *(outbuffer + offset + 3) = (u_max_disparity.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 84 offset += sizeof(this->max_disparity);
akashvibhute 0:30537dec6e0b 85 union {
akashvibhute 0:30537dec6e0b 86 float real;
akashvibhute 0:30537dec6e0b 87 uint32_t base;
akashvibhute 0:30537dec6e0b 88 } u_delta_d;
akashvibhute 0:30537dec6e0b 89 u_delta_d.real = this->delta_d;
akashvibhute 0:30537dec6e0b 90 *(outbuffer + offset + 0) = (u_delta_d.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 91 *(outbuffer + offset + 1) = (u_delta_d.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 92 *(outbuffer + offset + 2) = (u_delta_d.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 93 *(outbuffer + offset + 3) = (u_delta_d.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 94 offset += sizeof(this->delta_d);
akashvibhute 0:30537dec6e0b 95 return offset;
akashvibhute 0:30537dec6e0b 96 }
akashvibhute 0:30537dec6e0b 97
akashvibhute 0:30537dec6e0b 98 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 99 {
akashvibhute 0:30537dec6e0b 100 int offset = 0;
akashvibhute 0:30537dec6e0b 101 offset += this->header.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 102 offset += this->image.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 103 union {
akashvibhute 0:30537dec6e0b 104 float real;
akashvibhute 0:30537dec6e0b 105 uint32_t base;
akashvibhute 0:30537dec6e0b 106 } u_f;
akashvibhute 0:30537dec6e0b 107 u_f.base = 0;
akashvibhute 0:30537dec6e0b 108 u_f.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 109 u_f.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 110 u_f.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 111 u_f.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 112 this->f = u_f.real;
akashvibhute 0:30537dec6e0b 113 offset += sizeof(this->f);
akashvibhute 0:30537dec6e0b 114 union {
akashvibhute 0:30537dec6e0b 115 float real;
akashvibhute 0:30537dec6e0b 116 uint32_t base;
akashvibhute 0:30537dec6e0b 117 } u_T;
akashvibhute 0:30537dec6e0b 118 u_T.base = 0;
akashvibhute 0:30537dec6e0b 119 u_T.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 120 u_T.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 121 u_T.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 122 u_T.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 123 this->T = u_T.real;
akashvibhute 0:30537dec6e0b 124 offset += sizeof(this->T);
akashvibhute 0:30537dec6e0b 125 offset += this->valid_window.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 126 union {
akashvibhute 0:30537dec6e0b 127 float real;
akashvibhute 0:30537dec6e0b 128 uint32_t base;
akashvibhute 0:30537dec6e0b 129 } u_min_disparity;
akashvibhute 0:30537dec6e0b 130 u_min_disparity.base = 0;
akashvibhute 0:30537dec6e0b 131 u_min_disparity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 132 u_min_disparity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 133 u_min_disparity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 134 u_min_disparity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 135 this->min_disparity = u_min_disparity.real;
akashvibhute 0:30537dec6e0b 136 offset += sizeof(this->min_disparity);
akashvibhute 0:30537dec6e0b 137 union {
akashvibhute 0:30537dec6e0b 138 float real;
akashvibhute 0:30537dec6e0b 139 uint32_t base;
akashvibhute 0:30537dec6e0b 140 } u_max_disparity;
akashvibhute 0:30537dec6e0b 141 u_max_disparity.base = 0;
akashvibhute 0:30537dec6e0b 142 u_max_disparity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 143 u_max_disparity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 144 u_max_disparity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 145 u_max_disparity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 146 this->max_disparity = u_max_disparity.real;
akashvibhute 0:30537dec6e0b 147 offset += sizeof(this->max_disparity);
akashvibhute 0:30537dec6e0b 148 union {
akashvibhute 0:30537dec6e0b 149 float real;
akashvibhute 0:30537dec6e0b 150 uint32_t base;
akashvibhute 0:30537dec6e0b 151 } u_delta_d;
akashvibhute 0:30537dec6e0b 152 u_delta_d.base = 0;
akashvibhute 0:30537dec6e0b 153 u_delta_d.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 154 u_delta_d.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 155 u_delta_d.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 156 u_delta_d.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 157 this->delta_d = u_delta_d.real;
akashvibhute 0:30537dec6e0b 158 offset += sizeof(this->delta_d);
akashvibhute 0:30537dec6e0b 159 return offset;
akashvibhute 0:30537dec6e0b 160 }
akashvibhute 0:30537dec6e0b 161
akashvibhute 0:30537dec6e0b 162 const char * getType(){ return "stereo_msgs/DisparityImage"; };
akashvibhute 0:30537dec6e0b 163 const char * getMD5(){ return "04a177815f75271039fa21f16acad8c9"; };
akashvibhute 0:30537dec6e0b 164
akashvibhute 0:30537dec6e0b 165 };
akashvibhute 0:30537dec6e0b 166
akashvibhute 0:30537dec6e0b 167 }
akashvibhute 0:30537dec6e0b 168 #endif