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_PointCloud_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_sensor_msgs_PointCloud_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 "geometry_msgs/Point32.h"
akashvibhute 0:30537dec6e0b 10 #include "sensor_msgs/ChannelFloat32.h"
akashvibhute 0:30537dec6e0b 11
akashvibhute 0:30537dec6e0b 12 namespace sensor_msgs
akashvibhute 0:30537dec6e0b 13 {
akashvibhute 0:30537dec6e0b 14
akashvibhute 0:30537dec6e0b 15 class PointCloud : public ros::Msg
akashvibhute 0:30537dec6e0b 16 {
akashvibhute 0:30537dec6e0b 17 public:
akashvibhute 0:30537dec6e0b 18 std_msgs::Header header;
akashvibhute 0:30537dec6e0b 19 uint8_t points_length;
akashvibhute 0:30537dec6e0b 20 geometry_msgs::Point32 st_points;
akashvibhute 0:30537dec6e0b 21 geometry_msgs::Point32 * points;
akashvibhute 0:30537dec6e0b 22 uint8_t channels_length;
akashvibhute 0:30537dec6e0b 23 sensor_msgs::ChannelFloat32 st_channels;
akashvibhute 0:30537dec6e0b 24 sensor_msgs::ChannelFloat32 * channels;
akashvibhute 0:30537dec6e0b 25
akashvibhute 0:30537dec6e0b 26 PointCloud():
akashvibhute 0:30537dec6e0b 27 header(),
akashvibhute 0:30537dec6e0b 28 points_length(0), points(NULL),
akashvibhute 0:30537dec6e0b 29 channels_length(0), channels(NULL)
akashvibhute 0:30537dec6e0b 30 {
akashvibhute 0:30537dec6e0b 31 }
akashvibhute 0:30537dec6e0b 32
akashvibhute 0:30537dec6e0b 33 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 34 {
akashvibhute 0:30537dec6e0b 35 int offset = 0;
akashvibhute 0:30537dec6e0b 36 offset += this->header.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 37 *(outbuffer + offset++) = points_length;
akashvibhute 0:30537dec6e0b 38 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 39 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 40 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 41 for( uint8_t i = 0; i < points_length; i++){
akashvibhute 0:30537dec6e0b 42 offset += this->points[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 43 }
akashvibhute 0:30537dec6e0b 44 *(outbuffer + offset++) = channels_length;
akashvibhute 0:30537dec6e0b 45 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 46 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 47 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 48 for( uint8_t i = 0; i < channels_length; i++){
akashvibhute 0:30537dec6e0b 49 offset += this->channels[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 50 }
akashvibhute 0:30537dec6e0b 51 return offset;
akashvibhute 0:30537dec6e0b 52 }
akashvibhute 0:30537dec6e0b 53
akashvibhute 0:30537dec6e0b 54 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 55 {
akashvibhute 0:30537dec6e0b 56 int offset = 0;
akashvibhute 0:30537dec6e0b 57 offset += this->header.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 58 uint8_t points_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 59 if(points_lengthT > points_length)
akashvibhute 0:30537dec6e0b 60 this->points = (geometry_msgs::Point32*)realloc(this->points, points_lengthT * sizeof(geometry_msgs::Point32));
akashvibhute 0:30537dec6e0b 61 offset += 3;
akashvibhute 0:30537dec6e0b 62 points_length = points_lengthT;
akashvibhute 0:30537dec6e0b 63 for( uint8_t i = 0; i < points_length; i++){
akashvibhute 0:30537dec6e0b 64 offset += this->st_points.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 65 memcpy( &(this->points[i]), &(this->st_points), sizeof(geometry_msgs::Point32));
akashvibhute 0:30537dec6e0b 66 }
akashvibhute 0:30537dec6e0b 67 uint8_t channels_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 68 if(channels_lengthT > channels_length)
akashvibhute 0:30537dec6e0b 69 this->channels = (sensor_msgs::ChannelFloat32*)realloc(this->channels, channels_lengthT * sizeof(sensor_msgs::ChannelFloat32));
akashvibhute 0:30537dec6e0b 70 offset += 3;
akashvibhute 0:30537dec6e0b 71 channels_length = channels_lengthT;
akashvibhute 0:30537dec6e0b 72 for( uint8_t i = 0; i < channels_length; i++){
akashvibhute 0:30537dec6e0b 73 offset += this->st_channels.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 74 memcpy( &(this->channels[i]), &(this->st_channels), sizeof(sensor_msgs::ChannelFloat32));
akashvibhute 0:30537dec6e0b 75 }
akashvibhute 0:30537dec6e0b 76 return offset;
akashvibhute 0:30537dec6e0b 77 }
akashvibhute 0:30537dec6e0b 78
akashvibhute 0:30537dec6e0b 79 const char * getType(){ return "sensor_msgs/PointCloud"; };
akashvibhute 0:30537dec6e0b 80 const char * getMD5(){ return "d8e9c3f5afbdd8a130fd1d2763945fca"; };
akashvibhute 0:30537dec6e0b 81
akashvibhute 0:30537dec6e0b 82 };
akashvibhute 0:30537dec6e0b 83
akashvibhute 0:30537dec6e0b 84 }
akashvibhute 0:30537dec6e0b 85 #endif