modify for Hydro version

Dependencies:   MODSERIAL

Fork of rosserial_mbed_lib by nucho

Committer:
jjzak
Date:
Sat Oct 26 15:39:01 2013 +0000
Revision:
6:3c54bc7badd4
modify for Hydro version;

Who changed what in which revision?

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