rosserial library for mbed Inspired by nucho's rosserial library This library is still under development
Dependents: mbed_roshydro_test
Library still under development!
turtlesim/Pose.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_turtlesim_Pose_h |
akashvibhute | 0:30537dec6e0b | 2 | #define _ROS_turtlesim_Pose_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 | |
akashvibhute | 0:30537dec6e0b | 9 | namespace turtlesim |
akashvibhute | 0:30537dec6e0b | 10 | { |
akashvibhute | 0:30537dec6e0b | 11 | |
akashvibhute | 0:30537dec6e0b | 12 | class Pose : public ros::Msg |
akashvibhute | 0:30537dec6e0b | 13 | { |
akashvibhute | 0:30537dec6e0b | 14 | public: |
akashvibhute | 0:30537dec6e0b | 15 | float x; |
akashvibhute | 0:30537dec6e0b | 16 | float y; |
akashvibhute | 0:30537dec6e0b | 17 | float theta; |
akashvibhute | 0:30537dec6e0b | 18 | float linear_velocity; |
akashvibhute | 0:30537dec6e0b | 19 | float angular_velocity; |
akashvibhute | 0:30537dec6e0b | 20 | |
akashvibhute | 0:30537dec6e0b | 21 | Pose(): |
akashvibhute | 0:30537dec6e0b | 22 | x(0), |
akashvibhute | 0:30537dec6e0b | 23 | y(0), |
akashvibhute | 0:30537dec6e0b | 24 | theta(0), |
akashvibhute | 0:30537dec6e0b | 25 | linear_velocity(0), |
akashvibhute | 0:30537dec6e0b | 26 | angular_velocity(0) |
akashvibhute | 0:30537dec6e0b | 27 | { |
akashvibhute | 0:30537dec6e0b | 28 | } |
akashvibhute | 0:30537dec6e0b | 29 | |
akashvibhute | 0:30537dec6e0b | 30 | virtual int serialize(unsigned char *outbuffer) const |
akashvibhute | 0:30537dec6e0b | 31 | { |
akashvibhute | 0:30537dec6e0b | 32 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 33 | union { |
akashvibhute | 0:30537dec6e0b | 34 | float real; |
akashvibhute | 0:30537dec6e0b | 35 | uint32_t base; |
akashvibhute | 0:30537dec6e0b | 36 | } u_x; |
akashvibhute | 0:30537dec6e0b | 37 | u_x.real = this->x; |
akashvibhute | 0:30537dec6e0b | 38 | *(outbuffer + offset + 0) = (u_x.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 39 | *(outbuffer + offset + 1) = (u_x.base >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 40 | *(outbuffer + offset + 2) = (u_x.base >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 41 | *(outbuffer + offset + 3) = (u_x.base >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 42 | offset += sizeof(this->x); |
akashvibhute | 0:30537dec6e0b | 43 | union { |
akashvibhute | 0:30537dec6e0b | 44 | float real; |
akashvibhute | 0:30537dec6e0b | 45 | uint32_t base; |
akashvibhute | 0:30537dec6e0b | 46 | } u_y; |
akashvibhute | 0:30537dec6e0b | 47 | u_y.real = this->y; |
akashvibhute | 0:30537dec6e0b | 48 | *(outbuffer + offset + 0) = (u_y.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 49 | *(outbuffer + offset + 1) = (u_y.base >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 50 | *(outbuffer + offset + 2) = (u_y.base >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 51 | *(outbuffer + offset + 3) = (u_y.base >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 52 | offset += sizeof(this->y); |
akashvibhute | 0:30537dec6e0b | 53 | union { |
akashvibhute | 0:30537dec6e0b | 54 | float real; |
akashvibhute | 0:30537dec6e0b | 55 | uint32_t base; |
akashvibhute | 0:30537dec6e0b | 56 | } u_theta; |
akashvibhute | 0:30537dec6e0b | 57 | u_theta.real = this->theta; |
akashvibhute | 0:30537dec6e0b | 58 | *(outbuffer + offset + 0) = (u_theta.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 59 | *(outbuffer + offset + 1) = (u_theta.base >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 60 | *(outbuffer + offset + 2) = (u_theta.base >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 61 | *(outbuffer + offset + 3) = (u_theta.base >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 62 | offset += sizeof(this->theta); |
akashvibhute | 0:30537dec6e0b | 63 | union { |
akashvibhute | 0:30537dec6e0b | 64 | float real; |
akashvibhute | 0:30537dec6e0b | 65 | uint32_t base; |
akashvibhute | 0:30537dec6e0b | 66 | } u_linear_velocity; |
akashvibhute | 0:30537dec6e0b | 67 | u_linear_velocity.real = this->linear_velocity; |
akashvibhute | 0:30537dec6e0b | 68 | *(outbuffer + offset + 0) = (u_linear_velocity.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 69 | *(outbuffer + offset + 1) = (u_linear_velocity.base >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 70 | *(outbuffer + offset + 2) = (u_linear_velocity.base >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 71 | *(outbuffer + offset + 3) = (u_linear_velocity.base >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 72 | offset += sizeof(this->linear_velocity); |
akashvibhute | 0:30537dec6e0b | 73 | union { |
akashvibhute | 0:30537dec6e0b | 74 | float real; |
akashvibhute | 0:30537dec6e0b | 75 | uint32_t base; |
akashvibhute | 0:30537dec6e0b | 76 | } u_angular_velocity; |
akashvibhute | 0:30537dec6e0b | 77 | u_angular_velocity.real = this->angular_velocity; |
akashvibhute | 0:30537dec6e0b | 78 | *(outbuffer + offset + 0) = (u_angular_velocity.base >> (8 * 0)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 79 | *(outbuffer + offset + 1) = (u_angular_velocity.base >> (8 * 1)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 80 | *(outbuffer + offset + 2) = (u_angular_velocity.base >> (8 * 2)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 81 | *(outbuffer + offset + 3) = (u_angular_velocity.base >> (8 * 3)) & 0xFF; |
akashvibhute | 0:30537dec6e0b | 82 | offset += sizeof(this->angular_velocity); |
akashvibhute | 0:30537dec6e0b | 83 | return offset; |
akashvibhute | 0:30537dec6e0b | 84 | } |
akashvibhute | 0:30537dec6e0b | 85 | |
akashvibhute | 0:30537dec6e0b | 86 | virtual int deserialize(unsigned char *inbuffer) |
akashvibhute | 0:30537dec6e0b | 87 | { |
akashvibhute | 0:30537dec6e0b | 88 | int offset = 0; |
akashvibhute | 0:30537dec6e0b | 89 | union { |
akashvibhute | 0:30537dec6e0b | 90 | float real; |
akashvibhute | 0:30537dec6e0b | 91 | uint32_t base; |
akashvibhute | 0:30537dec6e0b | 92 | } u_x; |
akashvibhute | 0:30537dec6e0b | 93 | u_x.base = 0; |
akashvibhute | 0:30537dec6e0b | 94 | u_x.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 95 | u_x.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 96 | u_x.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 97 | u_x.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 98 | this->x = u_x.real; |
akashvibhute | 0:30537dec6e0b | 99 | offset += sizeof(this->x); |
akashvibhute | 0:30537dec6e0b | 100 | union { |
akashvibhute | 0:30537dec6e0b | 101 | float real; |
akashvibhute | 0:30537dec6e0b | 102 | uint32_t base; |
akashvibhute | 0:30537dec6e0b | 103 | } u_y; |
akashvibhute | 0:30537dec6e0b | 104 | u_y.base = 0; |
akashvibhute | 0:30537dec6e0b | 105 | u_y.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 106 | u_y.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 107 | u_y.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 108 | u_y.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 109 | this->y = u_y.real; |
akashvibhute | 0:30537dec6e0b | 110 | offset += sizeof(this->y); |
akashvibhute | 0:30537dec6e0b | 111 | union { |
akashvibhute | 0:30537dec6e0b | 112 | float real; |
akashvibhute | 0:30537dec6e0b | 113 | uint32_t base; |
akashvibhute | 0:30537dec6e0b | 114 | } u_theta; |
akashvibhute | 0:30537dec6e0b | 115 | u_theta.base = 0; |
akashvibhute | 0:30537dec6e0b | 116 | u_theta.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 117 | u_theta.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 118 | u_theta.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 119 | u_theta.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 120 | this->theta = u_theta.real; |
akashvibhute | 0:30537dec6e0b | 121 | offset += sizeof(this->theta); |
akashvibhute | 0:30537dec6e0b | 122 | union { |
akashvibhute | 0:30537dec6e0b | 123 | float real; |
akashvibhute | 0:30537dec6e0b | 124 | uint32_t base; |
akashvibhute | 0:30537dec6e0b | 125 | } u_linear_velocity; |
akashvibhute | 0:30537dec6e0b | 126 | u_linear_velocity.base = 0; |
akashvibhute | 0:30537dec6e0b | 127 | u_linear_velocity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 128 | u_linear_velocity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 129 | u_linear_velocity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 130 | u_linear_velocity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 131 | this->linear_velocity = u_linear_velocity.real; |
akashvibhute | 0:30537dec6e0b | 132 | offset += sizeof(this->linear_velocity); |
akashvibhute | 0:30537dec6e0b | 133 | union { |
akashvibhute | 0:30537dec6e0b | 134 | float real; |
akashvibhute | 0:30537dec6e0b | 135 | uint32_t base; |
akashvibhute | 0:30537dec6e0b | 136 | } u_angular_velocity; |
akashvibhute | 0:30537dec6e0b | 137 | u_angular_velocity.base = 0; |
akashvibhute | 0:30537dec6e0b | 138 | u_angular_velocity.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); |
akashvibhute | 0:30537dec6e0b | 139 | u_angular_velocity.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); |
akashvibhute | 0:30537dec6e0b | 140 | u_angular_velocity.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); |
akashvibhute | 0:30537dec6e0b | 141 | u_angular_velocity.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); |
akashvibhute | 0:30537dec6e0b | 142 | this->angular_velocity = u_angular_velocity.real; |
akashvibhute | 0:30537dec6e0b | 143 | offset += sizeof(this->angular_velocity); |
akashvibhute | 0:30537dec6e0b | 144 | return offset; |
akashvibhute | 0:30537dec6e0b | 145 | } |
akashvibhute | 0:30537dec6e0b | 146 | |
akashvibhute | 0:30537dec6e0b | 147 | const char * getType(){ return "turtlesim/Pose"; }; |
akashvibhute | 0:30537dec6e0b | 148 | const char * getMD5(){ return "863b248d5016ca62ea2e895ae5265cf9"; }; |
akashvibhute | 0:30537dec6e0b | 149 | |
akashvibhute | 0:30537dec6e0b | 150 | }; |
akashvibhute | 0:30537dec6e0b | 151 | |
akashvibhute | 0:30537dec6e0b | 152 | } |
akashvibhute | 0:30537dec6e0b | 153 | #endif |