LAB

Dependencies:   BufferedSerial

Dependents:   ROS_Remote_Car

Fork of ros_lib_indigo by Gary Servin

Committer:
MechanicalThomas
Date:
Thu Apr 19 14:57:05 2018 +0000
Revision:
1:1523bf60b9a9
Parent:
0:fd24f7ca9688
000;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
garyservin 0:fd24f7ca9688 1 #ifndef _ROS_trajectory_msgs_MultiDOFJointTrajectoryPoint_h
garyservin 0:fd24f7ca9688 2 #define _ROS_trajectory_msgs_MultiDOFJointTrajectoryPoint_h
garyservin 0:fd24f7ca9688 3
garyservin 0:fd24f7ca9688 4 #include <stdint.h>
garyservin 0:fd24f7ca9688 5 #include <string.h>
garyservin 0:fd24f7ca9688 6 #include <stdlib.h>
garyservin 0:fd24f7ca9688 7 #include "ros/msg.h"
garyservin 0:fd24f7ca9688 8 #include "geometry_msgs/Transform.h"
garyservin 0:fd24f7ca9688 9 #include "geometry_msgs/Twist.h"
garyservin 0:fd24f7ca9688 10 #include "ros/duration.h"
garyservin 0:fd24f7ca9688 11
garyservin 0:fd24f7ca9688 12 namespace trajectory_msgs
garyservin 0:fd24f7ca9688 13 {
garyservin 0:fd24f7ca9688 14
garyservin 0:fd24f7ca9688 15 class MultiDOFJointTrajectoryPoint : public ros::Msg
garyservin 0:fd24f7ca9688 16 {
garyservin 0:fd24f7ca9688 17 public:
garyservin 0:fd24f7ca9688 18 uint8_t transforms_length;
garyservin 0:fd24f7ca9688 19 geometry_msgs::Transform st_transforms;
garyservin 0:fd24f7ca9688 20 geometry_msgs::Transform * transforms;
garyservin 0:fd24f7ca9688 21 uint8_t velocities_length;
garyservin 0:fd24f7ca9688 22 geometry_msgs::Twist st_velocities;
garyservin 0:fd24f7ca9688 23 geometry_msgs::Twist * velocities;
garyservin 0:fd24f7ca9688 24 uint8_t accelerations_length;
garyservin 0:fd24f7ca9688 25 geometry_msgs::Twist st_accelerations;
garyservin 0:fd24f7ca9688 26 geometry_msgs::Twist * accelerations;
garyservin 0:fd24f7ca9688 27 ros::Duration time_from_start;
garyservin 0:fd24f7ca9688 28
garyservin 0:fd24f7ca9688 29 MultiDOFJointTrajectoryPoint():
garyservin 0:fd24f7ca9688 30 transforms_length(0), transforms(NULL),
garyservin 0:fd24f7ca9688 31 velocities_length(0), velocities(NULL),
garyservin 0:fd24f7ca9688 32 accelerations_length(0), accelerations(NULL),
garyservin 0:fd24f7ca9688 33 time_from_start()
garyservin 0:fd24f7ca9688 34 {
garyservin 0:fd24f7ca9688 35 }
garyservin 0:fd24f7ca9688 36
garyservin 0:fd24f7ca9688 37 virtual int serialize(unsigned char *outbuffer) const
garyservin 0:fd24f7ca9688 38 {
garyservin 0:fd24f7ca9688 39 int offset = 0;
garyservin 0:fd24f7ca9688 40 *(outbuffer + offset++) = transforms_length;
garyservin 0:fd24f7ca9688 41 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 42 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 43 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 44 for( uint8_t i = 0; i < transforms_length; i++){
garyservin 0:fd24f7ca9688 45 offset += this->transforms[i].serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 46 }
garyservin 0:fd24f7ca9688 47 *(outbuffer + offset++) = velocities_length;
garyservin 0:fd24f7ca9688 48 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 49 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 50 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 51 for( uint8_t i = 0; i < velocities_length; i++){
garyservin 0:fd24f7ca9688 52 offset += this->velocities[i].serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 53 }
garyservin 0:fd24f7ca9688 54 *(outbuffer + offset++) = accelerations_length;
garyservin 0:fd24f7ca9688 55 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 56 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 57 *(outbuffer + offset++) = 0;
garyservin 0:fd24f7ca9688 58 for( uint8_t i = 0; i < accelerations_length; i++){
garyservin 0:fd24f7ca9688 59 offset += this->accelerations[i].serialize(outbuffer + offset);
garyservin 0:fd24f7ca9688 60 }
garyservin 0:fd24f7ca9688 61 *(outbuffer + offset + 0) = (this->time_from_start.sec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 62 *(outbuffer + offset + 1) = (this->time_from_start.sec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 63 *(outbuffer + offset + 2) = (this->time_from_start.sec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 64 *(outbuffer + offset + 3) = (this->time_from_start.sec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 65 offset += sizeof(this->time_from_start.sec);
garyservin 0:fd24f7ca9688 66 *(outbuffer + offset + 0) = (this->time_from_start.nsec >> (8 * 0)) & 0xFF;
garyservin 0:fd24f7ca9688 67 *(outbuffer + offset + 1) = (this->time_from_start.nsec >> (8 * 1)) & 0xFF;
garyservin 0:fd24f7ca9688 68 *(outbuffer + offset + 2) = (this->time_from_start.nsec >> (8 * 2)) & 0xFF;
garyservin 0:fd24f7ca9688 69 *(outbuffer + offset + 3) = (this->time_from_start.nsec >> (8 * 3)) & 0xFF;
garyservin 0:fd24f7ca9688 70 offset += sizeof(this->time_from_start.nsec);
garyservin 0:fd24f7ca9688 71 return offset;
garyservin 0:fd24f7ca9688 72 }
garyservin 0:fd24f7ca9688 73
garyservin 0:fd24f7ca9688 74 virtual int deserialize(unsigned char *inbuffer)
garyservin 0:fd24f7ca9688 75 {
garyservin 0:fd24f7ca9688 76 int offset = 0;
garyservin 0:fd24f7ca9688 77 uint8_t transforms_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 78 if(transforms_lengthT > transforms_length)
garyservin 0:fd24f7ca9688 79 this->transforms = (geometry_msgs::Transform*)realloc(this->transforms, transforms_lengthT * sizeof(geometry_msgs::Transform));
garyservin 0:fd24f7ca9688 80 offset += 3;
garyservin 0:fd24f7ca9688 81 transforms_length = transforms_lengthT;
garyservin 0:fd24f7ca9688 82 for( uint8_t i = 0; i < transforms_length; i++){
garyservin 0:fd24f7ca9688 83 offset += this->st_transforms.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 84 memcpy( &(this->transforms[i]), &(this->st_transforms), sizeof(geometry_msgs::Transform));
garyservin 0:fd24f7ca9688 85 }
garyservin 0:fd24f7ca9688 86 uint8_t velocities_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 87 if(velocities_lengthT > velocities_length)
garyservin 0:fd24f7ca9688 88 this->velocities = (geometry_msgs::Twist*)realloc(this->velocities, velocities_lengthT * sizeof(geometry_msgs::Twist));
garyservin 0:fd24f7ca9688 89 offset += 3;
garyservin 0:fd24f7ca9688 90 velocities_length = velocities_lengthT;
garyservin 0:fd24f7ca9688 91 for( uint8_t i = 0; i < velocities_length; i++){
garyservin 0:fd24f7ca9688 92 offset += this->st_velocities.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 93 memcpy( &(this->velocities[i]), &(this->st_velocities), sizeof(geometry_msgs::Twist));
garyservin 0:fd24f7ca9688 94 }
garyservin 0:fd24f7ca9688 95 uint8_t accelerations_lengthT = *(inbuffer + offset++);
garyservin 0:fd24f7ca9688 96 if(accelerations_lengthT > accelerations_length)
garyservin 0:fd24f7ca9688 97 this->accelerations = (geometry_msgs::Twist*)realloc(this->accelerations, accelerations_lengthT * sizeof(geometry_msgs::Twist));
garyservin 0:fd24f7ca9688 98 offset += 3;
garyservin 0:fd24f7ca9688 99 accelerations_length = accelerations_lengthT;
garyservin 0:fd24f7ca9688 100 for( uint8_t i = 0; i < accelerations_length; i++){
garyservin 0:fd24f7ca9688 101 offset += this->st_accelerations.deserialize(inbuffer + offset);
garyservin 0:fd24f7ca9688 102 memcpy( &(this->accelerations[i]), &(this->st_accelerations), sizeof(geometry_msgs::Twist));
garyservin 0:fd24f7ca9688 103 }
garyservin 0:fd24f7ca9688 104 this->time_from_start.sec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 105 this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 106 this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 107 this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 108 offset += sizeof(this->time_from_start.sec);
garyservin 0:fd24f7ca9688 109 this->time_from_start.nsec = ((uint32_t) (*(inbuffer + offset)));
garyservin 0:fd24f7ca9688 110 this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
garyservin 0:fd24f7ca9688 111 this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
garyservin 0:fd24f7ca9688 112 this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
garyservin 0:fd24f7ca9688 113 offset += sizeof(this->time_from_start.nsec);
garyservin 0:fd24f7ca9688 114 return offset;
garyservin 0:fd24f7ca9688 115 }
garyservin 0:fd24f7ca9688 116
garyservin 0:fd24f7ca9688 117 const char * getType(){ return "trajectory_msgs/MultiDOFJointTrajectoryPoint"; };
garyservin 0:fd24f7ca9688 118 const char * getMD5(){ return "3ebe08d1abd5b65862d50e09430db776"; };
garyservin 0:fd24f7ca9688 119
garyservin 0:fd24f7ca9688 120 };
garyservin 0:fd24f7ca9688 121
garyservin 0:fd24f7ca9688 122 }
garyservin 0:fd24f7ca9688 123 #endif