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_object_recognition_msgs_RecognizedObject_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_object_recognition_msgs_RecognizedObject_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 "object_recognition_msgs/ObjectType.h"
akashvibhute 0:30537dec6e0b 10 #include "sensor_msgs/PointCloud2.h"
akashvibhute 0:30537dec6e0b 11 #include "shape_msgs/Mesh.h"
akashvibhute 0:30537dec6e0b 12 #include "geometry_msgs/Point.h"
akashvibhute 0:30537dec6e0b 13 #include "geometry_msgs/PoseWithCovarianceStamped.h"
akashvibhute 0:30537dec6e0b 14
akashvibhute 0:30537dec6e0b 15 namespace object_recognition_msgs
akashvibhute 0:30537dec6e0b 16 {
akashvibhute 0:30537dec6e0b 17
akashvibhute 0:30537dec6e0b 18 class RecognizedObject : public ros::Msg
akashvibhute 0:30537dec6e0b 19 {
akashvibhute 0:30537dec6e0b 20 public:
akashvibhute 0:30537dec6e0b 21 std_msgs::Header header;
akashvibhute 0:30537dec6e0b 22 object_recognition_msgs::ObjectType type;
akashvibhute 0:30537dec6e0b 23 float confidence;
akashvibhute 0:30537dec6e0b 24 uint8_t point_clouds_length;
akashvibhute 0:30537dec6e0b 25 sensor_msgs::PointCloud2 st_point_clouds;
akashvibhute 0:30537dec6e0b 26 sensor_msgs::PointCloud2 * point_clouds;
akashvibhute 0:30537dec6e0b 27 shape_msgs::Mesh bounding_mesh;
akashvibhute 0:30537dec6e0b 28 uint8_t bounding_contours_length;
akashvibhute 0:30537dec6e0b 29 geometry_msgs::Point st_bounding_contours;
akashvibhute 0:30537dec6e0b 30 geometry_msgs::Point * bounding_contours;
akashvibhute 0:30537dec6e0b 31 geometry_msgs::PoseWithCovarianceStamped pose;
akashvibhute 0:30537dec6e0b 32
akashvibhute 0:30537dec6e0b 33 RecognizedObject():
akashvibhute 0:30537dec6e0b 34 header(),
akashvibhute 0:30537dec6e0b 35 type(),
akashvibhute 0:30537dec6e0b 36 confidence(0),
akashvibhute 0:30537dec6e0b 37 point_clouds_length(0), point_clouds(NULL),
akashvibhute 0:30537dec6e0b 38 bounding_mesh(),
akashvibhute 0:30537dec6e0b 39 bounding_contours_length(0), bounding_contours(NULL),
akashvibhute 0:30537dec6e0b 40 pose()
akashvibhute 0:30537dec6e0b 41 {
akashvibhute 0:30537dec6e0b 42 }
akashvibhute 0:30537dec6e0b 43
akashvibhute 0:30537dec6e0b 44 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 45 {
akashvibhute 0:30537dec6e0b 46 int offset = 0;
akashvibhute 0:30537dec6e0b 47 offset += this->header.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 48 offset += this->type.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 49 union {
akashvibhute 0:30537dec6e0b 50 float real;
akashvibhute 0:30537dec6e0b 51 uint32_t base;
akashvibhute 0:30537dec6e0b 52 } u_confidence;
akashvibhute 0:30537dec6e0b 53 u_confidence.real = this->confidence;
akashvibhute 0:30537dec6e0b 54 *(outbuffer + offset + 0) = (u_confidence.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 55 *(outbuffer + offset + 1) = (u_confidence.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 56 *(outbuffer + offset + 2) = (u_confidence.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 57 *(outbuffer + offset + 3) = (u_confidence.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 58 offset += sizeof(this->confidence);
akashvibhute 0:30537dec6e0b 59 *(outbuffer + offset++) = point_clouds_length;
akashvibhute 0:30537dec6e0b 60 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 61 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 62 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 63 for( uint8_t i = 0; i < point_clouds_length; i++){
akashvibhute 0:30537dec6e0b 64 offset += this->point_clouds[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 65 }
akashvibhute 0:30537dec6e0b 66 offset += this->bounding_mesh.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 67 *(outbuffer + offset++) = bounding_contours_length;
akashvibhute 0:30537dec6e0b 68 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 69 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 70 *(outbuffer + offset++) = 0;
akashvibhute 0:30537dec6e0b 71 for( uint8_t i = 0; i < bounding_contours_length; i++){
akashvibhute 0:30537dec6e0b 72 offset += this->bounding_contours[i].serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 73 }
akashvibhute 0:30537dec6e0b 74 offset += this->pose.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 75 return offset;
akashvibhute 0:30537dec6e0b 76 }
akashvibhute 0:30537dec6e0b 77
akashvibhute 0:30537dec6e0b 78 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 79 {
akashvibhute 0:30537dec6e0b 80 int offset = 0;
akashvibhute 0:30537dec6e0b 81 offset += this->header.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 82 offset += this->type.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 83 union {
akashvibhute 0:30537dec6e0b 84 float real;
akashvibhute 0:30537dec6e0b 85 uint32_t base;
akashvibhute 0:30537dec6e0b 86 } u_confidence;
akashvibhute 0:30537dec6e0b 87 u_confidence.base = 0;
akashvibhute 0:30537dec6e0b 88 u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 89 u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 90 u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 91 u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 92 this->confidence = u_confidence.real;
akashvibhute 0:30537dec6e0b 93 offset += sizeof(this->confidence);
akashvibhute 0:30537dec6e0b 94 uint8_t point_clouds_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 95 if(point_clouds_lengthT > point_clouds_length)
akashvibhute 0:30537dec6e0b 96 this->point_clouds = (sensor_msgs::PointCloud2*)realloc(this->point_clouds, point_clouds_lengthT * sizeof(sensor_msgs::PointCloud2));
akashvibhute 0:30537dec6e0b 97 offset += 3;
akashvibhute 0:30537dec6e0b 98 point_clouds_length = point_clouds_lengthT;
akashvibhute 0:30537dec6e0b 99 for( uint8_t i = 0; i < point_clouds_length; i++){
akashvibhute 0:30537dec6e0b 100 offset += this->st_point_clouds.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 101 memcpy( &(this->point_clouds[i]), &(this->st_point_clouds), sizeof(sensor_msgs::PointCloud2));
akashvibhute 0:30537dec6e0b 102 }
akashvibhute 0:30537dec6e0b 103 offset += this->bounding_mesh.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 104 uint8_t bounding_contours_lengthT = *(inbuffer + offset++);
akashvibhute 0:30537dec6e0b 105 if(bounding_contours_lengthT > bounding_contours_length)
akashvibhute 0:30537dec6e0b 106 this->bounding_contours = (geometry_msgs::Point*)realloc(this->bounding_contours, bounding_contours_lengthT * sizeof(geometry_msgs::Point));
akashvibhute 0:30537dec6e0b 107 offset += 3;
akashvibhute 0:30537dec6e0b 108 bounding_contours_length = bounding_contours_lengthT;
akashvibhute 0:30537dec6e0b 109 for( uint8_t i = 0; i < bounding_contours_length; i++){
akashvibhute 0:30537dec6e0b 110 offset += this->st_bounding_contours.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 111 memcpy( &(this->bounding_contours[i]), &(this->st_bounding_contours), sizeof(geometry_msgs::Point));
akashvibhute 0:30537dec6e0b 112 }
akashvibhute 0:30537dec6e0b 113 offset += this->pose.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 114 return offset;
akashvibhute 0:30537dec6e0b 115 }
akashvibhute 0:30537dec6e0b 116
akashvibhute 0:30537dec6e0b 117 const char * getType(){ return "object_recognition_msgs/RecognizedObject"; };
akashvibhute 0:30537dec6e0b 118 const char * getMD5(){ return "f92c4cb29ba11f26c5f7219de97e900d"; };
akashvibhute 0:30537dec6e0b 119
akashvibhute 0:30537dec6e0b 120 };
akashvibhute 0:30537dec6e0b 121
akashvibhute 0:30537dec6e0b 122 }
akashvibhute 0:30537dec6e0b 123 #endif