ExecuteKnownTrajectory.h
Go to the documentation of this file.
00001 #ifndef _ROS_SERVICE_ExecuteKnownTrajectory_h
00002 #define _ROS_SERVICE_ExecuteKnownTrajectory_h
00003 #include <stdint.h>
00004 #include <string.h>
00005 #include <stdlib.h>
00006 #include "ros/msg.h"
00007 #include "moveit_msgs/MoveItErrorCodes.h"
00008 #include "moveit_msgs/RobotTrajectory.h"
00009 
00010 namespace moveit_msgs
00011 {
00012 
00013 static const char EXECUTEKNOWNTRAJECTORY[] = "moveit_msgs/ExecuteKnownTrajectory";
00014 
00015   class ExecuteKnownTrajectoryRequest : public ros::Msg
00016   {
00017     public:
00018       moveit_msgs::RobotTrajectory trajectory;
00019       bool wait_for_execution;
00020 
00021     virtual int serialize(unsigned char *outbuffer) const
00022     {
00023       int offset = 0;
00024       offset += this->trajectory.serialize(outbuffer + offset);
00025       union {
00026         bool real;
00027         uint8_t base;
00028       } u_wait_for_execution;
00029       u_wait_for_execution.real = this->wait_for_execution;
00030       *(outbuffer + offset + 0) = (u_wait_for_execution.base >> (8 * 0)) & 0xFF;
00031       offset += sizeof(this->wait_for_execution);
00032       return offset;
00033     }
00034 
00035     virtual int deserialize(unsigned char *inbuffer)
00036     {
00037       int offset = 0;
00038       offset += this->trajectory.deserialize(inbuffer + offset);
00039       union {
00040         bool real;
00041         uint8_t base;
00042       } u_wait_for_execution;
00043       u_wait_for_execution.base = 0;
00044       u_wait_for_execution.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00045       this->wait_for_execution = u_wait_for_execution.real;
00046       offset += sizeof(this->wait_for_execution);
00047      return offset;
00048     }
00049 
00050     const char * getType(){ return EXECUTEKNOWNTRAJECTORY; };
00051     const char * getMD5(){ return "2a3d2a0b337c6a27da4468bb351928e5"; };
00052 
00053   };
00054 
00055   class ExecuteKnownTrajectoryResponse : public ros::Msg
00056   {
00057     public:
00058       moveit_msgs::MoveItErrorCodes error_code;
00059 
00060     virtual int serialize(unsigned char *outbuffer) const
00061     {
00062       int offset = 0;
00063       offset += this->error_code.serialize(outbuffer + offset);
00064       return offset;
00065     }
00066 
00067     virtual int deserialize(unsigned char *inbuffer)
00068     {
00069       int offset = 0;
00070       offset += this->error_code.deserialize(inbuffer + offset);
00071      return offset;
00072     }
00073 
00074     const char * getType(){ return EXECUTEKNOWNTRAJECTORY; };
00075     const char * getMD5(){ return "1f7ab918f5d0c5312f25263d3d688122"; };
00076 
00077   };
00078 
00079   class ExecuteKnownTrajectory {
00080     public:
00081     typedef ExecuteKnownTrajectoryRequest Request;
00082     typedef ExecuteKnownTrajectoryResponse Response;
00083   };
00084 
00085 }
00086 #endif


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