This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial. This program contains an example.
Dependencies: rosserial_mbed_lib mbed Servo
Diff: nav_msgs/OccupancyGrid.h
- Revision:
- 4:2cbca0ac2569
- Parent:
- 3:dff241b66f84
--- a/nav_msgs/OccupancyGrid.h Sat Nov 12 23:53:04 2011 +0000 +++ /dev/null Thu Jan 01 00:00:00 1970 +0000 @@ -1,74 +0,0 @@ -#ifndef _ROS_nav_msgs_OccupancyGrid_h -#define _ROS_nav_msgs_OccupancyGrid_h - -#include <stdint.h> -#include <string.h> -#include <stdlib.h> -#include "ros/msg.h" -#include "std_msgs/Header.h" -#include "nav_msgs/MapMetaData.h" - -namespace nav_msgs -{ - - class OccupancyGrid : public ros::Msg - { - public: - std_msgs::Header header; - nav_msgs::MapMetaData info; - uint8_t data_length; - int8_t st_data; - int8_t * data; - - virtual int serialize(unsigned char *outbuffer) const - { - int offset = 0; - offset += this->header.serialize(outbuffer + offset); - offset += this->info.serialize(outbuffer + offset); - *(outbuffer + offset++) = data_length; - *(outbuffer + offset++) = 0; - *(outbuffer + offset++) = 0; - *(outbuffer + offset++) = 0; - for( uint8_t i = 0; i < data_length; i++){ - union { - int8_t real; - uint8_t base; - } u_datai; - u_datai.real = this->data[i]; - *(outbuffer + offset + 0) = (u_datai.base >> (8 * 0)) & 0xFF; - offset += sizeof(this->data[i]); - } - return offset; - } - - virtual int deserialize(unsigned char *inbuffer) - { - int offset = 0; - offset += this->header.deserialize(inbuffer + offset); - offset += this->info.deserialize(inbuffer + offset); - uint8_t data_lengthT = *(inbuffer + offset++); - if(data_lengthT > data_length) - this->data = (int8_t*)realloc(this->data, data_lengthT * sizeof(int8_t)); - offset += 3; - data_length = data_lengthT; - for( uint8_t i = 0; i < data_length; i++){ - union { - int8_t real; - uint8_t base; - } u_st_data; - u_st_data.base = 0; - u_st_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); - this->st_data = u_st_data.real; - offset += sizeof(this->st_data); - memcpy( &(this->data[i]), &(this->st_data), sizeof(int8_t)); - } - return offset; - } - - virtual const char * getType(){ return "nav_msgs/OccupancyGrid"; }; - virtual const char * getMD5(){ return "3381f2d731d4076ec5c71b0759edbe4e"; }; - - }; - -} -#endif \ No newline at end of file