added 1 custom message
Fork of ros_lib_kinetic by
trajectory_msgs/JointTrajectoryPoint.h@2:af816ffd33df, 2017-05-19 (annotated)
- Committer:
- randalthor
- Date:
- Fri May 19 08:59:12 2017 +0000
- Revision:
- 2:af816ffd33df
- Parent:
- 0:9e9b7db60fd5
custom message mobile robot added for ITU cyber physical lab
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:9e9b7db60fd5 | 1 | #ifndef _ROS_trajectory_msgs_JointTrajectoryPoint_h |
garyservin | 0:9e9b7db60fd5 | 2 | #define _ROS_trajectory_msgs_JointTrajectoryPoint_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 "ros/duration.h" |
garyservin | 0:9e9b7db60fd5 | 9 | |
garyservin | 0:9e9b7db60fd5 | 10 | namespace trajectory_msgs |
garyservin | 0:9e9b7db60fd5 | 11 | { |
garyservin | 0:9e9b7db60fd5 | 12 | |
garyservin | 0:9e9b7db60fd5 | 13 | class JointTrajectoryPoint : public ros::Msg |
garyservin | 0:9e9b7db60fd5 | 14 | { |
garyservin | 0:9e9b7db60fd5 | 15 | public: |
garyservin | 0:9e9b7db60fd5 | 16 | uint32_t positions_length; |
garyservin | 0:9e9b7db60fd5 | 17 | typedef double _positions_type; |
garyservin | 0:9e9b7db60fd5 | 18 | _positions_type st_positions; |
garyservin | 0:9e9b7db60fd5 | 19 | _positions_type * positions; |
garyservin | 0:9e9b7db60fd5 | 20 | uint32_t velocities_length; |
garyservin | 0:9e9b7db60fd5 | 21 | typedef double _velocities_type; |
garyservin | 0:9e9b7db60fd5 | 22 | _velocities_type st_velocities; |
garyservin | 0:9e9b7db60fd5 | 23 | _velocities_type * velocities; |
garyservin | 0:9e9b7db60fd5 | 24 | uint32_t accelerations_length; |
garyservin | 0:9e9b7db60fd5 | 25 | typedef double _accelerations_type; |
garyservin | 0:9e9b7db60fd5 | 26 | _accelerations_type st_accelerations; |
garyservin | 0:9e9b7db60fd5 | 27 | _accelerations_type * accelerations; |
garyservin | 0:9e9b7db60fd5 | 28 | uint32_t effort_length; |
garyservin | 0:9e9b7db60fd5 | 29 | typedef double _effort_type; |
garyservin | 0:9e9b7db60fd5 | 30 | _effort_type st_effort; |
garyservin | 0:9e9b7db60fd5 | 31 | _effort_type * effort; |
garyservin | 0:9e9b7db60fd5 | 32 | typedef ros::Duration _time_from_start_type; |
garyservin | 0:9e9b7db60fd5 | 33 | _time_from_start_type time_from_start; |
garyservin | 0:9e9b7db60fd5 | 34 | |
garyservin | 0:9e9b7db60fd5 | 35 | JointTrajectoryPoint(): |
garyservin | 0:9e9b7db60fd5 | 36 | positions_length(0), positions(NULL), |
garyservin | 0:9e9b7db60fd5 | 37 | velocities_length(0), velocities(NULL), |
garyservin | 0:9e9b7db60fd5 | 38 | accelerations_length(0), accelerations(NULL), |
garyservin | 0:9e9b7db60fd5 | 39 | effort_length(0), effort(NULL), |
garyservin | 0:9e9b7db60fd5 | 40 | time_from_start() |
garyservin | 0:9e9b7db60fd5 | 41 | { |
garyservin | 0:9e9b7db60fd5 | 42 | } |
garyservin | 0:9e9b7db60fd5 | 43 | |
garyservin | 0:9e9b7db60fd5 | 44 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:9e9b7db60fd5 | 45 | { |
garyservin | 0:9e9b7db60fd5 | 46 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 47 | *(outbuffer + offset + 0) = (this->positions_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 48 | *(outbuffer + offset + 1) = (this->positions_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 49 | *(outbuffer + offset + 2) = (this->positions_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 50 | *(outbuffer + offset + 3) = (this->positions_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 51 | offset += sizeof(this->positions_length); |
garyservin | 0:9e9b7db60fd5 | 52 | for( uint32_t i = 0; i < positions_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 53 | union { |
garyservin | 0:9e9b7db60fd5 | 54 | double real; |
garyservin | 0:9e9b7db60fd5 | 55 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 56 | } u_positionsi; |
garyservin | 0:9e9b7db60fd5 | 57 | u_positionsi.real = this->positions[i]; |
garyservin | 0:9e9b7db60fd5 | 58 | *(outbuffer + offset + 0) = (u_positionsi.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 59 | *(outbuffer + offset + 1) = (u_positionsi.base >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 60 | *(outbuffer + offset + 2) = (u_positionsi.base >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 61 | *(outbuffer + offset + 3) = (u_positionsi.base >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 62 | *(outbuffer + offset + 4) = (u_positionsi.base >> (8 * 4)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 63 | *(outbuffer + offset + 5) = (u_positionsi.base >> (8 * 5)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 64 | *(outbuffer + offset + 6) = (u_positionsi.base >> (8 * 6)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 65 | *(outbuffer + offset + 7) = (u_positionsi.base >> (8 * 7)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 66 | offset += sizeof(this->positions[i]); |
garyservin | 0:9e9b7db60fd5 | 67 | } |
garyservin | 0:9e9b7db60fd5 | 68 | *(outbuffer + offset + 0) = (this->velocities_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 69 | *(outbuffer + offset + 1) = (this->velocities_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 70 | *(outbuffer + offset + 2) = (this->velocities_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 71 | *(outbuffer + offset + 3) = (this->velocities_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 72 | offset += sizeof(this->velocities_length); |
garyservin | 0:9e9b7db60fd5 | 73 | for( uint32_t i = 0; i < velocities_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 74 | union { |
garyservin | 0:9e9b7db60fd5 | 75 | double real; |
garyservin | 0:9e9b7db60fd5 | 76 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 77 | } u_velocitiesi; |
garyservin | 0:9e9b7db60fd5 | 78 | u_velocitiesi.real = this->velocities[i]; |
garyservin | 0:9e9b7db60fd5 | 79 | *(outbuffer + offset + 0) = (u_velocitiesi.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 80 | *(outbuffer + offset + 1) = (u_velocitiesi.base >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 81 | *(outbuffer + offset + 2) = (u_velocitiesi.base >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 82 | *(outbuffer + offset + 3) = (u_velocitiesi.base >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 83 | *(outbuffer + offset + 4) = (u_velocitiesi.base >> (8 * 4)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 84 | *(outbuffer + offset + 5) = (u_velocitiesi.base >> (8 * 5)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 85 | *(outbuffer + offset + 6) = (u_velocitiesi.base >> (8 * 6)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 86 | *(outbuffer + offset + 7) = (u_velocitiesi.base >> (8 * 7)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 87 | offset += sizeof(this->velocities[i]); |
garyservin | 0:9e9b7db60fd5 | 88 | } |
garyservin | 0:9e9b7db60fd5 | 89 | *(outbuffer + offset + 0) = (this->accelerations_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 90 | *(outbuffer + offset + 1) = (this->accelerations_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 91 | *(outbuffer + offset + 2) = (this->accelerations_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 92 | *(outbuffer + offset + 3) = (this->accelerations_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 93 | offset += sizeof(this->accelerations_length); |
garyservin | 0:9e9b7db60fd5 | 94 | for( uint32_t i = 0; i < accelerations_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 95 | union { |
garyservin | 0:9e9b7db60fd5 | 96 | double real; |
garyservin | 0:9e9b7db60fd5 | 97 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 98 | } u_accelerationsi; |
garyservin | 0:9e9b7db60fd5 | 99 | u_accelerationsi.real = this->accelerations[i]; |
garyservin | 0:9e9b7db60fd5 | 100 | *(outbuffer + offset + 0) = (u_accelerationsi.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 101 | *(outbuffer + offset + 1) = (u_accelerationsi.base >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 102 | *(outbuffer + offset + 2) = (u_accelerationsi.base >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 103 | *(outbuffer + offset + 3) = (u_accelerationsi.base >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 104 | *(outbuffer + offset + 4) = (u_accelerationsi.base >> (8 * 4)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 105 | *(outbuffer + offset + 5) = (u_accelerationsi.base >> (8 * 5)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 106 | *(outbuffer + offset + 6) = (u_accelerationsi.base >> (8 * 6)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 107 | *(outbuffer + offset + 7) = (u_accelerationsi.base >> (8 * 7)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 108 | offset += sizeof(this->accelerations[i]); |
garyservin | 0:9e9b7db60fd5 | 109 | } |
garyservin | 0:9e9b7db60fd5 | 110 | *(outbuffer + offset + 0) = (this->effort_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 111 | *(outbuffer + offset + 1) = (this->effort_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 112 | *(outbuffer + offset + 2) = (this->effort_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 113 | *(outbuffer + offset + 3) = (this->effort_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 114 | offset += sizeof(this->effort_length); |
garyservin | 0:9e9b7db60fd5 | 115 | for( uint32_t i = 0; i < effort_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 116 | union { |
garyservin | 0:9e9b7db60fd5 | 117 | double real; |
garyservin | 0:9e9b7db60fd5 | 118 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 119 | } u_efforti; |
garyservin | 0:9e9b7db60fd5 | 120 | u_efforti.real = this->effort[i]; |
garyservin | 0:9e9b7db60fd5 | 121 | *(outbuffer + offset + 0) = (u_efforti.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 122 | *(outbuffer + offset + 1) = (u_efforti.base >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 123 | *(outbuffer + offset + 2) = (u_efforti.base >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 124 | *(outbuffer + offset + 3) = (u_efforti.base >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 125 | *(outbuffer + offset + 4) = (u_efforti.base >> (8 * 4)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 126 | *(outbuffer + offset + 5) = (u_efforti.base >> (8 * 5)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 127 | *(outbuffer + offset + 6) = (u_efforti.base >> (8 * 6)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 128 | *(outbuffer + offset + 7) = (u_efforti.base >> (8 * 7)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 129 | offset += sizeof(this->effort[i]); |
garyservin | 0:9e9b7db60fd5 | 130 | } |
garyservin | 0:9e9b7db60fd5 | 131 | *(outbuffer + offset + 0) = (this->time_from_start.sec >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 132 | *(outbuffer + offset + 1) = (this->time_from_start.sec >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 133 | *(outbuffer + offset + 2) = (this->time_from_start.sec >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 134 | *(outbuffer + offset + 3) = (this->time_from_start.sec >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 135 | offset += sizeof(this->time_from_start.sec); |
garyservin | 0:9e9b7db60fd5 | 136 | *(outbuffer + offset + 0) = (this->time_from_start.nsec >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 137 | *(outbuffer + offset + 1) = (this->time_from_start.nsec >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 138 | *(outbuffer + offset + 2) = (this->time_from_start.nsec >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 139 | *(outbuffer + offset + 3) = (this->time_from_start.nsec >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 140 | offset += sizeof(this->time_from_start.nsec); |
garyservin | 0:9e9b7db60fd5 | 141 | return offset; |
garyservin | 0:9e9b7db60fd5 | 142 | } |
garyservin | 0:9e9b7db60fd5 | 143 | |
garyservin | 0:9e9b7db60fd5 | 144 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:9e9b7db60fd5 | 145 | { |
garyservin | 0:9e9b7db60fd5 | 146 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 147 | uint32_t positions_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 148 | positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 149 | positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 150 | positions_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 151 | offset += sizeof(this->positions_length); |
garyservin | 0:9e9b7db60fd5 | 152 | if(positions_lengthT > positions_length) |
garyservin | 0:9e9b7db60fd5 | 153 | this->positions = (double*)realloc(this->positions, positions_lengthT * sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 154 | positions_length = positions_lengthT; |
garyservin | 0:9e9b7db60fd5 | 155 | for( uint32_t i = 0; i < positions_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 156 | union { |
garyservin | 0:9e9b7db60fd5 | 157 | double real; |
garyservin | 0:9e9b7db60fd5 | 158 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 159 | } u_st_positions; |
garyservin | 0:9e9b7db60fd5 | 160 | u_st_positions.base = 0; |
garyservin | 0:9e9b7db60fd5 | 161 | u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 162 | u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 163 | u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 164 | u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 165 | u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
garyservin | 0:9e9b7db60fd5 | 166 | u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
garyservin | 0:9e9b7db60fd5 | 167 | u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
garyservin | 0:9e9b7db60fd5 | 168 | u_st_positions.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
garyservin | 0:9e9b7db60fd5 | 169 | this->st_positions = u_st_positions.real; |
garyservin | 0:9e9b7db60fd5 | 170 | offset += sizeof(this->st_positions); |
garyservin | 0:9e9b7db60fd5 | 171 | memcpy( &(this->positions[i]), &(this->st_positions), sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 172 | } |
garyservin | 0:9e9b7db60fd5 | 173 | uint32_t velocities_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 174 | velocities_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 175 | velocities_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 176 | velocities_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 177 | offset += sizeof(this->velocities_length); |
garyservin | 0:9e9b7db60fd5 | 178 | if(velocities_lengthT > velocities_length) |
garyservin | 0:9e9b7db60fd5 | 179 | this->velocities = (double*)realloc(this->velocities, velocities_lengthT * sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 180 | velocities_length = velocities_lengthT; |
garyservin | 0:9e9b7db60fd5 | 181 | for( uint32_t i = 0; i < velocities_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 182 | union { |
garyservin | 0:9e9b7db60fd5 | 183 | double real; |
garyservin | 0:9e9b7db60fd5 | 184 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 185 | } u_st_velocities; |
garyservin | 0:9e9b7db60fd5 | 186 | u_st_velocities.base = 0; |
garyservin | 0:9e9b7db60fd5 | 187 | u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 188 | u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 189 | u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 190 | u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 191 | u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
garyservin | 0:9e9b7db60fd5 | 192 | u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
garyservin | 0:9e9b7db60fd5 | 193 | u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
garyservin | 0:9e9b7db60fd5 | 194 | u_st_velocities.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
garyservin | 0:9e9b7db60fd5 | 195 | this->st_velocities = u_st_velocities.real; |
garyservin | 0:9e9b7db60fd5 | 196 | offset += sizeof(this->st_velocities); |
garyservin | 0:9e9b7db60fd5 | 197 | memcpy( &(this->velocities[i]), &(this->st_velocities), sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 198 | } |
garyservin | 0:9e9b7db60fd5 | 199 | uint32_t accelerations_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 200 | accelerations_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 201 | accelerations_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 202 | accelerations_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 203 | offset += sizeof(this->accelerations_length); |
garyservin | 0:9e9b7db60fd5 | 204 | if(accelerations_lengthT > accelerations_length) |
garyservin | 0:9e9b7db60fd5 | 205 | this->accelerations = (double*)realloc(this->accelerations, accelerations_lengthT * sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 206 | accelerations_length = accelerations_lengthT; |
garyservin | 0:9e9b7db60fd5 | 207 | for( uint32_t i = 0; i < accelerations_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 208 | union { |
garyservin | 0:9e9b7db60fd5 | 209 | double real; |
garyservin | 0:9e9b7db60fd5 | 210 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 211 | } u_st_accelerations; |
garyservin | 0:9e9b7db60fd5 | 212 | u_st_accelerations.base = 0; |
garyservin | 0:9e9b7db60fd5 | 213 | u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 214 | u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 215 | u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 216 | u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 217 | u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
garyservin | 0:9e9b7db60fd5 | 218 | u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
garyservin | 0:9e9b7db60fd5 | 219 | u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
garyservin | 0:9e9b7db60fd5 | 220 | u_st_accelerations.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
garyservin | 0:9e9b7db60fd5 | 221 | this->st_accelerations = u_st_accelerations.real; |
garyservin | 0:9e9b7db60fd5 | 222 | offset += sizeof(this->st_accelerations); |
garyservin | 0:9e9b7db60fd5 | 223 | memcpy( &(this->accelerations[i]), &(this->st_accelerations), sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 224 | } |
garyservin | 0:9e9b7db60fd5 | 225 | uint32_t effort_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 226 | effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 227 | effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 228 | effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 229 | offset += sizeof(this->effort_length); |
garyservin | 0:9e9b7db60fd5 | 230 | if(effort_lengthT > effort_length) |
garyservin | 0:9e9b7db60fd5 | 231 | this->effort = (double*)realloc(this->effort, effort_lengthT * sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 232 | effort_length = effort_lengthT; |
garyservin | 0:9e9b7db60fd5 | 233 | for( uint32_t i = 0; i < effort_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 234 | union { |
garyservin | 0:9e9b7db60fd5 | 235 | double real; |
garyservin | 0:9e9b7db60fd5 | 236 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 237 | } u_st_effort; |
garyservin | 0:9e9b7db60fd5 | 238 | u_st_effort.base = 0; |
garyservin | 0:9e9b7db60fd5 | 239 | u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 240 | u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 241 | u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 242 | u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 243 | u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
garyservin | 0:9e9b7db60fd5 | 244 | u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
garyservin | 0:9e9b7db60fd5 | 245 | u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
garyservin | 0:9e9b7db60fd5 | 246 | u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
garyservin | 0:9e9b7db60fd5 | 247 | this->st_effort = u_st_effort.real; |
garyservin | 0:9e9b7db60fd5 | 248 | offset += sizeof(this->st_effort); |
garyservin | 0:9e9b7db60fd5 | 249 | memcpy( &(this->effort[i]), &(this->st_effort), sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 250 | } |
garyservin | 0:9e9b7db60fd5 | 251 | this->time_from_start.sec = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 252 | this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 253 | this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 254 | this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 255 | offset += sizeof(this->time_from_start.sec); |
garyservin | 0:9e9b7db60fd5 | 256 | this->time_from_start.nsec = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 257 | this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 258 | this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 259 | this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 260 | offset += sizeof(this->time_from_start.nsec); |
garyservin | 0:9e9b7db60fd5 | 261 | return offset; |
garyservin | 0:9e9b7db60fd5 | 262 | } |
garyservin | 0:9e9b7db60fd5 | 263 | |
garyservin | 0:9e9b7db60fd5 | 264 | const char * getType(){ return "trajectory_msgs/JointTrajectoryPoint"; }; |
garyservin | 0:9e9b7db60fd5 | 265 | const char * getMD5(){ return "f3cd1e1c4d320c79d6985c904ae5dcd3"; }; |
garyservin | 0:9e9b7db60fd5 | 266 | |
garyservin | 0:9e9b7db60fd5 | 267 | }; |
garyservin | 0:9e9b7db60fd5 | 268 | |
garyservin | 0:9e9b7db60fd5 | 269 | } |
garyservin | 0:9e9b7db60fd5 | 270 | #endif |