Just changed OUTPUT_SIZE and INPUT_SIZE in ros/node_handle.h

Dependencies:   BufferedSerial

Dependents:   WRS2020_mecanum_node

Committer:
sgrsn
Date:
Mon Nov 02 09:00:01 2020 +0000
Revision:
2:5d429be7d0aa
Parent:
0:04ac6be8229a
Change INPUT_SIZE and OUTPUT_SIZE on node_handle.h to pub sub

Who changed what in which revision?

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