hairo
Dependencies: mbed BufferedSerial
control_msgs/JointTolerance.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_control_msgs_JointTolerance_h |
garyservin | 0:9e9b7db60fd5 | 2 | #define _ROS_control_msgs_JointTolerance_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 | |
garyservin | 0:9e9b7db60fd5 | 9 | namespace control_msgs |
garyservin | 0:9e9b7db60fd5 | 10 | { |
garyservin | 0:9e9b7db60fd5 | 11 | |
garyservin | 0:9e9b7db60fd5 | 12 | class JointTolerance : public ros::Msg |
garyservin | 0:9e9b7db60fd5 | 13 | { |
garyservin | 0:9e9b7db60fd5 | 14 | public: |
garyservin | 0:9e9b7db60fd5 | 15 | typedef const char* _name_type; |
garyservin | 0:9e9b7db60fd5 | 16 | _name_type name; |
garyservin | 0:9e9b7db60fd5 | 17 | typedef double _position_type; |
garyservin | 0:9e9b7db60fd5 | 18 | _position_type position; |
garyservin | 0:9e9b7db60fd5 | 19 | typedef double _velocity_type; |
garyservin | 0:9e9b7db60fd5 | 20 | _velocity_type velocity; |
garyservin | 0:9e9b7db60fd5 | 21 | typedef double _acceleration_type; |
garyservin | 0:9e9b7db60fd5 | 22 | _acceleration_type acceleration; |
garyservin | 0:9e9b7db60fd5 | 23 | |
garyservin | 0:9e9b7db60fd5 | 24 | JointTolerance(): |
garyservin | 0:9e9b7db60fd5 | 25 | name(""), |
garyservin | 0:9e9b7db60fd5 | 26 | position(0), |
garyservin | 0:9e9b7db60fd5 | 27 | velocity(0), |
garyservin | 0:9e9b7db60fd5 | 28 | acceleration(0) |
garyservin | 0:9e9b7db60fd5 | 29 | { |
garyservin | 0:9e9b7db60fd5 | 30 | } |
garyservin | 0:9e9b7db60fd5 | 31 | |
garyservin | 0:9e9b7db60fd5 | 32 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:9e9b7db60fd5 | 33 | { |
garyservin | 0:9e9b7db60fd5 | 34 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 35 | uint32_t length_name = strlen(this->name); |
garyservin | 0:9e9b7db60fd5 | 36 | varToArr(outbuffer + offset, length_name); |
garyservin | 0:9e9b7db60fd5 | 37 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 38 | memcpy(outbuffer + offset, this->name, length_name); |
garyservin | 0:9e9b7db60fd5 | 39 | offset += length_name; |
garyservin | 0:9e9b7db60fd5 | 40 | union { |
garyservin | 0:9e9b7db60fd5 | 41 | double real; |
garyservin | 0:9e9b7db60fd5 | 42 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 43 | } u_position; |
garyservin | 0:9e9b7db60fd5 | 44 | u_position.real = this->position; |
garyservin | 0:9e9b7db60fd5 | 45 | *(outbuffer + offset + 0) = (u_position.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 46 | *(outbuffer + offset + 1) = (u_position.base >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 47 | *(outbuffer + offset + 2) = (u_position.base >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 48 | *(outbuffer + offset + 3) = (u_position.base >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 49 | *(outbuffer + offset + 4) = (u_position.base >> (8 * 4)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 50 | *(outbuffer + offset + 5) = (u_position.base >> (8 * 5)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 51 | *(outbuffer + offset + 6) = (u_position.base >> (8 * 6)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 52 | *(outbuffer + offset + 7) = (u_position.base >> (8 * 7)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 53 | offset += sizeof(this->position); |
garyservin | 0:9e9b7db60fd5 | 54 | union { |
garyservin | 0:9e9b7db60fd5 | 55 | double real; |
garyservin | 0:9e9b7db60fd5 | 56 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 57 | } u_velocity; |
garyservin | 0:9e9b7db60fd5 | 58 | u_velocity.real = this->velocity; |
garyservin | 0:9e9b7db60fd5 | 59 | *(outbuffer + offset + 0) = (u_velocity.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 60 | *(outbuffer + offset + 1) = (u_velocity.base >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 61 | *(outbuffer + offset + 2) = (u_velocity.base >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 62 | *(outbuffer + offset + 3) = (u_velocity.base >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 63 | *(outbuffer + offset + 4) = (u_velocity.base >> (8 * 4)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 64 | *(outbuffer + offset + 5) = (u_velocity.base >> (8 * 5)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 65 | *(outbuffer + offset + 6) = (u_velocity.base >> (8 * 6)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 66 | *(outbuffer + offset + 7) = (u_velocity.base >> (8 * 7)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 67 | offset += sizeof(this->velocity); |
garyservin | 0:9e9b7db60fd5 | 68 | union { |
garyservin | 0:9e9b7db60fd5 | 69 | double real; |
garyservin | 0:9e9b7db60fd5 | 70 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 71 | } u_acceleration; |
garyservin | 0:9e9b7db60fd5 | 72 | u_acceleration.real = this->acceleration; |
garyservin | 0:9e9b7db60fd5 | 73 | *(outbuffer + offset + 0) = (u_acceleration.base >> (8 * 0)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 74 | *(outbuffer + offset + 1) = (u_acceleration.base >> (8 * 1)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 75 | *(outbuffer + offset + 2) = (u_acceleration.base >> (8 * 2)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 76 | *(outbuffer + offset + 3) = (u_acceleration.base >> (8 * 3)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 77 | *(outbuffer + offset + 4) = (u_acceleration.base >> (8 * 4)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 78 | *(outbuffer + offset + 5) = (u_acceleration.base >> (8 * 5)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 79 | *(outbuffer + offset + 6) = (u_acceleration.base >> (8 * 6)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 80 | *(outbuffer + offset + 7) = (u_acceleration.base >> (8 * 7)) & 0xFF; |
garyservin | 0:9e9b7db60fd5 | 81 | offset += sizeof(this->acceleration); |
garyservin | 0:9e9b7db60fd5 | 82 | return offset; |
garyservin | 0:9e9b7db60fd5 | 83 | } |
garyservin | 0:9e9b7db60fd5 | 84 | |
garyservin | 0:9e9b7db60fd5 | 85 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:9e9b7db60fd5 | 86 | { |
garyservin | 0:9e9b7db60fd5 | 87 | int offset = 0; |
garyservin | 0:9e9b7db60fd5 | 88 | uint32_t length_name; |
garyservin | 0:9e9b7db60fd5 | 89 | arrToVar(length_name, (inbuffer + offset)); |
garyservin | 0:9e9b7db60fd5 | 90 | offset += 4; |
garyservin | 0:9e9b7db60fd5 | 91 | for(unsigned int k= offset; k< offset+length_name; ++k){ |
garyservin | 0:9e9b7db60fd5 | 92 | inbuffer[k-1]=inbuffer[k]; |
garyservin | 0:9e9b7db60fd5 | 93 | } |
garyservin | 0:9e9b7db60fd5 | 94 | inbuffer[offset+length_name-1]=0; |
garyservin | 0:9e9b7db60fd5 | 95 | this->name = (char *)(inbuffer + offset-1); |
garyservin | 0:9e9b7db60fd5 | 96 | offset += length_name; |
garyservin | 0:9e9b7db60fd5 | 97 | union { |
garyservin | 0:9e9b7db60fd5 | 98 | double real; |
garyservin | 0:9e9b7db60fd5 | 99 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 100 | } u_position; |
garyservin | 0:9e9b7db60fd5 | 101 | u_position.base = 0; |
garyservin | 0:9e9b7db60fd5 | 102 | u_position.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 103 | u_position.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 104 | u_position.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 105 | u_position.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 106 | u_position.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
garyservin | 0:9e9b7db60fd5 | 107 | u_position.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
garyservin | 0:9e9b7db60fd5 | 108 | u_position.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
garyservin | 0:9e9b7db60fd5 | 109 | u_position.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
garyservin | 0:9e9b7db60fd5 | 110 | this->position = u_position.real; |
garyservin | 0:9e9b7db60fd5 | 111 | offset += sizeof(this->position); |
garyservin | 0:9e9b7db60fd5 | 112 | union { |
garyservin | 0:9e9b7db60fd5 | 113 | double real; |
garyservin | 0:9e9b7db60fd5 | 114 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 115 | } u_velocity; |
garyservin | 0:9e9b7db60fd5 | 116 | u_velocity.base = 0; |
garyservin | 0:9e9b7db60fd5 | 117 | u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 118 | u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 119 | u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 120 | u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 121 | u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
garyservin | 0:9e9b7db60fd5 | 122 | u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
garyservin | 0:9e9b7db60fd5 | 123 | u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
garyservin | 0:9e9b7db60fd5 | 124 | u_velocity.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
garyservin | 0:9e9b7db60fd5 | 125 | this->velocity = u_velocity.real; |
garyservin | 0:9e9b7db60fd5 | 126 | offset += sizeof(this->velocity); |
garyservin | 0:9e9b7db60fd5 | 127 | union { |
garyservin | 0:9e9b7db60fd5 | 128 | double real; |
garyservin | 0:9e9b7db60fd5 | 129 | uint64_t base; |
garyservin | 0:9e9b7db60fd5 | 130 | } u_acceleration; |
garyservin | 0:9e9b7db60fd5 | 131 | u_acceleration.base = 0; |
garyservin | 0:9e9b7db60fd5 | 132 | u_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:9e9b7db60fd5 | 133 | u_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:9e9b7db60fd5 | 134 | u_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:9e9b7db60fd5 | 135 | u_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:9e9b7db60fd5 | 136 | u_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
garyservin | 0:9e9b7db60fd5 | 137 | u_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
garyservin | 0:9e9b7db60fd5 | 138 | u_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
garyservin | 0:9e9b7db60fd5 | 139 | u_acceleration.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
garyservin | 0:9e9b7db60fd5 | 140 | this->acceleration = u_acceleration.real; |
garyservin | 0:9e9b7db60fd5 | 141 | offset += sizeof(this->acceleration); |
garyservin | 0:9e9b7db60fd5 | 142 | return offset; |
garyservin | 0:9e9b7db60fd5 | 143 | } |
garyservin | 0:9e9b7db60fd5 | 144 | |
garyservin | 0:9e9b7db60fd5 | 145 | const char * getType(){ return "control_msgs/JointTolerance"; }; |
garyservin | 0:9e9b7db60fd5 | 146 | const char * getMD5(){ return "f544fe9c16cf04547e135dd6063ff5be"; }; |
garyservin | 0:9e9b7db60fd5 | 147 | |
garyservin | 0:9e9b7db60fd5 | 148 | }; |
garyservin | 0:9e9b7db60fd5 | 149 | |
garyservin | 0:9e9b7db60fd5 | 150 | } |
garyservin | 0:9e9b7db60fd5 | 151 | #endif |