modify for Hydro version
Fork of rosserial_mbed_lib by
sensor_msgs/SetCameraInfo.h@0:77afd7560544, 2011-08-19 (annotated)
- Committer:
- nucho
- Date:
- Fri Aug 19 09:06:30 2011 +0000
- Revision:
- 0:77afd7560544
- Child:
- 3:1cf99502f396
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
nucho | 0:77afd7560544 | 1 | #ifndef ros_SERVICE_SetCameraInfo_h |
nucho | 0:77afd7560544 | 2 | #define ros_SERVICE_SetCameraInfo_h |
nucho | 0:77afd7560544 | 3 | #include <stdint.h> |
nucho | 0:77afd7560544 | 4 | #include <string.h> |
nucho | 0:77afd7560544 | 5 | #include <stdlib.h> |
nucho | 0:77afd7560544 | 6 | #include "../ros/msg.h" |
nucho | 0:77afd7560544 | 7 | #include "sensor_msgs/CameraInfo.h" |
nucho | 0:77afd7560544 | 8 | |
nucho | 0:77afd7560544 | 9 | namespace sensor_msgs |
nucho | 0:77afd7560544 | 10 | { |
nucho | 0:77afd7560544 | 11 | |
nucho | 0:77afd7560544 | 12 | static const char SETCAMERAINFO[] = "sensor_msgs/SetCameraInfo"; |
nucho | 0:77afd7560544 | 13 | |
nucho | 0:77afd7560544 | 14 | class SetCameraInfoRequest : public ros::Msg |
nucho | 0:77afd7560544 | 15 | { |
nucho | 0:77afd7560544 | 16 | public: |
nucho | 0:77afd7560544 | 17 | sensor_msgs::CameraInfo camera_info; |
nucho | 0:77afd7560544 | 18 | |
nucho | 0:77afd7560544 | 19 | virtual int serialize(unsigned char *outbuffer) |
nucho | 0:77afd7560544 | 20 | { |
nucho | 0:77afd7560544 | 21 | int offset = 0; |
nucho | 0:77afd7560544 | 22 | offset += this->camera_info.serialize(outbuffer + offset); |
nucho | 0:77afd7560544 | 23 | return offset; |
nucho | 0:77afd7560544 | 24 | } |
nucho | 0:77afd7560544 | 25 | |
nucho | 0:77afd7560544 | 26 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 0:77afd7560544 | 27 | { |
nucho | 0:77afd7560544 | 28 | int offset = 0; |
nucho | 0:77afd7560544 | 29 | offset += this->camera_info.deserialize(inbuffer + offset); |
nucho | 0:77afd7560544 | 30 | return offset; |
nucho | 0:77afd7560544 | 31 | } |
nucho | 0:77afd7560544 | 32 | |
nucho | 0:77afd7560544 | 33 | virtual const char * getType(){ return SETCAMERAINFO; }; |
nucho | 0:77afd7560544 | 34 | |
nucho | 0:77afd7560544 | 35 | }; |
nucho | 0:77afd7560544 | 36 | |
nucho | 0:77afd7560544 | 37 | class SetCameraInfoResponse : public ros::Msg |
nucho | 0:77afd7560544 | 38 | { |
nucho | 0:77afd7560544 | 39 | public: |
nucho | 0:77afd7560544 | 40 | bool success; |
nucho | 0:77afd7560544 | 41 | char * status_message; |
nucho | 0:77afd7560544 | 42 | |
nucho | 0:77afd7560544 | 43 | virtual int serialize(unsigned char *outbuffer) |
nucho | 0:77afd7560544 | 44 | { |
nucho | 0:77afd7560544 | 45 | int offset = 0; |
nucho | 0:77afd7560544 | 46 | union { |
nucho | 0:77afd7560544 | 47 | bool real; |
nucho | 0:77afd7560544 | 48 | unsigned char base; |
nucho | 0:77afd7560544 | 49 | } u_success; |
nucho | 0:77afd7560544 | 50 | u_success.real = this->success; |
nucho | 0:77afd7560544 | 51 | *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; |
nucho | 0:77afd7560544 | 52 | offset += sizeof(this->success); |
nucho | 0:77afd7560544 | 53 | long * length_status_message = (long *)(outbuffer + offset); |
nucho | 0:77afd7560544 | 54 | *length_status_message = strlen( (const char*) this->status_message); |
nucho | 0:77afd7560544 | 55 | offset += 4; |
nucho | 0:77afd7560544 | 56 | memcpy(outbuffer + offset, this->status_message, *length_status_message); |
nucho | 0:77afd7560544 | 57 | offset += *length_status_message; |
nucho | 0:77afd7560544 | 58 | return offset; |
nucho | 0:77afd7560544 | 59 | } |
nucho | 0:77afd7560544 | 60 | |
nucho | 0:77afd7560544 | 61 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 0:77afd7560544 | 62 | { |
nucho | 0:77afd7560544 | 63 | int offset = 0; |
nucho | 0:77afd7560544 | 64 | union { |
nucho | 0:77afd7560544 | 65 | bool real; |
nucho | 0:77afd7560544 | 66 | unsigned char base; |
nucho | 0:77afd7560544 | 67 | } u_success; |
nucho | 0:77afd7560544 | 68 | u_success.base = 0; |
nucho | 0:77afd7560544 | 69 | u_success.base |= ((typeof(u_success.base)) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 0:77afd7560544 | 70 | this->success = u_success.real; |
nucho | 0:77afd7560544 | 71 | offset += sizeof(this->success); |
nucho | 0:77afd7560544 | 72 | uint32_t length_status_message = *(uint32_t *)(inbuffer + offset); |
nucho | 0:77afd7560544 | 73 | offset += 4; |
nucho | 0:77afd7560544 | 74 | for(unsigned int k= offset; k< offset+length_status_message; ++k){ |
nucho | 0:77afd7560544 | 75 | inbuffer[k-1]=inbuffer[k]; |
nucho | 0:77afd7560544 | 76 | } |
nucho | 0:77afd7560544 | 77 | inbuffer[offset+length_status_message-1]=0; |
nucho | 0:77afd7560544 | 78 | this->status_message = (char *)(inbuffer + offset-1); |
nucho | 0:77afd7560544 | 79 | offset += length_status_message; |
nucho | 0:77afd7560544 | 80 | return offset; |
nucho | 0:77afd7560544 | 81 | } |
nucho | 0:77afd7560544 | 82 | |
nucho | 0:77afd7560544 | 83 | virtual const char * getType(){ return SETCAMERAINFO; }; |
nucho | 0:77afd7560544 | 84 | |
nucho | 0:77afd7560544 | 85 | }; |
nucho | 0:77afd7560544 | 86 | |
nucho | 0:77afd7560544 | 87 | } |
nucho | 0:77afd7560544 | 88 | #endif |