hairo

Dependencies:   mbed BufferedSerial

Committer:
tknara
Date:
Tue Dec 04 00:14:32 2018 +0000
Revision:
4:bcdd99711326
Parent:
0:9e9b7db60fd5
test

Who changed what in which revision?

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