rosserial library for mbed Inspired by nucho's rosserial library This library is still under development
Dependents: mbed_roshydro_test
Library still under development!
Diff: sensor_msgs/SetCameraInfo.h
- Revision:
- 0:30537dec6e0b
diff -r 000000000000 -r 30537dec6e0b sensor_msgs/SetCameraInfo.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/sensor_msgs/SetCameraInfo.h Sun Feb 15 10:53:43 2015 +0000 @@ -0,0 +1,96 @@ +#ifndef _ROS_SERVICE_SetCameraInfo_h +#define _ROS_SERVICE_SetCameraInfo_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" +#include "sensor_msgs/CameraInfo.h" + +namespace sensor_msgs +{ + +static const char SETCAMERAINFO[] = "sensor_msgs/SetCameraInfo"; + + class SetCameraInfoRequest : public ros::Msg + { + public: + sensor_msgs::CameraInfo camera_info; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + offset += this->camera_info.serialize(outbuffer + offset); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + offset += this->camera_info.deserialize(inbuffer + offset); + return offset; + } + + virtual const char * getType(){ return SETCAMERAINFO; }; + virtual const char * getMD5(){ return "ee34be01fdeee563d0d99cd594d5581d"; }; + + }; + + class SetCameraInfoResponse : public ros::Msg + { + public: + bool success; + char * status_message; + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t * length_status_message = (uint32_t *)(outbuffer + offset); + *length_status_message = strlen( (const char*) this->status_message); + offset += 4; + memcpy(outbuffer + offset, this->status_message, *length_status_message); + offset += *length_status_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_status_message = *(uint32_t *)(inbuffer + offset); + offset += 4; + for(unsigned int k= offset; k< offset+length_status_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_status_message-1]=0; + this->status_message = (char *)(inbuffer + offset-1); + offset += length_status_message; + return offset; + } + + virtual const char * getType(){ return SETCAMERAINFO; }; + virtual const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; }; + + }; + + class SetCameraInfo { + public: + typedef SetCameraInfoRequest Request; + typedef SetCameraInfoResponse Response; + }; + +} +#endif