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