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_sensor_msgs_Range_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_sensor_msgs_Range_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
akashvibhute 0:30537dec6e0b 10 namespace sensor_msgs
akashvibhute 0:30537dec6e0b 11 {
akashvibhute 0:30537dec6e0b 12
akashvibhute 0:30537dec6e0b 13 class Range : public ros::Msg
akashvibhute 0:30537dec6e0b 14 {
akashvibhute 0:30537dec6e0b 15 public:
akashvibhute 0:30537dec6e0b 16 std_msgs::Header header;
akashvibhute 0:30537dec6e0b 17 uint8_t radiation_type;
akashvibhute 0:30537dec6e0b 18 float field_of_view;
akashvibhute 0:30537dec6e0b 19 float min_range;
akashvibhute 0:30537dec6e0b 20 float max_range;
akashvibhute 0:30537dec6e0b 21 float range;
akashvibhute 0:30537dec6e0b 22 enum { ULTRASOUND = 0 };
akashvibhute 0:30537dec6e0b 23 enum { INFRARED = 1 };
akashvibhute 0:30537dec6e0b 24
akashvibhute 0:30537dec6e0b 25 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 26 {
akashvibhute 0:30537dec6e0b 27 int offset = 0;
akashvibhute 0:30537dec6e0b 28 offset += this->header.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 29 *(outbuffer + offset + 0) = (this->radiation_type >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 30 offset += sizeof(this->radiation_type);
akashvibhute 0:30537dec6e0b 31 union {
akashvibhute 0:30537dec6e0b 32 float real;
akashvibhute 0:30537dec6e0b 33 uint32_t base;
akashvibhute 0:30537dec6e0b 34 } u_field_of_view;
akashvibhute 0:30537dec6e0b 35 u_field_of_view.real = this->field_of_view;
akashvibhute 0:30537dec6e0b 36 *(outbuffer + offset + 0) = (u_field_of_view.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 37 *(outbuffer + offset + 1) = (u_field_of_view.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 38 *(outbuffer + offset + 2) = (u_field_of_view.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 39 *(outbuffer + offset + 3) = (u_field_of_view.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 40 offset += sizeof(this->field_of_view);
akashvibhute 0:30537dec6e0b 41 union {
akashvibhute 0:30537dec6e0b 42 float real;
akashvibhute 0:30537dec6e0b 43 uint32_t base;
akashvibhute 0:30537dec6e0b 44 } u_min_range;
akashvibhute 0:30537dec6e0b 45 u_min_range.real = this->min_range;
akashvibhute 0:30537dec6e0b 46 *(outbuffer + offset + 0) = (u_min_range.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 47 *(outbuffer + offset + 1) = (u_min_range.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 48 *(outbuffer + offset + 2) = (u_min_range.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 49 *(outbuffer + offset + 3) = (u_min_range.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 50 offset += sizeof(this->min_range);
akashvibhute 0:30537dec6e0b 51 union {
akashvibhute 0:30537dec6e0b 52 float real;
akashvibhute 0:30537dec6e0b 53 uint32_t base;
akashvibhute 0:30537dec6e0b 54 } u_max_range;
akashvibhute 0:30537dec6e0b 55 u_max_range.real = this->max_range;
akashvibhute 0:30537dec6e0b 56 *(outbuffer + offset + 0) = (u_max_range.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 57 *(outbuffer + offset + 1) = (u_max_range.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 58 *(outbuffer + offset + 2) = (u_max_range.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 59 *(outbuffer + offset + 3) = (u_max_range.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 60 offset += sizeof(this->max_range);
akashvibhute 0:30537dec6e0b 61 union {
akashvibhute 0:30537dec6e0b 62 float real;
akashvibhute 0:30537dec6e0b 63 uint32_t base;
akashvibhute 0:30537dec6e0b 64 } u_range;
akashvibhute 0:30537dec6e0b 65 u_range.real = this->range;
akashvibhute 0:30537dec6e0b 66 *(outbuffer + offset + 0) = (u_range.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 67 *(outbuffer + offset + 1) = (u_range.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 68 *(outbuffer + offset + 2) = (u_range.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 69 *(outbuffer + offset + 3) = (u_range.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 70 offset += sizeof(this->range);
akashvibhute 0:30537dec6e0b 71 return offset;
akashvibhute 0:30537dec6e0b 72 }
akashvibhute 0:30537dec6e0b 73
akashvibhute 0:30537dec6e0b 74 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 75 {
akashvibhute 0:30537dec6e0b 76 int offset = 0;
akashvibhute 0:30537dec6e0b 77 offset += this->header.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 78 this->radiation_type |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 79 offset += sizeof(this->radiation_type);
akashvibhute 0:30537dec6e0b 80 union {
akashvibhute 0:30537dec6e0b 81 float real;
akashvibhute 0:30537dec6e0b 82 uint32_t base;
akashvibhute 0:30537dec6e0b 83 } u_field_of_view;
akashvibhute 0:30537dec6e0b 84 u_field_of_view.base = 0;
akashvibhute 0:30537dec6e0b 85 u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 86 u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 87 u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 88 u_field_of_view.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 89 this->field_of_view = u_field_of_view.real;
akashvibhute 0:30537dec6e0b 90 offset += sizeof(this->field_of_view);
akashvibhute 0:30537dec6e0b 91 union {
akashvibhute 0:30537dec6e0b 92 float real;
akashvibhute 0:30537dec6e0b 93 uint32_t base;
akashvibhute 0:30537dec6e0b 94 } u_min_range;
akashvibhute 0:30537dec6e0b 95 u_min_range.base = 0;
akashvibhute 0:30537dec6e0b 96 u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 97 u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 98 u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 99 u_min_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 100 this->min_range = u_min_range.real;
akashvibhute 0:30537dec6e0b 101 offset += sizeof(this->min_range);
akashvibhute 0:30537dec6e0b 102 union {
akashvibhute 0:30537dec6e0b 103 float real;
akashvibhute 0:30537dec6e0b 104 uint32_t base;
akashvibhute 0:30537dec6e0b 105 } u_max_range;
akashvibhute 0:30537dec6e0b 106 u_max_range.base = 0;
akashvibhute 0:30537dec6e0b 107 u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 108 u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 109 u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 110 u_max_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 111 this->max_range = u_max_range.real;
akashvibhute 0:30537dec6e0b 112 offset += sizeof(this->max_range);
akashvibhute 0:30537dec6e0b 113 union {
akashvibhute 0:30537dec6e0b 114 float real;
akashvibhute 0:30537dec6e0b 115 uint32_t base;
akashvibhute 0:30537dec6e0b 116 } u_range;
akashvibhute 0:30537dec6e0b 117 u_range.base = 0;
akashvibhute 0:30537dec6e0b 118 u_range.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 119 u_range.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 120 u_range.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 121 u_range.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 122 this->range = u_range.real;
akashvibhute 0:30537dec6e0b 123 offset += sizeof(this->range);
akashvibhute 0:30537dec6e0b 124 return offset;
akashvibhute 0:30537dec6e0b 125 }
akashvibhute 0:30537dec6e0b 126
akashvibhute 0:30537dec6e0b 127 virtual const char * getType(){ return "sensor_msgs/Range"; };
akashvibhute 0:30537dec6e0b 128 virtual const char * getMD5(){ return "c005c34273dc426c67a020a87bc24148"; };
akashvibhute 0:30537dec6e0b 129
akashvibhute 0:30537dec6e0b 130 };
akashvibhute 0:30537dec6e0b 131
akashvibhute 0:30537dec6e0b 132 }
akashvibhute 0:30537dec6e0b 133 #endif