AllowedCollisionEntry.h
Go to the documentation of this file.
00001 #ifndef _ROS_moveit_msgs_AllowedCollisionEntry_h
00002 #define _ROS_moveit_msgs_AllowedCollisionEntry_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 
00009 namespace moveit_msgs
00010 {
00011 
00012   class AllowedCollisionEntry : public ros::Msg
00013   {
00014     public:
00015       uint8_t enabled_length;
00016       bool st_enabled;
00017       bool * enabled;
00018 
00019     virtual int serialize(unsigned char *outbuffer) const
00020     {
00021       int offset = 0;
00022       *(outbuffer + offset++) = enabled_length;
00023       *(outbuffer + offset++) = 0;
00024       *(outbuffer + offset++) = 0;
00025       *(outbuffer + offset++) = 0;
00026       for( uint8_t i = 0; i < enabled_length; i++){
00027       union {
00028         bool real;
00029         uint8_t base;
00030       } u_enabledi;
00031       u_enabledi.real = this->enabled[i];
00032       *(outbuffer + offset + 0) = (u_enabledi.base >> (8 * 0)) & 0xFF;
00033       offset += sizeof(this->enabled[i]);
00034       }
00035       return offset;
00036     }
00037 
00038     virtual int deserialize(unsigned char *inbuffer)
00039     {
00040       int offset = 0;
00041       uint8_t enabled_lengthT = *(inbuffer + offset++);
00042       if(enabled_lengthT > enabled_length)
00043         this->enabled = (bool*)realloc(this->enabled, enabled_lengthT * sizeof(bool));
00044       offset += 3;
00045       enabled_length = enabled_lengthT;
00046       for( uint8_t i = 0; i < enabled_length; i++){
00047       union {
00048         bool real;
00049         uint8_t base;
00050       } u_st_enabled;
00051       u_st_enabled.base = 0;
00052       u_st_enabled.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00053       this->st_enabled = u_st_enabled.real;
00054       offset += sizeof(this->st_enabled);
00055         memcpy( &(this->enabled[i]), &(this->st_enabled), sizeof(bool));
00056       }
00057      return offset;
00058     }
00059 
00060     const char * getType(){ return "moveit_msgs/AllowedCollisionEntry"; };
00061     const char * getMD5(){ return "90d1ae1850840724bb043562fe3285fc"; };
00062 
00063   };
00064 
00065 }
00066 #endif


ric_mc
Author(s): RoboTiCan
autogenerated on Fri May 20 2016 03:48:54