This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial.

Dependencies:  

Dependents:   rosserial_mbed robot_S2

Committer:
nucho
Date:
Wed Feb 29 23:00:21 2012 +0000
Revision:
4:684f39d0c346
Parent:
3:1cf99502f396

        

Who changed what in which revision?

UserRevisionLine numberNew contents of line
nucho 3:1cf99502f396 1 #ifndef _ROS_SERVICE_SetCameraInfo_h
nucho 3:1cf99502f396 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 3:1cf99502f396 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 3:1cf99502f396 19 virtual int serialize(unsigned char *outbuffer) const
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 3:1cf99502f396 33 virtual const char * getType(){ return SETCAMERAINFO; };
nucho 3:1cf99502f396 34 virtual const char * getMD5(){ return "ee34be01fdeee563d0d99cd594d5581d"; };
nucho 0:77afd7560544 35
nucho 0:77afd7560544 36 };
nucho 0:77afd7560544 37
nucho 0:77afd7560544 38 class SetCameraInfoResponse : public ros::Msg
nucho 0:77afd7560544 39 {
nucho 0:77afd7560544 40 public:
nucho 0:77afd7560544 41 bool success;
nucho 0:77afd7560544 42 char * status_message;
nucho 0:77afd7560544 43
nucho 3:1cf99502f396 44 virtual int serialize(unsigned char *outbuffer) const
nucho 0:77afd7560544 45 {
nucho 0:77afd7560544 46 int offset = 0;
nucho 0:77afd7560544 47 union {
nucho 0:77afd7560544 48 bool real;
nucho 3:1cf99502f396 49 uint8_t base;
nucho 0:77afd7560544 50 } u_success;
nucho 0:77afd7560544 51 u_success.real = this->success;
nucho 0:77afd7560544 52 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
nucho 0:77afd7560544 53 offset += sizeof(this->success);
nucho 3:1cf99502f396 54 uint32_t * length_status_message = (uint32_t *)(outbuffer + offset);
nucho 0:77afd7560544 55 *length_status_message = strlen( (const char*) this->status_message);
nucho 0:77afd7560544 56 offset += 4;
nucho 0:77afd7560544 57 memcpy(outbuffer + offset, this->status_message, *length_status_message);
nucho 0:77afd7560544 58 offset += *length_status_message;
nucho 0:77afd7560544 59 return offset;
nucho 0:77afd7560544 60 }
nucho 0:77afd7560544 61
nucho 0:77afd7560544 62 virtual int deserialize(unsigned char *inbuffer)
nucho 0:77afd7560544 63 {
nucho 0:77afd7560544 64 int offset = 0;
nucho 0:77afd7560544 65 union {
nucho 0:77afd7560544 66 bool real;
nucho 3:1cf99502f396 67 uint8_t base;
nucho 0:77afd7560544 68 } u_success;
nucho 0:77afd7560544 69 u_success.base = 0;
nucho 3:1cf99502f396 70 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
nucho 0:77afd7560544 71 this->success = u_success.real;
nucho 0:77afd7560544 72 offset += sizeof(this->success);
nucho 0:77afd7560544 73 uint32_t length_status_message = *(uint32_t *)(inbuffer + offset);
nucho 0:77afd7560544 74 offset += 4;
nucho 0:77afd7560544 75 for(unsigned int k= offset; k< offset+length_status_message; ++k){
nucho 0:77afd7560544 76 inbuffer[k-1]=inbuffer[k];
nucho 3:1cf99502f396 77 }
nucho 0:77afd7560544 78 inbuffer[offset+length_status_message-1]=0;
nucho 0:77afd7560544 79 this->status_message = (char *)(inbuffer + offset-1);
nucho 0:77afd7560544 80 offset += length_status_message;
nucho 0:77afd7560544 81 return offset;
nucho 0:77afd7560544 82 }
nucho 0:77afd7560544 83
nucho 3:1cf99502f396 84 virtual const char * getType(){ return SETCAMERAINFO; };
nucho 3:1cf99502f396 85 virtual const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
nucho 3:1cf99502f396 86
nucho 3:1cf99502f396 87 };
nucho 0:77afd7560544 88
nucho 3:1cf99502f396 89 class SetCameraInfo {
nucho 3:1cf99502f396 90 public:
nucho 3:1cf99502f396 91 typedef SetCameraInfoRequest Request;
nucho 3:1cf99502f396 92 typedef SetCameraInfoResponse Response;
nucho 0:77afd7560544 93 };
nucho 0:77afd7560544 94
nucho 0:77afd7560544 95 }
nucho 0:77afd7560544 96 #endif