00001 #ifndef _ROS_std_msgs_Duration_h 00002 #define _ROS_std_msgs_Duration_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "ros/duration.h" 00009 00010 namespace std_msgs 00011 { 00012 00013 class Duration : public ros::Msg 00014 { 00015 public: 00016 ros::Duration data; 00017 00018 virtual int serialize(unsigned char *outbuffer) const 00019 { 00020 int offset = 0; 00021 *(outbuffer + offset + 0) = (this->data.sec >> (8 * 0)) & 0xFF; 00022 *(outbuffer + offset + 1) = (this->data.sec >> (8 * 1)) & 0xFF; 00023 *(outbuffer + offset + 2) = (this->data.sec >> (8 * 2)) & 0xFF; 00024 *(outbuffer + offset + 3) = (this->data.sec >> (8 * 3)) & 0xFF; 00025 offset += sizeof(this->data.sec); 00026 *(outbuffer + offset + 0) = (this->data.nsec >> (8 * 0)) & 0xFF; 00027 *(outbuffer + offset + 1) = (this->data.nsec >> (8 * 1)) & 0xFF; 00028 *(outbuffer + offset + 2) = (this->data.nsec >> (8 * 2)) & 0xFF; 00029 *(outbuffer + offset + 3) = (this->data.nsec >> (8 * 3)) & 0xFF; 00030 offset += sizeof(this->data.nsec); 00031 return offset; 00032 } 00033 00034 virtual int deserialize(unsigned char *inbuffer) 00035 { 00036 int offset = 0; 00037 this->data.sec |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00038 this->data.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00039 this->data.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00040 this->data.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00041 offset += sizeof(this->data.sec); 00042 this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00043 this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00044 this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00045 this->data.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00046 offset += sizeof(this->data.nsec); 00047 return offset; 00048 } 00049 00050 const char * getType(){ return "std_msgs/Duration"; }; 00051 const char * getMD5(){ return "3e286caf4241d664e55f3ad380e2ae46"; }; 00052 00053 }; 00054 00055 } 00056 #endif