PlanningScene.h
Go to the documentation of this file.
00001 #ifndef _ROS_moveit_msgs_PlanningScene_h
00002 #define _ROS_moveit_msgs_PlanningScene_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "moveit_msgs/RobotState.h"
00009 #include "geometry_msgs/TransformStamped.h"
00010 #include "moveit_msgs/AllowedCollisionMatrix.h"
00011 #include "moveit_msgs/LinkPadding.h"
00012 #include "moveit_msgs/LinkScale.h"
00013 #include "moveit_msgs/ObjectColor.h"
00014 #include "moveit_msgs/PlanningSceneWorld.h"
00015 
00016 namespace moveit_msgs
00017 {
00018 
00019   class PlanningScene : public ros::Msg
00020   {
00021     public:
00022       const char* name;
00023       moveit_msgs::RobotState robot_state;
00024       const char* robot_model_name;
00025       uint8_t fixed_frame_transforms_length;
00026       geometry_msgs::TransformStamped st_fixed_frame_transforms;
00027       geometry_msgs::TransformStamped * fixed_frame_transforms;
00028       moveit_msgs::AllowedCollisionMatrix allowed_collision_matrix;
00029       uint8_t link_padding_length;
00030       moveit_msgs::LinkPadding st_link_padding;
00031       moveit_msgs::LinkPadding * link_padding;
00032       uint8_t link_scale_length;
00033       moveit_msgs::LinkScale st_link_scale;
00034       moveit_msgs::LinkScale * link_scale;
00035       uint8_t object_colors_length;
00036       moveit_msgs::ObjectColor st_object_colors;
00037       moveit_msgs::ObjectColor * object_colors;
00038       moveit_msgs::PlanningSceneWorld world;
00039       bool is_diff;
00040 
00041     virtual int serialize(unsigned char *outbuffer) const
00042     {
00043       int offset = 0;
00044       uint32_t length_name = strlen(this->name);
00045       memcpy(outbuffer + offset, &length_name, sizeof(uint32_t));
00046       offset += 4;
00047       memcpy(outbuffer + offset, this->name, length_name);
00048       offset += length_name;
00049       offset += this->robot_state.serialize(outbuffer + offset);
00050       uint32_t length_robot_model_name = strlen(this->robot_model_name);
00051       memcpy(outbuffer + offset, &length_robot_model_name, sizeof(uint32_t));
00052       offset += 4;
00053       memcpy(outbuffer + offset, this->robot_model_name, length_robot_model_name);
00054       offset += length_robot_model_name;
00055       *(outbuffer + offset++) = fixed_frame_transforms_length;
00056       *(outbuffer + offset++) = 0;
00057       *(outbuffer + offset++) = 0;
00058       *(outbuffer + offset++) = 0;
00059       for( uint8_t i = 0; i < fixed_frame_transforms_length; i++){
00060       offset += this->fixed_frame_transforms[i].serialize(outbuffer + offset);
00061       }
00062       offset += this->allowed_collision_matrix.serialize(outbuffer + offset);
00063       *(outbuffer + offset++) = link_padding_length;
00064       *(outbuffer + offset++) = 0;
00065       *(outbuffer + offset++) = 0;
00066       *(outbuffer + offset++) = 0;
00067       for( uint8_t i = 0; i < link_padding_length; i++){
00068       offset += this->link_padding[i].serialize(outbuffer + offset);
00069       }
00070       *(outbuffer + offset++) = link_scale_length;
00071       *(outbuffer + offset++) = 0;
00072       *(outbuffer + offset++) = 0;
00073       *(outbuffer + offset++) = 0;
00074       for( uint8_t i = 0; i < link_scale_length; i++){
00075       offset += this->link_scale[i].serialize(outbuffer + offset);
00076       }
00077       *(outbuffer + offset++) = object_colors_length;
00078       *(outbuffer + offset++) = 0;
00079       *(outbuffer + offset++) = 0;
00080       *(outbuffer + offset++) = 0;
00081       for( uint8_t i = 0; i < object_colors_length; i++){
00082       offset += this->object_colors[i].serialize(outbuffer + offset);
00083       }
00084       offset += this->world.serialize(outbuffer + offset);
00085       union {
00086         bool real;
00087         uint8_t base;
00088       } u_is_diff;
00089       u_is_diff.real = this->is_diff;
00090       *(outbuffer + offset + 0) = (u_is_diff.base >> (8 * 0)) & 0xFF;
00091       offset += sizeof(this->is_diff);
00092       return offset;
00093     }
00094 
00095     virtual int deserialize(unsigned char *inbuffer)
00096     {
00097       int offset = 0;
00098       uint32_t length_name;
00099       memcpy(&length_name, (inbuffer + offset), sizeof(uint32_t));
00100       offset += 4;
00101       for(unsigned int k= offset; k< offset+length_name; ++k){
00102           inbuffer[k-1]=inbuffer[k];
00103       }
00104       inbuffer[offset+length_name-1]=0;
00105       this->name = (char *)(inbuffer + offset-1);
00106       offset += length_name;
00107       offset += this->robot_state.deserialize(inbuffer + offset);
00108       uint32_t length_robot_model_name;
00109       memcpy(&length_robot_model_name, (inbuffer + offset), sizeof(uint32_t));
00110       offset += 4;
00111       for(unsigned int k= offset; k< offset+length_robot_model_name; ++k){
00112           inbuffer[k-1]=inbuffer[k];
00113       }
00114       inbuffer[offset+length_robot_model_name-1]=0;
00115       this->robot_model_name = (char *)(inbuffer + offset-1);
00116       offset += length_robot_model_name;
00117       uint8_t fixed_frame_transforms_lengthT = *(inbuffer + offset++);
00118       if(fixed_frame_transforms_lengthT > fixed_frame_transforms_length)
00119         this->fixed_frame_transforms = (geometry_msgs::TransformStamped*)realloc(this->fixed_frame_transforms, fixed_frame_transforms_lengthT * sizeof(geometry_msgs::TransformStamped));
00120       offset += 3;
00121       fixed_frame_transforms_length = fixed_frame_transforms_lengthT;
00122       for( uint8_t i = 0; i < fixed_frame_transforms_length; i++){
00123       offset += this->st_fixed_frame_transforms.deserialize(inbuffer + offset);
00124         memcpy( &(this->fixed_frame_transforms[i]), &(this->st_fixed_frame_transforms), sizeof(geometry_msgs::TransformStamped));
00125       }
00126       offset += this->allowed_collision_matrix.deserialize(inbuffer + offset);
00127       uint8_t link_padding_lengthT = *(inbuffer + offset++);
00128       if(link_padding_lengthT > link_padding_length)
00129         this->link_padding = (moveit_msgs::LinkPadding*)realloc(this->link_padding, link_padding_lengthT * sizeof(moveit_msgs::LinkPadding));
00130       offset += 3;
00131       link_padding_length = link_padding_lengthT;
00132       for( uint8_t i = 0; i < link_padding_length; i++){
00133       offset += this->st_link_padding.deserialize(inbuffer + offset);
00134         memcpy( &(this->link_padding[i]), &(this->st_link_padding), sizeof(moveit_msgs::LinkPadding));
00135       }
00136       uint8_t link_scale_lengthT = *(inbuffer + offset++);
00137       if(link_scale_lengthT > link_scale_length)
00138         this->link_scale = (moveit_msgs::LinkScale*)realloc(this->link_scale, link_scale_lengthT * sizeof(moveit_msgs::LinkScale));
00139       offset += 3;
00140       link_scale_length = link_scale_lengthT;
00141       for( uint8_t i = 0; i < link_scale_length; i++){
00142       offset += this->st_link_scale.deserialize(inbuffer + offset);
00143         memcpy( &(this->link_scale[i]), &(this->st_link_scale), sizeof(moveit_msgs::LinkScale));
00144       }
00145       uint8_t object_colors_lengthT = *(inbuffer + offset++);
00146       if(object_colors_lengthT > object_colors_length)
00147         this->object_colors = (moveit_msgs::ObjectColor*)realloc(this->object_colors, object_colors_lengthT * sizeof(moveit_msgs::ObjectColor));
00148       offset += 3;
00149       object_colors_length = object_colors_lengthT;
00150       for( uint8_t i = 0; i < object_colors_length; i++){
00151       offset += this->st_object_colors.deserialize(inbuffer + offset);
00152         memcpy( &(this->object_colors[i]), &(this->st_object_colors), sizeof(moveit_msgs::ObjectColor));
00153       }
00154       offset += this->world.deserialize(inbuffer + offset);
00155       union {
00156         bool real;
00157         uint8_t base;
00158       } u_is_diff;
00159       u_is_diff.base = 0;
00160       u_is_diff.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00161       this->is_diff = u_is_diff.real;
00162       offset += sizeof(this->is_diff);
00163      return offset;
00164     }
00165 
00166     const char * getType(){ return "moveit_msgs/PlanningScene"; };
00167     const char * getMD5(){ return "89aac6d20db967ba716cba5a86b1b9d5"; };
00168 
00169   };
00170 
00171 }
00172 #endif


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