Personal fork

Dependencies:   MODSERIAL

Dependents:   rosserial_mbed

Fork of rosserial_mbed_lib by nucho

Revision:
3:1cf99502f396
Parent:
0:77afd7560544
--- a/sensor_msgs/SetCameraInfo.h	Sun Oct 16 09:35:11 2011 +0000
+++ b/sensor_msgs/SetCameraInfo.h	Sat Nov 12 23:54:45 2011 +0000
@@ -1,9 +1,9 @@
-#ifndef ros_SERVICE_SetCameraInfo_h
-#define ros_SERVICE_SetCameraInfo_h
+#ifndef _ROS_SERVICE_SetCameraInfo_h
+#define _ROS_SERVICE_SetCameraInfo_h
 #include <stdint.h>
 #include <string.h>
 #include <stdlib.h>
-#include "../ros/msg.h"
+#include "ros/msg.h"
 #include "sensor_msgs/CameraInfo.h"
 
 namespace sensor_msgs
@@ -16,7 +16,7 @@
     public:
       sensor_msgs::CameraInfo camera_info;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       offset += this->camera_info.serialize(outbuffer + offset);
@@ -30,7 +30,8 @@
      return offset;
     }
 
-   virtual const char * getType(){ return SETCAMERAINFO; };
+    virtual const char * getType(){ return SETCAMERAINFO; };
+    virtual const char * getMD5(){ return "ee34be01fdeee563d0d99cd594d5581d"; };
 
   };
 
@@ -40,17 +41,17 @@
       bool success;
       char * status_message;
 
-    virtual int serialize(unsigned char *outbuffer)
+    virtual int serialize(unsigned char *outbuffer) const
     {
       int offset = 0;
       union {
         bool real;
-        unsigned char base;
+        uint8_t base;
       } u_success;
       u_success.real = this->success;
       *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
       offset += sizeof(this->success);
-      long * length_status_message = (long *)(outbuffer + offset);
+      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);
@@ -63,25 +64,32 @@
       int offset = 0;
       union {
         bool real;
-        unsigned char base;
+        uint8_t base;
       } u_success;
       u_success.base = 0;
-      u_success.base |= ((typeof(u_success.base)) (*(inbuffer + offset + 0))) << (8 * 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 * getType(){ return SETCAMERAINFO; };
+    virtual const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
+
+  };
 
+  class SetCameraInfo {
+    public:
+    typedef SetCameraInfoRequest Request;
+    typedef SetCameraInfoResponse Response;
   };
 
 }