PlanningSceneComponents.h
Go to the documentation of this file.
00001 #ifndef _ROS_moveit_msgs_PlanningSceneComponents_h
00002 #define _ROS_moveit_msgs_PlanningSceneComponents_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 PlanningSceneComponents : public ros::Msg
00013   {
00014     public:
00015       uint32_t components;
00016       enum { SCENE_SETTINGS = 1 };
00017       enum { ROBOT_STATE = 2 };
00018       enum { ROBOT_STATE_ATTACHED_OBJECTS = 4 };
00019       enum { WORLD_OBJECT_NAMES = 8 };
00020       enum { WORLD_OBJECT_GEOMETRY = 16 };
00021       enum { OCTOMAP = 32 };
00022       enum { TRANSFORMS = 64 };
00023       enum { ALLOWED_COLLISION_MATRIX = 128 };
00024       enum { LINK_PADDING_AND_SCALING = 256 };
00025       enum { OBJECT_COLORS = 512 };
00026 
00027     virtual int serialize(unsigned char *outbuffer) const
00028     {
00029       int offset = 0;
00030       *(outbuffer + offset + 0) = (this->components >> (8 * 0)) & 0xFF;
00031       *(outbuffer + offset + 1) = (this->components >> (8 * 1)) & 0xFF;
00032       *(outbuffer + offset + 2) = (this->components >> (8 * 2)) & 0xFF;
00033       *(outbuffer + offset + 3) = (this->components >> (8 * 3)) & 0xFF;
00034       offset += sizeof(this->components);
00035       return offset;
00036     }
00037 
00038     virtual int deserialize(unsigned char *inbuffer)
00039     {
00040       int offset = 0;
00041       this->components =  ((uint32_t) (*(inbuffer + offset)));
00042       this->components |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00043       this->components |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00044       this->components |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00045       offset += sizeof(this->components);
00046      return offset;
00047     }
00048 
00049     const char * getType(){ return "moveit_msgs/PlanningSceneComponents"; };
00050     const char * getMD5(){ return "bc993e784476960b918b6e7ad5bb58ce"; };
00051 
00052   };
00053 
00054 }
00055 #endif


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