MultiDOFJointTrajectoryPoint.h
Go to the documentation of this file.
00001 #ifndef _ROS_trajectory_msgs_MultiDOFJointTrajectoryPoint_h
00002 #define _ROS_trajectory_msgs_MultiDOFJointTrajectoryPoint_h
00003 
00004 #include <stdint.h>
00005 #include <string.h>
00006 #include <stdlib.h>
00007 #include "ros/msg.h"
00008 #include "geometry_msgs/Transform.h"
00009 #include "geometry_msgs/Twist.h"
00010 #include "ros/duration.h"
00011 
00012 namespace trajectory_msgs
00013 {
00014 
00015   class MultiDOFJointTrajectoryPoint : public ros::Msg
00016   {
00017     public:
00018       uint8_t transforms_length;
00019       geometry_msgs::Transform st_transforms;
00020       geometry_msgs::Transform * transforms;
00021       uint8_t velocities_length;
00022       geometry_msgs::Twist st_velocities;
00023       geometry_msgs::Twist * velocities;
00024       uint8_t accelerations_length;
00025       geometry_msgs::Twist st_accelerations;
00026       geometry_msgs::Twist * accelerations;
00027       ros::Duration time_from_start;
00028 
00029     virtual int serialize(unsigned char *outbuffer) const
00030     {
00031       int offset = 0;
00032       *(outbuffer + offset++) = transforms_length;
00033       *(outbuffer + offset++) = 0;
00034       *(outbuffer + offset++) = 0;
00035       *(outbuffer + offset++) = 0;
00036       for( uint8_t i = 0; i < transforms_length; i++){
00037       offset += this->transforms[i].serialize(outbuffer + offset);
00038       }
00039       *(outbuffer + offset++) = velocities_length;
00040       *(outbuffer + offset++) = 0;
00041       *(outbuffer + offset++) = 0;
00042       *(outbuffer + offset++) = 0;
00043       for( uint8_t i = 0; i < velocities_length; i++){
00044       offset += this->velocities[i].serialize(outbuffer + offset);
00045       }
00046       *(outbuffer + offset++) = accelerations_length;
00047       *(outbuffer + offset++) = 0;
00048       *(outbuffer + offset++) = 0;
00049       *(outbuffer + offset++) = 0;
00050       for( uint8_t i = 0; i < accelerations_length; i++){
00051       offset += this->accelerations[i].serialize(outbuffer + offset);
00052       }
00053       *(outbuffer + offset + 0) = (this->time_from_start.sec >> (8 * 0)) & 0xFF;
00054       *(outbuffer + offset + 1) = (this->time_from_start.sec >> (8 * 1)) & 0xFF;
00055       *(outbuffer + offset + 2) = (this->time_from_start.sec >> (8 * 2)) & 0xFF;
00056       *(outbuffer + offset + 3) = (this->time_from_start.sec >> (8 * 3)) & 0xFF;
00057       offset += sizeof(this->time_from_start.sec);
00058       *(outbuffer + offset + 0) = (this->time_from_start.nsec >> (8 * 0)) & 0xFF;
00059       *(outbuffer + offset + 1) = (this->time_from_start.nsec >> (8 * 1)) & 0xFF;
00060       *(outbuffer + offset + 2) = (this->time_from_start.nsec >> (8 * 2)) & 0xFF;
00061       *(outbuffer + offset + 3) = (this->time_from_start.nsec >> (8 * 3)) & 0xFF;
00062       offset += sizeof(this->time_from_start.nsec);
00063       return offset;
00064     }
00065 
00066     virtual int deserialize(unsigned char *inbuffer)
00067     {
00068       int offset = 0;
00069       uint8_t transforms_lengthT = *(inbuffer + offset++);
00070       if(transforms_lengthT > transforms_length)
00071         this->transforms = (geometry_msgs::Transform*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::Transform));
00072       offset += 3;
00073       transforms_length = transforms_lengthT;
00074       for( uint8_t i = 0; i < transforms_length; i++){
00075       offset += this->st_transforms.deserialize(inbuffer + offset);
00076         memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::Transform));
00077       }
00078       uint8_t velocities_lengthT = *(inbuffer + offset++);
00079       if(velocities_lengthT > velocities_length)
00080         this->velocities = (geometry_msgs::Twist*)realloc(this->velocities, velocities_lengthT * sizeof(geometry_msgs::Twist));
00081       offset += 3;
00082       velocities_length = velocities_lengthT;
00083       for( uint8_t i = 0; i < velocities_length; i++){
00084       offset += this->st_velocities.deserialize(inbuffer + offset);
00085         memcpy( &(this->velocities[i]), &(this->st_velocities), sizeof(geometry_msgs::Twist));
00086       }
00087       uint8_t accelerations_lengthT = *(inbuffer + offset++);
00088       if(accelerations_lengthT > accelerations_length)
00089         this->accelerations = (geometry_msgs::Twist*)realloc(this->accelerations, accelerations_lengthT * sizeof(geometry_msgs::Twist));
00090       offset += 3;
00091       accelerations_length = accelerations_lengthT;
00092       for( uint8_t i = 0; i < accelerations_length; i++){
00093       offset += this->st_accelerations.deserialize(inbuffer + offset);
00094         memcpy( &(this->accelerations[i]), &(this->st_accelerations), sizeof(geometry_msgs::Twist));
00095       }
00096       this->time_from_start.sec =  ((uint32_t) (*(inbuffer + offset)));
00097       this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00098       this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00099       this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00100       offset += sizeof(this->time_from_start.sec);
00101       this->time_from_start.nsec =  ((uint32_t) (*(inbuffer + offset)));
00102       this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00103       this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00104       this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00105       offset += sizeof(this->time_from_start.nsec);
00106      return offset;
00107     }
00108 
00109     const char * getType(){ return "trajectory_msgs/MultiDOFJointTrajectoryPoint"; };
00110     const char * getMD5(){ return "3ebe08d1abd5b65862d50e09430db776"; };
00111 
00112   };
00113 
00114 }
00115 #endif


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