This is a fork from the original, including a small change in the buffer size of the hardware interface (increased to 2048) and decreasing the number of publishers and subscribers to 5. Besides, the library about the message Adc.h was modified so as to increase the number of available Adc channels to be read ( from 6 to 7 ) For this modification, a change in checksum was required

Dependencies:   BufferedSerial

Fork of ros_lib_kinetic by Gary Servin

Committer:
garyservin
Date:
Sat Dec 31 00:48:34 2016 +0000
Revision:
0:9e9b7db60fd5
Initial commit, generated based on a clean kinetic-desktop-full

Who changed what in which revision?

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