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_household_objects_database_msgs_DatabaseModelPose_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_household_objects_database_msgs_DatabaseModelPose_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 "object_recognition_msgs/ObjectType.h"
akashvibhute 0:30537dec6e0b 9 #include "geometry_msgs/PoseStamped.h"
akashvibhute 0:30537dec6e0b 10
akashvibhute 0:30537dec6e0b 11 namespace household_objects_database_msgs
akashvibhute 0:30537dec6e0b 12 {
akashvibhute 0:30537dec6e0b 13
akashvibhute 0:30537dec6e0b 14 class DatabaseModelPose : public ros::Msg
akashvibhute 0:30537dec6e0b 15 {
akashvibhute 0:30537dec6e0b 16 public:
akashvibhute 0:30537dec6e0b 17 int32_t model_id;
akashvibhute 0:30537dec6e0b 18 object_recognition_msgs::ObjectType type;
akashvibhute 0:30537dec6e0b 19 geometry_msgs::PoseStamped pose;
akashvibhute 0:30537dec6e0b 20 float confidence;
akashvibhute 0:30537dec6e0b 21 const char* detector_name;
akashvibhute 0:30537dec6e0b 22
akashvibhute 0:30537dec6e0b 23 DatabaseModelPose():
akashvibhute 0:30537dec6e0b 24 model_id(0),
akashvibhute 0:30537dec6e0b 25 type(),
akashvibhute 0:30537dec6e0b 26 pose(),
akashvibhute 0:30537dec6e0b 27 confidence(0),
akashvibhute 0:30537dec6e0b 28 detector_name("")
akashvibhute 0:30537dec6e0b 29 {
akashvibhute 0:30537dec6e0b 30 }
akashvibhute 0:30537dec6e0b 31
akashvibhute 0:30537dec6e0b 32 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 33 {
akashvibhute 0:30537dec6e0b 34 int offset = 0;
akashvibhute 0:30537dec6e0b 35 union {
akashvibhute 0:30537dec6e0b 36 int32_t real;
akashvibhute 0:30537dec6e0b 37 uint32_t base;
akashvibhute 0:30537dec6e0b 38 } u_model_id;
akashvibhute 0:30537dec6e0b 39 u_model_id.real = this->model_id;
akashvibhute 0:30537dec6e0b 40 *(outbuffer + offset + 0) = (u_model_id.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 41 *(outbuffer + offset + 1) = (u_model_id.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 42 *(outbuffer + offset + 2) = (u_model_id.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 43 *(outbuffer + offset + 3) = (u_model_id.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 44 offset += sizeof(this->model_id);
akashvibhute 0:30537dec6e0b 45 offset += this->type.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 46 offset += this->pose.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 47 union {
akashvibhute 0:30537dec6e0b 48 float real;
akashvibhute 0:30537dec6e0b 49 uint32_t base;
akashvibhute 0:30537dec6e0b 50 } u_confidence;
akashvibhute 0:30537dec6e0b 51 u_confidence.real = this->confidence;
akashvibhute 0:30537dec6e0b 52 *(outbuffer + offset + 0) = (u_confidence.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 53 *(outbuffer + offset + 1) = (u_confidence.base >> (8 * 1)) & 0xFF;
akashvibhute 0:30537dec6e0b 54 *(outbuffer + offset + 2) = (u_confidence.base >> (8 * 2)) & 0xFF;
akashvibhute 0:30537dec6e0b 55 *(outbuffer + offset + 3) = (u_confidence.base >> (8 * 3)) & 0xFF;
akashvibhute 0:30537dec6e0b 56 offset += sizeof(this->confidence);
akashvibhute 0:30537dec6e0b 57 uint32_t length_detector_name = strlen(this->detector_name);
akashvibhute 0:30537dec6e0b 58 memcpy(outbuffer + offset, &length_detector_name, sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 59 offset += 4;
akashvibhute 0:30537dec6e0b 60 memcpy(outbuffer + offset, this->detector_name, length_detector_name);
akashvibhute 0:30537dec6e0b 61 offset += length_detector_name;
akashvibhute 0:30537dec6e0b 62 return offset;
akashvibhute 0:30537dec6e0b 63 }
akashvibhute 0:30537dec6e0b 64
akashvibhute 0:30537dec6e0b 65 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 66 {
akashvibhute 0:30537dec6e0b 67 int offset = 0;
akashvibhute 0:30537dec6e0b 68 union {
akashvibhute 0:30537dec6e0b 69 int32_t real;
akashvibhute 0:30537dec6e0b 70 uint32_t base;
akashvibhute 0:30537dec6e0b 71 } u_model_id;
akashvibhute 0:30537dec6e0b 72 u_model_id.base = 0;
akashvibhute 0:30537dec6e0b 73 u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 74 u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 75 u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 76 u_model_id.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 77 this->model_id = u_model_id.real;
akashvibhute 0:30537dec6e0b 78 offset += sizeof(this->model_id);
akashvibhute 0:30537dec6e0b 79 offset += this->type.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 80 offset += this->pose.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 81 union {
akashvibhute 0:30537dec6e0b 82 float real;
akashvibhute 0:30537dec6e0b 83 uint32_t base;
akashvibhute 0:30537dec6e0b 84 } u_confidence;
akashvibhute 0:30537dec6e0b 85 u_confidence.base = 0;
akashvibhute 0:30537dec6e0b 86 u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 87 u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
akashvibhute 0:30537dec6e0b 88 u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
akashvibhute 0:30537dec6e0b 89 u_confidence.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
akashvibhute 0:30537dec6e0b 90 this->confidence = u_confidence.real;
akashvibhute 0:30537dec6e0b 91 offset += sizeof(this->confidence);
akashvibhute 0:30537dec6e0b 92 uint32_t length_detector_name;
akashvibhute 0:30537dec6e0b 93 memcpy(&length_detector_name, (inbuffer + offset), sizeof(uint32_t));
akashvibhute 0:30537dec6e0b 94 offset += 4;
akashvibhute 0:30537dec6e0b 95 for(unsigned int k= offset; k< offset+length_detector_name; ++k){
akashvibhute 0:30537dec6e0b 96 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 97 }
akashvibhute 0:30537dec6e0b 98 inbuffer[offset+length_detector_name-1]=0;
akashvibhute 0:30537dec6e0b 99 this->detector_name = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 100 offset += length_detector_name;
akashvibhute 0:30537dec6e0b 101 return offset;
akashvibhute 0:30537dec6e0b 102 }
akashvibhute 0:30537dec6e0b 103
akashvibhute 0:30537dec6e0b 104 const char * getType(){ return "household_objects_database_msgs/DatabaseModelPose"; };
akashvibhute 0:30537dec6e0b 105 const char * getMD5(){ return "6bc39ef48ca57cc7d4341cfc13a5a110"; };
akashvibhute 0:30537dec6e0b 106
akashvibhute 0:30537dec6e0b 107 };
akashvibhute 0:30537dec6e0b 108
akashvibhute 0:30537dec6e0b 109 }
akashvibhute 0:30537dec6e0b 110 #endif