GetNormal.h
Go to the documentation of this file.
00001 #ifndef _ROS_SERVICE_GetNormal_h
00002 #define _ROS_SERVICE_GetNormal_h
00003 #include <stdint.h>
00004 #include <string.h>
00005 #include <stdlib.h>
00006 #include "ros/msg.h"
00007 #include "geometry_msgs/PointStamped.h"
00008 #include "geometry_msgs/Vector3.h"
00009 
00010 namespace hector_nav_msgs
00011 {
00012 
00013 static const char GETNORMAL[] = "hector_nav_msgs/GetNormal";
00014 
00015   class GetNormalRequest : public ros::Msg
00016   {
00017     public:
00018       geometry_msgs::PointStamped point;
00019 
00020     virtual int serialize(unsigned char *outbuffer) const
00021     {
00022       int offset = 0;
00023       offset += this->point.serialize(outbuffer + offset);
00024       return offset;
00025     }
00026 
00027     virtual int deserialize(unsigned char *inbuffer)
00028     {
00029       int offset = 0;
00030       offset += this->point.deserialize(inbuffer + offset);
00031      return offset;
00032     }
00033 
00034     const char * getType(){ return GETNORMAL; };
00035     const char * getMD5(){ return "47dfdbd810b48d0a47b7ad67e4191bcc"; };
00036 
00037   };
00038 
00039   class GetNormalResponse : public ros::Msg
00040   {
00041     public:
00042       geometry_msgs::Vector3 normal;
00043       float yaw;
00044 
00045     virtual int serialize(unsigned char *outbuffer) const
00046     {
00047       int offset = 0;
00048       offset += this->normal.serialize(outbuffer + offset);
00049       union {
00050         float real;
00051         uint32_t base;
00052       } u_yaw;
00053       u_yaw.real = this->yaw;
00054       *(outbuffer + offset + 0) = (u_yaw.base >> (8 * 0)) & 0xFF;
00055       *(outbuffer + offset + 1) = (u_yaw.base >> (8 * 1)) & 0xFF;
00056       *(outbuffer + offset + 2) = (u_yaw.base >> (8 * 2)) & 0xFF;
00057       *(outbuffer + offset + 3) = (u_yaw.base >> (8 * 3)) & 0xFF;
00058       offset += sizeof(this->yaw);
00059       return offset;
00060     }
00061 
00062     virtual int deserialize(unsigned char *inbuffer)
00063     {
00064       int offset = 0;
00065       offset += this->normal.deserialize(inbuffer + offset);
00066       union {
00067         float real;
00068         uint32_t base;
00069       } u_yaw;
00070       u_yaw.base = 0;
00071       u_yaw.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
00072       u_yaw.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00073       u_yaw.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00074       u_yaw.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00075       this->yaw = u_yaw.real;
00076       offset += sizeof(this->yaw);
00077      return offset;
00078     }
00079 
00080     const char * getType(){ return GETNORMAL; };
00081     const char * getMD5(){ return "8ea5d051594753307ebd995c02db60a3"; };
00082 
00083   };
00084 
00085   class GetNormal {
00086     public:
00087     typedef GetNormalRequest Request;
00088     typedef GetNormalResponse Response;
00089   };
00090 
00091 }
00092 #endif


ric_mc
Author(s): RoboTiCan
autogenerated on Thu Aug 27 2015 14:39:49