Working towards recieving twists

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers SetCameraInfo.h Source File

SetCameraInfo.h

00001 #ifndef _ROS_SERVICE_SetCameraInfo_h
00002 #define _ROS_SERVICE_SetCameraInfo_h
00003 #include <stdint.h>
00004 #include <string.h>
00005 #include <stdlib.h>
00006 #include "ros/msg.h"
00007 #include "sensor_msgs/CameraInfo.h"
00008 
00009 namespace sensor_msgs
00010 {
00011 
00012 static const char SETCAMERAINFO[] = "sensor_msgs/SetCameraInfo";
00013 
00014   class SetCameraInfoRequest : public ros::Msg
00015   {
00016     public:
00017       typedef sensor_msgs::CameraInfo _camera_info_type;
00018       _camera_info_type camera_info;
00019 
00020     SetCameraInfoRequest():
00021       camera_info()
00022     {
00023     }
00024 
00025     virtual int serialize(unsigned char *outbuffer) const
00026     {
00027       int offset = 0;
00028       offset += this->camera_info.serialize(outbuffer + offset);
00029       return offset;
00030     }
00031 
00032     virtual int deserialize(unsigned char *inbuffer)
00033     {
00034       int offset = 0;
00035       offset += this->camera_info.deserialize(inbuffer + offset);
00036      return offset;
00037     }
00038 
00039     const char * getType(){ return SETCAMERAINFO; };
00040     const char * getMD5(){ return "ee34be01fdeee563d0d99cd594d5581d"; };
00041 
00042   };
00043 
00044   class SetCameraInfoResponse : public ros::Msg
00045   {
00046     public:
00047       typedef bool _success_type;
00048       _success_type success;
00049       typedef const char* _status_message_type;
00050       _status_message_type status_message;
00051 
00052     SetCameraInfoResponse():
00053       success(0),
00054       status_message("")
00055     {
00056     }
00057 
00058     virtual int serialize(unsigned char *outbuffer) const
00059     {
00060       int offset = 0;
00061       union {
00062         bool real;
00063         uint8_t base;
00064       } u_success;
00065       u_success.real = this->success;
00066       *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
00067       offset += sizeof(this->success);
00068       uint32_t length_status_message = strlen(this->status_message);
00069       varToArr(outbuffer + offset, length_status_message);
00070       offset += 4;
00071       memcpy(outbuffer + offset, this->status_message, length_status_message);
00072       offset += length_status_message;
00073       return offset;
00074     }
00075 
00076     virtual int deserialize(unsigned char *inbuffer)
00077     {
00078       int offset = 0;
00079       union {
00080         bool real;
00081         uint8_t base;
00082       } u_success;
00083       u_success.base = 0;
00084       u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00085       this->success = u_success.real;
00086       offset += sizeof(this->success);
00087       uint32_t length_status_message;
00088       arrToVar(length_status_message, (inbuffer + offset));
00089       offset += 4;
00090       for(unsigned int k= offset; k< offset+length_status_message; ++k){
00091           inbuffer[k-1]=inbuffer[k];
00092       }
00093       inbuffer[offset+length_status_message-1]=0;
00094       this->status_message = (char *)(inbuffer + offset-1);
00095       offset += length_status_message;
00096      return offset;
00097     }
00098 
00099     const char * getType(){ return SETCAMERAINFO; };
00100     const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
00101 
00102   };
00103 
00104   class SetCameraInfo {
00105     public:
00106     typedef SetCameraInfoRequest Request;
00107     typedef SetCameraInfoResponse Response;
00108   };
00109 
00110 }
00111 #endif