catchrobo2022 / Mbed 2 deprecated catchrobo2022_mbed

Dependencies:   mbed

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers MotionPlanResponse.h Source File

MotionPlanResponse.h

00001 #ifndef _ROS_moveit_msgs_MotionPlanResponse_h
00002 #define _ROS_moveit_msgs_MotionPlanResponse_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 "moveit_msgs/RobotTrajectory.h"
00010 #include "moveit_msgs/MoveItErrorCodes.h"
00011 
00012 namespace moveit_msgs
00013 {
00014 
00015   class MotionPlanResponse : public ros::Msg
00016   {
00017     public:
00018       typedef moveit_msgs::RobotState _trajectory_start_type;
00019       _trajectory_start_type trajectory_start;
00020       typedef const char* _group_name_type;
00021       _group_name_type group_name;
00022       typedef moveit_msgs::RobotTrajectory _trajectory_type;
00023       _trajectory_type trajectory;
00024       typedef double _planning_time_type;
00025       _planning_time_type planning_time;
00026       typedef moveit_msgs::MoveItErrorCodes _error_code_type;
00027       _error_code_type error_code;
00028 
00029     MotionPlanResponse():
00030       trajectory_start(),
00031       group_name(""),
00032       trajectory(),
00033       planning_time(0),
00034       error_code()
00035     {
00036     }
00037 
00038     virtual int serialize(unsigned char *outbuffer) const
00039     {
00040       int offset = 0;
00041       offset += this->trajectory_start.serialize(outbuffer + offset);
00042       uint32_t length_group_name = strlen(this->group_name);
00043       varToArr(outbuffer + offset, length_group_name);
00044       offset += 4;
00045       memcpy(outbuffer + offset, this->group_name, length_group_name);
00046       offset += length_group_name;
00047       offset += this->trajectory.serialize(outbuffer + offset);
00048       union {
00049         double real;
00050         uint64_t base;
00051       } u_planning_time;
00052       u_planning_time.real = this->planning_time;
00053       *(outbuffer + offset + 0) = (u_planning_time.base >> (8 * 0)) & 0xFF;
00054       *(outbuffer + offset + 1) = (u_planning_time.base >> (8 * 1)) & 0xFF;
00055       *(outbuffer + offset + 2) = (u_planning_time.base >> (8 * 2)) & 0xFF;
00056       *(outbuffer + offset + 3) = (u_planning_time.base >> (8 * 3)) & 0xFF;
00057       *(outbuffer + offset + 4) = (u_planning_time.base >> (8 * 4)) & 0xFF;
00058       *(outbuffer + offset + 5) = (u_planning_time.base >> (8 * 5)) & 0xFF;
00059       *(outbuffer + offset + 6) = (u_planning_time.base >> (8 * 6)) & 0xFF;
00060       *(outbuffer + offset + 7) = (u_planning_time.base >> (8 * 7)) & 0xFF;
00061       offset += sizeof(this->planning_time);
00062       offset += this->error_code.serialize(outbuffer + offset);
00063       return offset;
00064     }
00065 
00066     virtual int deserialize(unsigned char *inbuffer)
00067     {
00068       int offset = 0;
00069       offset += this->trajectory_start.deserialize(inbuffer + offset);
00070       uint32_t length_group_name;
00071       arrToVar(length_group_name, (inbuffer + offset));
00072       offset += 4;
00073       for(unsigned int k= offset; k< offset+length_group_name; ++k){
00074           inbuffer[k-1]=inbuffer[k];
00075       }
00076       inbuffer[offset+length_group_name-1]=0;
00077       this->group_name = (char *)(inbuffer + offset-1);
00078       offset += length_group_name;
00079       offset += this->trajectory.deserialize(inbuffer + offset);
00080       union {
00081         double real;
00082         uint64_t base;
00083       } u_planning_time;
00084       u_planning_time.base = 0;
00085       u_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0);
00086       u_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1);
00087       u_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2);
00088       u_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3);
00089       u_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4);
00090       u_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5);
00091       u_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6);
00092       u_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7);
00093       this->planning_time = u_planning_time.real;
00094       offset += sizeof(this->planning_time);
00095       offset += this->error_code.deserialize(inbuffer + offset);
00096      return offset;
00097     }
00098 
00099     virtual const char * getType(){ return "moveit_msgs/MotionPlanResponse"; };
00100     virtual const char * getMD5(){ return "e493d20ab41424c48f671e152c70fc74"; };
00101 
00102   };
00103 
00104 }
00105 #endif