Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: mbed
MoveGroupResult.h
00001 #ifndef _ROS_moveit_msgs_MoveGroupResult_h 00002 #define _ROS_moveit_msgs_MoveGroupResult_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "moveit_msgs/MoveItErrorCodes.h" 00009 #include "moveit_msgs/RobotState.h" 00010 #include "moveit_msgs/RobotTrajectory.h" 00011 00012 namespace moveit_msgs 00013 { 00014 00015 class MoveGroupResult : public ros::Msg 00016 { 00017 public: 00018 typedef moveit_msgs::MoveItErrorCodes _error_code_type; 00019 _error_code_type error_code; 00020 typedef moveit_msgs::RobotState _trajectory_start_type; 00021 _trajectory_start_type trajectory_start; 00022 typedef moveit_msgs::RobotTrajectory _planned_trajectory_type; 00023 _planned_trajectory_type planned_trajectory; 00024 typedef moveit_msgs::RobotTrajectory _executed_trajectory_type; 00025 _executed_trajectory_type executed_trajectory; 00026 typedef double _planning_time_type; 00027 _planning_time_type planning_time; 00028 00029 MoveGroupResult(): 00030 error_code(), 00031 trajectory_start(), 00032 planned_trajectory(), 00033 executed_trajectory(), 00034 planning_time(0) 00035 { 00036 } 00037 00038 virtual int serialize(unsigned char *outbuffer) const 00039 { 00040 int offset = 0; 00041 offset += this->error_code.serialize(outbuffer + offset); 00042 offset += this->trajectory_start.serialize(outbuffer + offset); 00043 offset += this->planned_trajectory.serialize(outbuffer + offset); 00044 offset += this->executed_trajectory.serialize(outbuffer + offset); 00045 union { 00046 double real; 00047 uint64_t base; 00048 } u_planning_time; 00049 u_planning_time.real = this->planning_time; 00050 *(outbuffer + offset + 0) = (u_planning_time.base >> (8 * 0)) & 0xFF; 00051 *(outbuffer + offset + 1) = (u_planning_time.base >> (8 * 1)) & 0xFF; 00052 *(outbuffer + offset + 2) = (u_planning_time.base >> (8 * 2)) & 0xFF; 00053 *(outbuffer + offset + 3) = (u_planning_time.base >> (8 * 3)) & 0xFF; 00054 *(outbuffer + offset + 4) = (u_planning_time.base >> (8 * 4)) & 0xFF; 00055 *(outbuffer + offset + 5) = (u_planning_time.base >> (8 * 5)) & 0xFF; 00056 *(outbuffer + offset + 6) = (u_planning_time.base >> (8 * 6)) & 0xFF; 00057 *(outbuffer + offset + 7) = (u_planning_time.base >> (8 * 7)) & 0xFF; 00058 offset += sizeof(this->planning_time); 00059 return offset; 00060 } 00061 00062 virtual int deserialize(unsigned char *inbuffer) 00063 { 00064 int offset = 0; 00065 offset += this->error_code.deserialize(inbuffer + offset); 00066 offset += this->trajectory_start.deserialize(inbuffer + offset); 00067 offset += this->planned_trajectory.deserialize(inbuffer + offset); 00068 offset += this->executed_trajectory.deserialize(inbuffer + offset); 00069 union { 00070 double real; 00071 uint64_t base; 00072 } u_planning_time; 00073 u_planning_time.base = 0; 00074 u_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); 00075 u_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); 00076 u_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); 00077 u_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); 00078 u_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); 00079 u_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); 00080 u_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); 00081 u_planning_time.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); 00082 this->planning_time = u_planning_time.real; 00083 offset += sizeof(this->planning_time); 00084 return offset; 00085 } 00086 00087 virtual const char * getType(){ return "moveit_msgs/MoveGroupResult"; }; 00088 virtual const char * getMD5(){ return "34098589d402fee7ae9c3fd413e5a6c6"; }; 00089 00090 }; 00091 00092 } 00093 #endif
Generated on Mon Sep 26 2022 13:47:02 by
