This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial.

Dependencies:  

Dependents:   rosserial_mbed robot_S2

Committer:
nucho
Date:
Sun Oct 16 07:19:36 2011 +0000
Revision:
1:ff0ec969dad1
Parent:
0:77afd7560544
Child:
3:1cf99502f396
This program supported the revision of 143 of rosserial.
And the bug fix of receive of array data.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
nucho 1:ff0ec969dad1 1 #ifndef ros_nav_msgs_OccupancyGrid_h
nucho 1:ff0ec969dad1 2 #define ros_nav_msgs_OccupancyGrid_h
nucho 0:77afd7560544 3
nucho 0:77afd7560544 4 #include <stdint.h>
nucho 0:77afd7560544 5 #include <string.h>
nucho 0:77afd7560544 6 #include <stdlib.h>
nucho 0:77afd7560544 7 #include "../ros/msg.h"
nucho 0:77afd7560544 8 #include "std_msgs/Header.h"
nucho 0:77afd7560544 9 #include "nav_msgs/MapMetaData.h"
nucho 0:77afd7560544 10
nucho 0:77afd7560544 11 namespace nav_msgs
nucho 0:77afd7560544 12 {
nucho 0:77afd7560544 13
nucho 0:77afd7560544 14 class OccupancyGrid : public ros::Msg
nucho 0:77afd7560544 15 {
nucho 0:77afd7560544 16 public:
nucho 0:77afd7560544 17 std_msgs::Header header;
nucho 0:77afd7560544 18 nav_msgs::MapMetaData info;
nucho 0:77afd7560544 19 unsigned char data_length;
nucho 0:77afd7560544 20 signed char st_data;
nucho 0:77afd7560544 21 signed char * data;
nucho 0:77afd7560544 22
nucho 0:77afd7560544 23 virtual int serialize(unsigned char *outbuffer)
nucho 0:77afd7560544 24 {
nucho 0:77afd7560544 25 int offset = 0;
nucho 0:77afd7560544 26 offset += this->header.serialize(outbuffer + offset);
nucho 0:77afd7560544 27 offset += this->info.serialize(outbuffer + offset);
nucho 0:77afd7560544 28 *(outbuffer + offset++) = data_length;
nucho 0:77afd7560544 29 *(outbuffer + offset++) = 0;
nucho 0:77afd7560544 30 *(outbuffer + offset++) = 0;
nucho 0:77afd7560544 31 *(outbuffer + offset++) = 0;
nucho 0:77afd7560544 32 for( unsigned char i = 0; i < data_length; i++){
nucho 0:77afd7560544 33 union {
nucho 0:77afd7560544 34 signed char real;
nucho 0:77afd7560544 35 unsigned char base;
nucho 0:77afd7560544 36 } u_datai;
nucho 0:77afd7560544 37 u_datai.real = this->data[i];
nucho 0:77afd7560544 38 *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 39 offset += sizeof(this->data[i]);
nucho 0:77afd7560544 40 }
nucho 0:77afd7560544 41 return offset;
nucho 0:77afd7560544 42 }
nucho 0:77afd7560544 43
nucho 0:77afd7560544 44 virtual int deserialize(unsigned char *inbuffer)
nucho 0:77afd7560544 45 {
nucho 0:77afd7560544 46 int offset = 0;
nucho 0:77afd7560544 47 offset += this->header.deserialize(inbuffer + offset);
nucho 0:77afd7560544 48 offset += this->info.deserialize(inbuffer + offset);
nucho 0:77afd7560544 49 unsigned char data_lengthT = *(inbuffer + offset++);
nucho 0:77afd7560544 50 if(data_lengthT > data_length)
nucho 0:77afd7560544 51 this->data = (signed char*)realloc(this->data, data_lengthT * sizeof(signed char));
nucho 0:77afd7560544 52 offset += 3;
nucho 0:77afd7560544 53 data_length = data_lengthT;
nucho 0:77afd7560544 54 for( unsigned char i = 0; i < data_length; i++){
nucho 0:77afd7560544 55 union {
nucho 0:77afd7560544 56 signed char real;
nucho 0:77afd7560544 57 unsigned char base;
nucho 0:77afd7560544 58 } u_st_data;
nucho 0:77afd7560544 59 u_st_data.base = 0;
nucho 0:77afd7560544 60 u_st_data.base |= ((typeof(u_st_data.base)) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 61 this->st_data = u_st_data.real;
nucho 0:77afd7560544 62 offset += sizeof(this->st_data);
nucho 0:77afd7560544 63 memcpy( &(this->data[i]), &(this->st_data), sizeof(signed char));
nucho 0:77afd7560544 64 }
nucho 0:77afd7560544 65 return offset;
nucho 0:77afd7560544 66 }
nucho 0:77afd7560544 67
nucho 0:77afd7560544 68 virtual const char * getType(){ return "nav_msgs/OccupancyGrid"; };
nucho 0:77afd7560544 69
nucho 0:77afd7560544 70 };
nucho 0:77afd7560544 71
nucho 0:77afd7560544 72 }
nucho 0:77afd7560544 73 #endif