rosserial library for mbed Inspired by nucho's rosserial library This library is still under development
Dependents: mbed_roshydro_test
Library still under development!
trajectory_msgs/JointTrajectoryPoint.h@0:30537dec6e0b, 2015-02-15 (annotated)
- Committer:
- akashvibhute
- Date:
- Sun Feb 15 10:53:43 2015 +0000
- Revision:
- 0:30537dec6e0b
First commit; Library still need to be debugged, compilation issues with new mbed and modserial updates.
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
akashvibhute | 0:30537dec6e0b | 1 | #ifndef _ROS_trajectory_msgs_JointTrajectoryPoint_h |
akashvibhute | 0:30537dec6e0b | 2 | #define _ROS_trajectory_msgs_JointTrajectoryPoint_h |
akashvibhute | 0:30537dec6e0b | 3 | |
akashvibhute | 0:30537dec6e0b | 4 | #include <stdint.h> |
akashvibhute | 0:30537dec6e0b | 5 | #include <string.h> |
akashvibhute | 0:30537dec6e0b | 6 | #include <stdlib.h> |
akashvibhute | 0:30537dec6e0b | 7 | #include "ros/msg.h" |
akashvibhute | 0:30537dec6e0b | 8 | #include "ros/duration.h" |
akashvibhute | 0:30537dec6e0b | 9 | |
akashvibhute | 0:30537dec6e0b | 10 | namespace trajectory_msgs |
akashvibhute | 0:30537dec6e0b | 11 | { |
akashvibhute | 0:30537dec6e0b | 12 | |
akashvibhute | 0:30537dec6e0b | 13 | class JointTrajectoryPoint : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 14 | { |
akashvibhute | 0:30537dec6e0b | 15 | public: |
akashvibhute | 0:30537dec6e0b | 16 | uint8_t positions_length; |
akashvibhute | 0:30537dec6e0b | 17 | float st_positions; |
akashvibhute | 0:30537dec6e0b | 18 | float * positions; |
akashvibhute | 0:30537dec6e0b | 19 | uint8_t velocities_length; |
akashvibhute | 0:30537dec6e0b | 20 | float st_velocities; |
akashvibhute | 0:30537dec6e0b | 21 | float * velocities; |
akashvibhute | 0:30537dec6e0b | 22 | uint8_t accelerations_length; |
akashvibhute | 0:30537dec6e0b | 23 | float st_accelerations; |
akashvibhute | 0:30537dec6e0b | 24 | float * accelerations; |
akashvibhute | 0:30537dec6e0b | 25 | uint8_t effort_length; |
akashvibhute | 0:30537dec6e0b | 26 | float st_effort; |
akashvibhute | 0:30537dec6e0b | 27 | float * effort; |
akashvibhute | 0:30537dec6e0b | 28 | ros::Duration time_from_start; |
akashvibhute | 0:30537dec6e0b | 29 | |
akashvibhute | 0:30537dec6e0b | 30 | JointTrajectoryPoint(): |
akashvibhute | 0:30537dec6e0b | 31 | positions_length(0), positions(NULL), |
akashvibhute | 0:30537dec6e0b | 32 | velocities_length(0), velocities(NULL), |
akashvibhute | 0:30537dec6e0b | 33 | accelerations_length(0), accelerations(NULL), |
akashvibhute | 0:30537dec6e0b | 34 | effort_length(0), effort(NULL), |
akashvibhute | 0:30537dec6e0b | 35 | time_from_start() |
akashvibhute | 0:30537dec6e0b | 36 | { |
akashvibhute | 0:30537dec6e0b | 37 | } |
akashvibhute | 0:30537dec6e0b | 38 | |
akashvibhute | 0:30537dec6e0b | 39 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 40 | { |
akashvibhute | 0:30537dec6e0b | 41 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 42 | *(outbuffer + offset++) = positions_length; |
akashvibhute | 0:30537dec6e0b | 43 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 44 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 45 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 46 | for( uint8_t i = 0; i < positions_length; i++){ |
akashvibhute | 0:30537dec6e0b | 47 | offset += serializeAvrFloat64(outbuffer + offset, this->positions[i]); |
akashvibhute | 0:30537dec6e0b | 48 | } |
akashvibhute | 0:30537dec6e0b | 49 | *(outbuffer + offset++) = velocities_length; |
akashvibhute | 0:30537dec6e0b | 50 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 51 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 52 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 53 | for( uint8_t i = 0; i < velocities_length; i++){ |
akashvibhute | 0:30537dec6e0b | 54 | offset += serializeAvrFloat64(outbuffer + offset, this->velocities[i]); |
akashvibhute | 0:30537dec6e0b | 55 | } |
akashvibhute | 0:30537dec6e0b | 56 | *(outbuffer + offset++) = accelerations_length; |
akashvibhute | 0:30537dec6e0b | 57 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 58 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 59 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 60 | for( uint8_t i = 0; i < accelerations_length; i++){ |
akashvibhute | 0:30537dec6e0b | 61 | offset += serializeAvrFloat64(outbuffer + offset, this->accelerations[i]); |
akashvibhute | 0:30537dec6e0b | 62 | } |
akashvibhute | 0:30537dec6e0b | 63 | *(outbuffer + offset++) = effort_length; |
akashvibhute | 0:30537dec6e0b | 64 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 65 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 66 | *(outbuffer + offset++) = 0; |
akashvibhute | 0:30537dec6e0b | 67 | for( uint8_t i = 0; i < effort_length; i++){ |
akashvibhute | 0:30537dec6e0b | 68 | offset += serializeAvrFloat64(outbuffer + offset, this->effort[i]); |
akashvibhute | 0:30537dec6e0b | 69 | } |
akashvibhute | 0:30537dec6e0b | 70 | *(outbuffer + offset + 0) = (this->time_from_start.sec >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 71 | *(outbuffer + offset + 1) = (this->time_from_start.sec >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 72 | *(outbuffer + offset + 2) = (this->time_from_start.sec >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 73 | *(outbuffer + offset + 3) = (this->time_from_start.sec >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 74 | offset += sizeof(this->time_from_start.sec); |
akashvibhute | 0:30537dec6e0b | 75 | *(outbuffer + offset + 0) = (this->time_from_start.nsec >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 76 | *(outbuffer + offset + 1) = (this->time_from_start.nsec >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 77 | *(outbuffer + offset + 2) = (this->time_from_start.nsec >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 78 | *(outbuffer + offset + 3) = (this->time_from_start.nsec >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 79 | offset += sizeof(this->time_from_start.nsec); |
akashvibhute | 0:30537dec6e0b | 80 | return offset; |
akashvibhute | 0:30537dec6e0b | 81 | } |
akashvibhute | 0:30537dec6e0b | 82 | |
akashvibhute | 0:30537dec6e0b | 83 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 84 | { |
akashvibhute | 0:30537dec6e0b | 85 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 86 | uint8_t positions_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 87 | if(positions_lengthT > positions_length) |
akashvibhute | 0:30537dec6e0b | 88 | this->positions = (float*)realloc(this->positions, positions_lengthT * sizeof(float)); |
akashvibhute | 0:30537dec6e0b | 89 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 90 | positions_length = positions_lengthT; |
akashvibhute | 0:30537dec6e0b | 91 | for( uint8_t i = 0; i < positions_length; i++){ |
akashvibhute | 0:30537dec6e0b | 92 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_positions)); |
akashvibhute | 0:30537dec6e0b | 93 | memcpy( &(this->positions[i]), &(this->st_positions), sizeof(float)); |
akashvibhute | 0:30537dec6e0b | 94 | } |
akashvibhute | 0:30537dec6e0b | 95 | uint8_t velocities_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 96 | if(velocities_lengthT > velocities_length) |
akashvibhute | 0:30537dec6e0b | 97 | this->velocities = (float*)realloc(this->velocities, velocities_lengthT * sizeof(float)); |
akashvibhute | 0:30537dec6e0b | 98 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 99 | velocities_length = velocities_lengthT; |
akashvibhute | 0:30537dec6e0b | 100 | for( uint8_t i = 0; i < velocities_length; i++){ |
akashvibhute | 0:30537dec6e0b | 101 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_velocities)); |
akashvibhute | 0:30537dec6e0b | 102 | memcpy( &(this->velocities[i]), &(this->st_velocities), sizeof(float)); |
akashvibhute | 0:30537dec6e0b | 103 | } |
akashvibhute | 0:30537dec6e0b | 104 | uint8_t accelerations_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 105 | if(accelerations_lengthT > accelerations_length) |
akashvibhute | 0:30537dec6e0b | 106 | this->accelerations = (float*)realloc(this->accelerations, accelerations_lengthT * sizeof(float)); |
akashvibhute | 0:30537dec6e0b | 107 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 108 | accelerations_length = accelerations_lengthT; |
akashvibhute | 0:30537dec6e0b | 109 | for( uint8_t i = 0; i < accelerations_length; i++){ |
akashvibhute | 0:30537dec6e0b | 110 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_accelerations)); |
akashvibhute | 0:30537dec6e0b | 111 | memcpy( &(this->accelerations[i]), &(this->st_accelerations), sizeof(float)); |
akashvibhute | 0:30537dec6e0b | 112 | } |
akashvibhute | 0:30537dec6e0b | 113 | uint8_t effort_lengthT = *(inbuffer + offset++); |
akashvibhute | 0:30537dec6e0b | 114 | if(effort_lengthT > effort_length) |
akashvibhute | 0:30537dec6e0b | 115 | this->effort = (float*)realloc(this->effort, effort_lengthT * sizeof(float)); |
akashvibhute | 0:30537dec6e0b | 116 | offset += 3; |
akashvibhute | 0:30537dec6e0b | 117 | effort_length = effort_lengthT; |
akashvibhute | 0:30537dec6e0b | 118 | for( uint8_t i = 0; i < effort_length; i++){ |
akashvibhute | 0:30537dec6e0b | 119 | offset += deserializeAvrFloat64(inbuffer + offset, &(this->st_effort)); |
akashvibhute | 0:30537dec6e0b | 120 | memcpy( &(this->effort[i]), &(this->st_effort), sizeof(float)); |
akashvibhute | 0:30537dec6e0b | 121 | } |
akashvibhute | 0:30537dec6e0b | 122 | this->time_from_start.sec = ((uint32_t) (*(inbuffer + offset))); |
akashvibhute | 0:30537dec6e0b | 123 | this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 124 | this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 125 | this->time_from_start.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 126 | offset += sizeof(this->time_from_start.sec); |
akashvibhute | 0:30537dec6e0b | 127 | this->time_from_start.nsec = ((uint32_t) (*(inbuffer + offset))); |
akashvibhute | 0:30537dec6e0b | 128 | this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 129 | this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 130 | this->time_from_start.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 131 | offset += sizeof(this->time_from_start.nsec); |
akashvibhute | 0:30537dec6e0b | 132 | return offset; |
akashvibhute | 0:30537dec6e0b | 133 | } |
akashvibhute | 0:30537dec6e0b | 134 | |
akashvibhute | 0:30537dec6e0b | 135 | const char * getType(){ return "trajectory_msgs/JointTrajectoryPoint"; }; |
akashvibhute | 0:30537dec6e0b | 136 | const char * getMD5(){ return "f3cd1e1c4d320c79d6985c904ae5dcd3"; }; |
akashvibhute | 0:30537dec6e0b | 137 | |
akashvibhute | 0:30537dec6e0b | 138 | }; |
akashvibhute | 0:30537dec6e0b | 139 | |
akashvibhute | 0:30537dec6e0b | 140 | } |
akashvibhute | 0:30537dec6e0b | 141 | #endif |