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 sensor_msgs::CameraInfo camera_info; 00018 00019 virtual int serialize(unsigned char *outbuffer) const 00020 { 00021 int offset = 0; 00022 offset += this->camera_info.serialize(outbuffer + offset); 00023 return offset; 00024 } 00025 00026 virtual int deserialize(unsigned char *inbuffer) 00027 { 00028 int offset = 0; 00029 offset += this->camera_info.deserialize(inbuffer + offset); 00030 return offset; 00031 } 00032 00033 const char * getType(){ return SETCAMERAINFO; }; 00034 const char * getMD5(){ return "ee34be01fdeee563d0d99cd594d5581d"; }; 00035 00036 }; 00037 00038 class SetCameraInfoResponse : public ros::Msg 00039 { 00040 public: 00041 bool success; 00042 char * status_message; 00043 00044 virtual int serialize(unsigned char *outbuffer) const 00045 { 00046 int offset = 0; 00047 union { 00048 bool real; 00049 uint8_t base; 00050 } u_success; 00051 u_success.real = this->success; 00052 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; 00053 offset += sizeof(this->success); 00054 uint32_t * length_status_message = (uint32_t *)(outbuffer + offset); 00055 *length_status_message = strlen( (const char*) this->status_message); 00056 offset += 4; 00057 memcpy(outbuffer + offset, this->status_message, *length_status_message); 00058 offset += *length_status_message; 00059 return offset; 00060 } 00061 00062 virtual int deserialize(unsigned char *inbuffer) 00063 { 00064 int offset = 0; 00065 union { 00066 bool real; 00067 uint8_t base; 00068 } u_success; 00069 u_success.base = 0; 00070 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00071 this->success = u_success.real; 00072 offset += sizeof(this->success); 00073 uint32_t length_status_message = *(uint32_t *)(inbuffer + offset); 00074 offset += 4; 00075 for(unsigned int k= offset; k< offset+length_status_message; ++k){ 00076 inbuffer[k-1]=inbuffer[k]; 00077 } 00078 inbuffer[offset+length_status_message-1]=0; 00079 this->status_message = (char *)(inbuffer + offset-1); 00080 offset += length_status_message; 00081 return offset; 00082 } 00083 00084 const char * getType(){ return SETCAMERAINFO; }; 00085 const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; }; 00086 00087 }; 00088 00089 class SetCameraInfo { 00090 public: 00091 typedef SetCameraInfoRequest Request; 00092 typedef SetCameraInfoResponse Response; 00093 }; 00094 00095 } 00096 #endif