ROS Serial library for Mbed platforms for ROS Kinetic Kame. Check http://wiki.ros.org/rosserial_mbed/ for more information.
sensor_msgs/JointState.h@0:9e9b7db60fd5, 2016-12-31 (annotated)
- 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?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:9e9b7db60fd5 | 1 | #ifndef _ROS_sensor_msgs_JointState_h |
garyservin | 0:9e9b7db60fd5 | 2 | #define _ROS_sensor_msgs_JointState_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 "std_msgs/Header.h" |
garyservin | 0:9e9b7db60fd5 | 9 | |
garyservin | 0:9e9b7db60fd5 | 10 | namespace sensor_msgs |
garyservin | 0:9e9b7db60fd5 | 11 | { |
garyservin | 0:9e9b7db60fd5 | 12 | |
garyservin | 0:9e9b7db60fd5 | 13 | class JointState : public ros::Msg |
garyservin | 0:9e9b7db60fd5 | 14 | { |
garyservin | 0:9e9b7db60fd5 | 15 | public: |
garyservin | 0:9e9b7db60fd5 | 16 | typedef std_msgs::Header _header_type; |
garyservin | 0:9e9b7db60fd5 | 17 | _header_type header; |
garyservin | 0:9e9b7db60fd5 | 18 | uint32_t name_length; |
garyservin | 0:9e9b7db60fd5 | 19 | typedef char* _name_type; |
garyservin | 0:9e9b7db60fd5 | 20 | _name_type st_name; |
garyservin | 0:9e9b7db60fd5 | 21 | _name_type * name; |
garyservin | 0:9e9b7db60fd5 | 22 | uint32_t position_length; |
garyservin | 0:9e9b7db60fd5 | 23 | typedef double _position_type; |
garyservin | 0:9e9b7db60fd5 | 24 | _position_type st_position; |
garyservin | 0:9e9b7db60fd5 | 25 | _position_type * position; |
garyservin | 0:9e9b7db60fd5 | 26 | uint32_t velocity_length; |
garyservin | 0:9e9b7db60fd5 | 27 | typedef double _velocity_type; |
garyservin | 0:9e9b7db60fd5 | 28 | _velocity_type st_velocity; |
garyservin | 0:9e9b7db60fd5 | 29 | _velocity_type * velocity; |
garyservin | 0:9e9b7db60fd5 | 30 | uint32_t effort_length; |
garyservin | 0:9e9b7db60fd5 | 31 | typedef double _effort_type; |
garyservin | 0:9e9b7db60fd5 | 32 | _effort_type st_effort; |
garyservin | 0:9e9b7db60fd5 | 33 | _effort_type * effort; |
garyservin | 0:9e9b7db60fd5 | 34 | |
garyservin | 0:9e9b7db60fd5 | 35 | JointState(): |
garyservin | 0:9e9b7db60fd5 | 36 | header(), |
garyservin | 0:9e9b7db60fd5 | 37 | name_length(0), name(NULL), |
garyservin | 0:9e9b7db60fd5 | 38 | position_length(0), position(NULL), |
garyservin | 0:9e9b7db60fd5 | 39 | velocity_length(0), velocity(NULL), |
garyservin | 0:9e9b7db60fd5 | 40 | effort_length(0), effort(NULL) |
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 | offset += this->header.serialize(outbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 48 | *(outbuffer + offset + 0) = (this->name_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 49 | *(outbuffer + offset + 1) = (this->name_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 50 | *(outbuffer + offset + 2) = (this->name_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 51 | *(outbuffer + offset + 3) = (this->name_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 52 | offset += sizeof(this->name_length); |
garyservin | 0:9e9b7db60fd5 | 53 | for( uint32_t i = 0; i < name_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 54 | uint32_t length_namei = strlen(this->name[i]); |
garyservin | 0:9e9b7db60fd5 | 55 | varToArr(outbuffer + offset, length_namei); |
garyservin | 0:9e9b7db60fd5 | 56 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 57 | memcpy(outbuffer + offset, this->name[i], length_namei); |
garyservin | 0:9e9b7db60fd5 | 58 | offset += length_namei; |
garyservin | 0:9e9b7db60fd5 | 59 | } |
garyservin | 0:9e9b7db60fd5 | 60 | *(outbuffer + offset + 0) = (this->position_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 61 | *(outbuffer + offset + 1) = (this->position_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 62 | *(outbuffer + offset + 2) = (this->position_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 63 | *(outbuffer + offset + 3) = (this->position_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 64 | offset += sizeof(this->position_length); |
garyservin | 0:9e9b7db60fd5 | 65 | for( uint32_t i = 0; i < position_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 66 | union { |
garyservin | 0:9e9b7db60fd5 | 67 | double real; |
garyservin | 0:9e9b7db60fd5 | 68 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 69 | } u_positioni; |
garyservin | 0:9e9b7db60fd5 | 70 | u_positioni.real = this->position[i]; |
garyservin | 0:9e9b7db60fd5 | 71 | *(outbuffer + offset + 0) = (u_positioni.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 72 | *(outbuffer + offset + 1) = (u_positioni.base >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 73 | *(outbuffer + offset + 2) = (u_positioni.base >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 74 | *(outbuffer + offset + 3) = (u_positioni.base >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 75 | *(outbuffer + offset + 4) = (u_positioni.base >> (8 * 4)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 76 | *(outbuffer + offset + 5) = (u_positioni.base >> (8 * 5)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 77 | *(outbuffer + offset + 6) = (u_positioni.base >> (8 * 6)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 78 | *(outbuffer + offset + 7) = (u_positioni.base >> (8 * 7)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 79 | offset += sizeof(this->position[i]); |
garyservin | 0:9e9b7db60fd5 | 80 | } |
garyservin | 0:9e9b7db60fd5 | 81 | *(outbuffer + offset + 0) = (this->velocity_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 82 | *(outbuffer + offset + 1) = (this->velocity_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 83 | *(outbuffer + offset + 2) = (this->velocity_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 84 | *(outbuffer + offset + 3) = (this->velocity_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 85 | offset += sizeof(this->velocity_length); |
garyservin | 0:9e9b7db60fd5 | 86 | for( uint32_t i = 0; i < velocity_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 87 | union { |
garyservin | 0:9e9b7db60fd5 | 88 | double real; |
garyservin | 0:9e9b7db60fd5 | 89 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 90 | } u_velocityi; |
garyservin | 0:9e9b7db60fd5 | 91 | u_velocityi.real = this->velocity[i]; |
garyservin | 0:9e9b7db60fd5 | 92 | *(outbuffer + offset + 0) = (u_velocityi.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 93 | *(outbuffer + offset + 1) = (u_velocityi.base >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 94 | *(outbuffer + offset + 2) = (u_velocityi.base >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 95 | *(outbuffer + offset + 3) = (u_velocityi.base >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 96 | *(outbuffer + offset + 4) = (u_velocityi.base >> (8 * 4)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 97 | *(outbuffer + offset + 5) = (u_velocityi.base >> (8 * 5)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 98 | *(outbuffer + offset + 6) = (u_velocityi.base >> (8 * 6)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 99 | *(outbuffer + offset + 7) = (u_velocityi.base >> (8 * 7)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 100 | offset += sizeof(this->velocity[i]); |
garyservin | 0:9e9b7db60fd5 | 101 | } |
garyservin | 0:9e9b7db60fd5 | 102 | *(outbuffer + offset + 0) = (this->effort_length >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 103 | *(outbuffer + offset + 1) = (this->effort_length >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 104 | *(outbuffer + offset + 2) = (this->effort_length >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 105 | *(outbuffer + offset + 3) = (this->effort_length >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 106 | offset += sizeof(this->effort_length); |
garyservin | 0:9e9b7db60fd5 | 107 | for( uint32_t i = 0; i < effort_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 108 | union { |
garyservin | 0:9e9b7db60fd5 | 109 | double real; |
garyservin | 0:9e9b7db60fd5 | 110 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 111 | } u_efforti; |
garyservin | 0:9e9b7db60fd5 | 112 | u_efforti.real = this->effort[i]; |
garyservin | 0:9e9b7db60fd5 | 113 | *(outbuffer + offset + 0) = (u_efforti.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 114 | *(outbuffer + offset + 1) = (u_efforti.base >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 115 | *(outbuffer + offset + 2) = (u_efforti.base >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 116 | *(outbuffer + offset + 3) = (u_efforti.base >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 117 | *(outbuffer + offset + 4) = (u_efforti.base >> (8 * 4)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 118 | *(outbuffer + offset + 5) = (u_efforti.base >> (8 * 5)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 119 | *(outbuffer + offset + 6) = (u_efforti.base >> (8 * 6)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 120 | *(outbuffer + offset + 7) = (u_efforti.base >> (8 * 7)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 121 | offset += sizeof(this->effort[i]); |
garyservin | 0:9e9b7db60fd5 | 122 | } |
garyservin | 0:9e9b7db60fd5 | 123 | return offset; |
garyservin | 0:9e9b7db60fd5 | 124 | } |
garyservin | 0:9e9b7db60fd5 | 125 | |
garyservin | 0:9e9b7db60fd5 | 126 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:9e9b7db60fd5 | 127 | { |
garyservin | 0:9e9b7db60fd5 | 128 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 129 | offset += this->header.deserialize(inbuffer + offset); |
garyservin | 0:9e9b7db60fd5 | 130 | uint32_t name_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 131 | name_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 132 | name_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 133 | name_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 134 | offset += sizeof(this->name_length); |
garyservin | 0:9e9b7db60fd5 | 135 | if(name_lengthT > name_length) |
garyservin | 0:9e9b7db60fd5 | 136 | this->name = (char**)realloc(this->name, name_lengthT * sizeof(char*)); |
garyservin | 0:9e9b7db60fd5 | 137 | name_length = name_lengthT; |
garyservin | 0:9e9b7db60fd5 | 138 | for( uint32_t i = 0; i < name_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 139 | uint32_t length_st_name; |
garyservin | 0:9e9b7db60fd5 | 140 | arrToVar(length_st_name, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 141 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 142 | for(unsigned int k= offset; k< offset+length_st_name; ++k){ |
garyservin | 0:9e9b7db60fd5 | 143 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 144 | } |
garyservin | 0:9e9b7db60fd5 | 145 | inbuffer[offset+length_st_name-1]=0; |
garyservin | 0:9e9b7db60fd5 | 146 | this->st_name = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 147 | offset += length_st_name; |
garyservin | 0:9e9b7db60fd5 | 148 | memcpy( &(this->name[i]), &(this->st_name), sizeof(char*)); |
garyservin | 0:9e9b7db60fd5 | 149 | } |
garyservin | 0:9e9b7db60fd5 | 150 | uint32_t position_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 151 | position_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 152 | position_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 153 | position_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 154 | offset += sizeof(this->position_length); |
garyservin | 0:9e9b7db60fd5 | 155 | if(position_lengthT > position_length) |
garyservin | 0:9e9b7db60fd5 | 156 | this->position = (double*)realloc(this->position, position_lengthT * sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 157 | position_length = position_lengthT; |
garyservin | 0:9e9b7db60fd5 | 158 | for( uint32_t i = 0; i < position_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 159 | union { |
garyservin | 0:9e9b7db60fd5 | 160 | double real; |
garyservin | 0:9e9b7db60fd5 | 161 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 162 | } u_st_position; |
garyservin | 0:9e9b7db60fd5 | 163 | u_st_position.base = 0; |
garyservin | 0:9e9b7db60fd5 | 164 | u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 165 | u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 166 | u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 167 | u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 168 | u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
garyservin | 0:9e9b7db60fd5 | 169 | u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
garyservin | 0:9e9b7db60fd5 | 170 | u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
garyservin | 0:9e9b7db60fd5 | 171 | u_st_position.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
garyservin | 0:9e9b7db60fd5 | 172 | this->st_position = u_st_position.real; |
garyservin | 0:9e9b7db60fd5 | 173 | offset += sizeof(this->st_position); |
garyservin | 0:9e9b7db60fd5 | 174 | memcpy( &(this->position[i]), &(this->st_position), sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 175 | } |
garyservin | 0:9e9b7db60fd5 | 176 | uint32_t velocity_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 177 | velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 178 | velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 179 | velocity_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 180 | offset += sizeof(this->velocity_length); |
garyservin | 0:9e9b7db60fd5 | 181 | if(velocity_lengthT > velocity_length) |
garyservin | 0:9e9b7db60fd5 | 182 | this->velocity = (double*)realloc(this->velocity, velocity_lengthT * sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 183 | velocity_length = velocity_lengthT; |
garyservin | 0:9e9b7db60fd5 | 184 | for( uint32_t i = 0; i < velocity_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 185 | union { |
garyservin | 0:9e9b7db60fd5 | 186 | double real; |
garyservin | 0:9e9b7db60fd5 | 187 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 188 | } u_st_velocity; |
garyservin | 0:9e9b7db60fd5 | 189 | u_st_velocity.base = 0; |
garyservin | 0:9e9b7db60fd5 | 190 | u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 191 | u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 192 | u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 193 | u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 194 | u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
garyservin | 0:9e9b7db60fd5 | 195 | u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
garyservin | 0:9e9b7db60fd5 | 196 | u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
garyservin | 0:9e9b7db60fd5 | 197 | u_st_velocity.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
garyservin | 0:9e9b7db60fd5 | 198 | this->st_velocity = u_st_velocity.real; |
garyservin | 0:9e9b7db60fd5 | 199 | offset += sizeof(this->st_velocity); |
garyservin | 0:9e9b7db60fd5 | 200 | memcpy( &(this->velocity[i]), &(this->st_velocity), sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 201 | } |
garyservin | 0:9e9b7db60fd5 | 202 | uint32_t effort_lengthT = ((uint32_t) (*(inbuffer + offset))); |
garyservin | 0:9e9b7db60fd5 | 203 | effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 204 | effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 205 | effort_lengthT |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 206 | offset += sizeof(this->effort_length); |
garyservin | 0:9e9b7db60fd5 | 207 | if(effort_lengthT > effort_length) |
garyservin | 0:9e9b7db60fd5 | 208 | this->effort = (double*)realloc(this->effort, effort_lengthT * sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 209 | effort_length = effort_lengthT; |
garyservin | 0:9e9b7db60fd5 | 210 | for( uint32_t i = 0; i < effort_length; i++){ |
garyservin | 0:9e9b7db60fd5 | 211 | union { |
garyservin | 0:9e9b7db60fd5 | 212 | double real; |
garyservin | 0:9e9b7db60fd5 | 213 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 214 | } u_st_effort; |
garyservin | 0:9e9b7db60fd5 | 215 | u_st_effort.base = 0; |
garyservin | 0:9e9b7db60fd5 | 216 | u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 217 | u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 218 | u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 219 | u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 220 | u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
garyservin | 0:9e9b7db60fd5 | 221 | u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
garyservin | 0:9e9b7db60fd5 | 222 | u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
garyservin | 0:9e9b7db60fd5 | 223 | u_st_effort.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
garyservin | 0:9e9b7db60fd5 | 224 | this->st_effort = u_st_effort.real; |
garyservin | 0:9e9b7db60fd5 | 225 | offset += sizeof(this->st_effort); |
garyservin | 0:9e9b7db60fd5 | 226 | memcpy( &(this->effort[i]), &(this->st_effort), sizeof(double)); |
garyservin | 0:9e9b7db60fd5 | 227 | } |
garyservin | 0:9e9b7db60fd5 | 228 | return offset; |
garyservin | 0:9e9b7db60fd5 | 229 | } |
garyservin | 0:9e9b7db60fd5 | 230 | |
garyservin | 0:9e9b7db60fd5 | 231 | const char * getType(){ return "sensor_msgs/JointState"; }; |
garyservin | 0:9e9b7db60fd5 | 232 | const char * getMD5(){ return "3066dcd76a6cfaef579bd0f34173e9fd"; }; |
garyservin | 0:9e9b7db60fd5 | 233 | |
garyservin | 0:9e9b7db60fd5 | 234 | }; |
garyservin | 0:9e9b7db60fd5 | 235 | |
garyservin | 0:9e9b7db60fd5 | 236 | } |
garyservin | 0:9e9b7db60fd5 | 237 | #endif |