ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information

Dependencies:   BufferedSerial

Dependents:   rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers MultiDOFJointTrajectoryPoint.h Source File

MultiDOFJointTrajectoryPoint.h

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     MultiDOFJointTrajectoryPoint():
00030       transforms_length(0), transforms(NULL),
00031       velocities_length(0), velocities(NULL),
00032       accelerations_length(0), accelerations(NULL),
00033       time_from_start()
00034     {
00035     }
00036 
00037     virtual int serialize(unsigned char *outbuffer) const
00038     {
00039       int offset = 0;
00040       *(outbuffer + offset++) = transforms_length;
00041       *(outbuffer + offset++) = 0;
00042       *(outbuffer + offset++) = 0;
00043       *(outbuffer + offset++) = 0;
00044       for( uint8_t i = 0; i < transforms_length; i++){
00045       offset += this->transforms[i].serialize(outbuffer + offset);
00046       }
00047       *(outbuffer + offset++) = velocities_length;
00048       *(outbuffer + offset++) = 0;
00049       *(outbuffer + offset++) = 0;
00050       *(outbuffer + offset++) = 0;
00051       for( uint8_t i = 0; i < velocities_length; i++){
00052       offset += this->velocities[i].serialize(outbuffer + offset);
00053       }
00054       *(outbuffer + offset++) = accelerations_length;
00055       *(outbuffer + offset++) = 0;
00056       *(outbuffer + offset++) = 0;
00057       *(outbuffer + offset++) = 0;
00058       for( uint8_t i = 0; i < accelerations_length; i++){
00059       offset += this->accelerations[i].serialize(outbuffer + offset);
00060       }
00061       *(outbuffer + offset + 0) = (this->time_from_start.sec >> (8 * 0)) & 0xFF;
00062       *(outbuffer + offset + 1) = (this->time_from_start.sec >> (8 * 1)) & 0xFF;
00063       *(outbuffer + offset + 2) = (this->time_from_start.sec >> (8 * 2)) & 0xFF;
00064       *(outbuffer + offset + 3) = (this->time_from_start.sec >> (8 * 3)) & 0xFF;
00065       offset += sizeof(this->time_from_start.sec);
00066       *(outbuffer + offset + 0) = (this->time_from_start.nsec >> (8 * 0)) & 0xFF;
00067       *(outbuffer + offset + 1) = (this->time_from_start.nsec >> (8 * 1)) & 0xFF;
00068       *(outbuffer + offset + 2) = (this->time_from_start.nsec >> (8 * 2)) & 0xFF;
00069       *(outbuffer + offset + 3) = (this->time_from_start.nsec >> (8 * 3)) & 0xFF;
00070       offset += sizeof(this->time_from_start.nsec);
00071       return offset;
00072     }
00073 
00074     virtual int deserialize(unsigned char *inbuffer)
00075     {
00076       int offset = 0;
00077       uint8_t transforms_lengthT = *(inbuffer + offset++);
00078       if(transforms_lengthT > transforms_length)
00079         this->transforms = (geometry_msgs::Transform*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::Transform));
00080       offset += 3;
00081       transforms_length = transforms_lengthT;
00082       for( uint8_t i = 0; i < transforms_length; i++){
00083       offset += this->st_transforms.deserialize(inbuffer + offset);
00084         memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::Transform));
00085       }
00086       uint8_t velocities_lengthT = *(inbuffer + offset++);
00087       if(velocities_lengthT > velocities_length)
00088         this->velocities = (geometry_msgs::Twist*)realloc(this->velocities, velocities_lengthT * sizeof(geometry_msgs::Twist));
00089       offset += 3;
00090       velocities_length = velocities_lengthT;
00091       for( uint8_t i = 0; i < velocities_length; i++){
00092       offset += this->st_velocities.deserialize(inbuffer + offset);
00093         memcpy( &(this->velocities[i]), &(this->st_velocities), sizeof(geometry_msgs::Twist));
00094       }
00095       uint8_t accelerations_lengthT = *(inbuffer + offset++);
00096       if(accelerations_lengthT > accelerations_length)
00097         this->accelerations = (geometry_msgs::Twist*)realloc(this->accelerations, accelerations_lengthT * sizeof(geometry_msgs::Twist));
00098       offset += 3;
00099       accelerations_length = accelerations_lengthT;
00100       for( uint8_t i = 0; i < accelerations_length; i++){
00101       offset += this->st_accelerations.deserialize(inbuffer + offset);
00102         memcpy( &(this->accelerations[i]), &(this->st_accelerations), sizeof(geometry_msgs::Twist));
00103       }
00104       this->time_from_start.sec =  ((uint32_t) (*(inbuffer + offset)));
00105       this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00106       this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00107       this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00108       offset += sizeof(this->time_from_start.sec);
00109       this->time_from_start.nsec =  ((uint32_t) (*(inbuffer + offset)));
00110       this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00111       this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00112       this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00113       offset += sizeof(this->time_from_start.nsec);
00114      return offset;
00115     }
00116 
00117     const char * getType(){ return "trajectory_msgs/MultiDOFJointTrajectoryPoint"; };
00118     const char * getMD5(){ return "3ebe08d1abd5b65862d50e09430db776"; };
00119 
00120   };
00121 
00122 }
00123 #endif