00001 #ifndef _ROS_moveit_msgs_DisplayTrajectory_h 00002 #define _ROS_moveit_msgs_DisplayTrajectory_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "moveit_msgs/RobotTrajectory.h" 00009 #include "moveit_msgs/RobotState.h" 00010 00011 namespace moveit_msgs 00012 { 00013 00014 class DisplayTrajectory : public ros::Msg 00015 { 00016 public: 00017 const char* model_id; 00018 uint8_t trajectory_length; 00019 moveit_msgs::RobotTrajectory st_trajectory; 00020 moveit_msgs::RobotTrajectory * trajectory; 00021 moveit_msgs::RobotState trajectory_start; 00022 00023 virtual int serialize(unsigned char *outbuffer) const 00024 { 00025 int offset = 0; 00026 uint32_t length_model_id = strlen(this->model_id); 00027 memcpy(outbuffer + offset, &length_model_id, sizeof(uint32_t)); 00028 offset += 4; 00029 memcpy(outbuffer + offset, this->model_id, length_model_id); 00030 offset += length_model_id; 00031 *(outbuffer + offset++) = trajectory_length; 00032 *(outbuffer + offset++) = 0; 00033 *(outbuffer + offset++) = 0; 00034 *(outbuffer + offset++) = 0; 00035 for( uint8_t i = 0; i < trajectory_length; i++){ 00036 offset += this->trajectory[i].serialize(outbuffer + offset); 00037 } 00038 offset += this->trajectory_start.serialize(outbuffer + offset); 00039 return offset; 00040 } 00041 00042 virtual int deserialize(unsigned char *inbuffer) 00043 { 00044 int offset = 0; 00045 uint32_t length_model_id; 00046 memcpy(&length_model_id, (inbuffer + offset), sizeof(uint32_t)); 00047 offset += 4; 00048 for(unsigned int k= offset; k< offset+length_model_id; ++k){ 00049 inbuffer[k-1]=inbuffer[k]; 00050 } 00051 inbuffer[offset+length_model_id-1]=0; 00052 this->model_id = (char *)(inbuffer + offset-1); 00053 offset += length_model_id; 00054 uint8_t trajectory_lengthT = *(inbuffer + offset++); 00055 if(trajectory_lengthT > trajectory_length) 00056 this->trajectory = (moveit_msgs::RobotTrajectory*)realloc(this->trajectory, trajectory_lengthT * sizeof(moveit_msgs::RobotTrajectory)); 00057 offset += 3; 00058 trajectory_length = trajectory_lengthT; 00059 for( uint8_t i = 0; i < trajectory_length; i++){ 00060 offset += this->st_trajectory.deserialize(inbuffer + offset); 00061 memcpy( &(this->trajectory[i]), &(this->st_trajectory), sizeof(moveit_msgs::RobotTrajectory)); 00062 } 00063 offset += this->trajectory_start.deserialize(inbuffer + offset); 00064 return offset; 00065 } 00066 00067 const char * getType(){ return "moveit_msgs/DisplayTrajectory"; }; 00068 const char * getMD5(){ return "c3c039261ab9e8a11457dac56b6316c8"; }; 00069 00070 }; 00071 00072 } 00073 #endif