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_SERVICE_SetCameraInfo_h
akashvibhute 0:30537dec6e0b 2 #define _ROS_SERVICE_SetCameraInfo_h
akashvibhute 0:30537dec6e0b 3 #include <stdint.h>
akashvibhute 0:30537dec6e0b 4 #include <string.h>
akashvibhute 0:30537dec6e0b 5 #include <stdlib.h>
akashvibhute 0:30537dec6e0b 6 #include "ros/msg.h"
akashvibhute 0:30537dec6e0b 7 #include "sensor_msgs/CameraInfo.h"
akashvibhute 0:30537dec6e0b 8
akashvibhute 0:30537dec6e0b 9 namespace sensor_msgs
akashvibhute 0:30537dec6e0b 10 {
akashvibhute 0:30537dec6e0b 11
akashvibhute 0:30537dec6e0b 12 static const char SETCAMERAINFO[] = "sensor_msgs/SetCameraInfo";
akashvibhute 0:30537dec6e0b 13
akashvibhute 0:30537dec6e0b 14 class SetCameraInfoRequest : public ros::Msg
akashvibhute 0:30537dec6e0b 15 {
akashvibhute 0:30537dec6e0b 16 public:
akashvibhute 0:30537dec6e0b 17 sensor_msgs::CameraInfo camera_info;
akashvibhute 0:30537dec6e0b 18
akashvibhute 0:30537dec6e0b 19 virtual int serialize(unsigned char *outbuffer) const
akashvibhute 0:30537dec6e0b 20 {
akashvibhute 0:30537dec6e0b 21 int offset = 0;
akashvibhute 0:30537dec6e0b 22 offset += this->camera_info.serialize(outbuffer + offset);
akashvibhute 0:30537dec6e0b 23 return offset;
akashvibhute 0:30537dec6e0b 24 }
akashvibhute 0:30537dec6e0b 25
akashvibhute 0:30537dec6e0b 26 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 27 {
akashvibhute 0:30537dec6e0b 28 int offset = 0;
akashvibhute 0:30537dec6e0b 29 offset += this->camera_info.deserialize(inbuffer + offset);
akashvibhute 0:30537dec6e0b 30 return offset;
akashvibhute 0:30537dec6e0b 31 }
akashvibhute 0:30537dec6e0b 32
akashvibhute 0:30537dec6e0b 33 virtual const char * getType(){ return SETCAMERAINFO; };
akashvibhute 0:30537dec6e0b 34 virtual const char * getMD5(){ return "ee34be01fdeee563d0d99cd594d5581d"; };
akashvibhute 0:30537dec6e0b 35
akashvibhute 0:30537dec6e0b 36 };
akashvibhute 0:30537dec6e0b 37
akashvibhute 0:30537dec6e0b 38 class SetCameraInfoResponse : public ros::Msg
akashvibhute 0:30537dec6e0b 39 {
akashvibhute 0:30537dec6e0b 40 public:
akashvibhute 0:30537dec6e0b 41 bool success;
akashvibhute 0:30537dec6e0b 42 char * status_message;
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 union {
akashvibhute 0:30537dec6e0b 48 bool real;
akashvibhute 0:30537dec6e0b 49 uint8_t base;
akashvibhute 0:30537dec6e0b 50 } u_success;
akashvibhute 0:30537dec6e0b 51 u_success.real = this->success;
akashvibhute 0:30537dec6e0b 52 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
akashvibhute 0:30537dec6e0b 53 offset += sizeof(this->success);
akashvibhute 0:30537dec6e0b 54 uint32_t * length_status_message = (uint32_t *)(outbuffer + offset);
akashvibhute 0:30537dec6e0b 55 *length_status_message = strlen( (const char*) this->status_message);
akashvibhute 0:30537dec6e0b 56 offset += 4;
akashvibhute 0:30537dec6e0b 57 memcpy(outbuffer + offset, this->status_message, *length_status_message);
akashvibhute 0:30537dec6e0b 58 offset += *length_status_message;
akashvibhute 0:30537dec6e0b 59 return offset;
akashvibhute 0:30537dec6e0b 60 }
akashvibhute 0:30537dec6e0b 61
akashvibhute 0:30537dec6e0b 62 virtual int deserialize(unsigned char *inbuffer)
akashvibhute 0:30537dec6e0b 63 {
akashvibhute 0:30537dec6e0b 64 int offset = 0;
akashvibhute 0:30537dec6e0b 65 union {
akashvibhute 0:30537dec6e0b 66 bool real;
akashvibhute 0:30537dec6e0b 67 uint8_t base;
akashvibhute 0:30537dec6e0b 68 } u_success;
akashvibhute 0:30537dec6e0b 69 u_success.base = 0;
akashvibhute 0:30537dec6e0b 70 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
akashvibhute 0:30537dec6e0b 71 this->success = u_success.real;
akashvibhute 0:30537dec6e0b 72 offset += sizeof(this->success);
akashvibhute 0:30537dec6e0b 73 uint32_t length_status_message = *(uint32_t *)(inbuffer + offset);
akashvibhute 0:30537dec6e0b 74 offset += 4;
akashvibhute 0:30537dec6e0b 75 for(unsigned int k= offset; k< offset+length_status_message; ++k){
akashvibhute 0:30537dec6e0b 76 inbuffer[k-1]=inbuffer[k];
akashvibhute 0:30537dec6e0b 77 }
akashvibhute 0:30537dec6e0b 78 inbuffer[offset+length_status_message-1]=0;
akashvibhute 0:30537dec6e0b 79 this->status_message = (char *)(inbuffer + offset-1);
akashvibhute 0:30537dec6e0b 80 offset += length_status_message;
akashvibhute 0:30537dec6e0b 81 return offset;
akashvibhute 0:30537dec6e0b 82 }
akashvibhute 0:30537dec6e0b 83
akashvibhute 0:30537dec6e0b 84 virtual const char * getType(){ return SETCAMERAINFO; };
akashvibhute 0:30537dec6e0b 85 virtual const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
akashvibhute 0:30537dec6e0b 86
akashvibhute 0:30537dec6e0b 87 };
akashvibhute 0:30537dec6e0b 88
akashvibhute 0:30537dec6e0b 89 class SetCameraInfo {
akashvibhute 0:30537dec6e0b 90 public:
akashvibhute 0:30537dec6e0b 91 typedef SetCameraInfoRequest Request;
akashvibhute 0:30537dec6e0b 92 typedef SetCameraInfoResponse Response;
akashvibhute 0:30537dec6e0b 93 };
akashvibhute 0:30537dec6e0b 94
akashvibhute 0:30537dec6e0b 95 }
akashvibhute 0:30537dec6e0b 96 #endif