It has only one change from original one. I added robotfeedback message on it.
Dependents: RobotFeedback mobileRobotITU
Fork of ros_lib_indigo by
geometry_msgs/TwistWithCovariance.h@0:fd24f7ca9688, 2016-03-31 (annotated)
- Committer:
- garyservin
- Date:
- Thu Mar 31 14:22:59 2016 +0000
- Revision:
- 0:fd24f7ca9688
Initial commit, generated based on a clean indigo-desktop-full
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
garyservin | 0:fd24f7ca9688 | 1 | #ifndef _ROS_geometry_msgs_TwistWithCovariance_h |
garyservin | 0:fd24f7ca9688 | 2 | #define _ROS_geometry_msgs_TwistWithCovariance_h |
garyservin | 0:fd24f7ca9688 | 3 | |
garyservin | 0:fd24f7ca9688 | 4 | #include <stdint.h> |
garyservin | 0:fd24f7ca9688 | 5 | #include <string.h> |
garyservin | 0:fd24f7ca9688 | 6 | #include <stdlib.h> |
garyservin | 0:fd24f7ca9688 | 7 | #include "ros/msg.h" |
garyservin | 0:fd24f7ca9688 | 8 | #include "geometry_msgs/Twist.h" |
garyservin | 0:fd24f7ca9688 | 9 | |
garyservin | 0:fd24f7ca9688 | 10 | namespace geometry_msgs |
garyservin | 0:fd24f7ca9688 | 11 | { |
garyservin | 0:fd24f7ca9688 | 12 | |
garyservin | 0:fd24f7ca9688 | 13 | class TwistWithCovariance : public ros::Msg |
garyservin | 0:fd24f7ca9688 | 14 | { |
garyservin | 0:fd24f7ca9688 | 15 | public: |
garyservin | 0:fd24f7ca9688 | 16 | geometry_msgs::Twist twist; |
garyservin | 0:fd24f7ca9688 | 17 | double covariance[36]; |
garyservin | 0:fd24f7ca9688 | 18 | |
garyservin | 0:fd24f7ca9688 | 19 | TwistWithCovariance(): |
garyservin | 0:fd24f7ca9688 | 20 | twist(), |
garyservin | 0:fd24f7ca9688 | 21 | covariance() |
garyservin | 0:fd24f7ca9688 | 22 | { |
garyservin | 0:fd24f7ca9688 | 23 | } |
garyservin | 0:fd24f7ca9688 | 24 | |
garyservin | 0:fd24f7ca9688 | 25 | virtual int serialize(unsigned char *outbuffer) const |
garyservin | 0:fd24f7ca9688 | 26 | { |
garyservin | 0:fd24f7ca9688 | 27 | int offset = 0; |
garyservin | 0:fd24f7ca9688 | 28 | offset += this->twist.serialize(outbuffer + offset); |
garyservin | 0:fd24f7ca9688 | 29 | for( uint8_t i = 0; i < 36; i++){ |
garyservin | 0:fd24f7ca9688 | 30 | union { |
garyservin | 0:fd24f7ca9688 | 31 | double real; |
garyservin | 0:fd24f7ca9688 | 32 | uint64_t base; |
garyservin | 0:fd24f7ca9688 | 33 | } u_covariancei; |
garyservin | 0:fd24f7ca9688 | 34 | u_covariancei.real = this->covariance[i]; |
garyservin | 0:fd24f7ca9688 | 35 | *(outbuffer + offset + 0) = (u_covariancei.base >> (8 * 0)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 36 | *(outbuffer + offset + 1) = (u_covariancei.base >> (8 * 1)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 37 | *(outbuffer + offset + 2) = (u_covariancei.base >> (8 * 2)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 38 | *(outbuffer + offset + 3) = (u_covariancei.base >> (8 * 3)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 39 | *(outbuffer + offset + 4) = (u_covariancei.base >> (8 * 4)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 40 | *(outbuffer + offset + 5) = (u_covariancei.base >> (8 * 5)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 41 | *(outbuffer + offset + 6) = (u_covariancei.base >> (8 * 6)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 42 | *(outbuffer + offset + 7) = (u_covariancei.base >> (8 * 7)) & 0xFF; |
garyservin | 0:fd24f7ca9688 | 43 | offset += sizeof(this->covariance[i]); |
garyservin | 0:fd24f7ca9688 | 44 | } |
garyservin | 0:fd24f7ca9688 | 45 | return offset; |
garyservin | 0:fd24f7ca9688 | 46 | } |
garyservin | 0:fd24f7ca9688 | 47 | |
garyservin | 0:fd24f7ca9688 | 48 | virtual int deserialize(unsigned char *inbuffer) |
garyservin | 0:fd24f7ca9688 | 49 | { |
garyservin | 0:fd24f7ca9688 | 50 | int offset = 0; |
garyservin | 0:fd24f7ca9688 | 51 | offset += this->twist.deserialize(inbuffer + offset); |
garyservin | 0:fd24f7ca9688 | 52 | for( uint8_t i = 0; i < 36; i++){ |
garyservin | 0:fd24f7ca9688 | 53 | union { |
garyservin | 0:fd24f7ca9688 | 54 | double real; |
garyservin | 0:fd24f7ca9688 | 55 | uint64_t base; |
garyservin | 0:fd24f7ca9688 | 56 | } u_covariancei; |
garyservin | 0:fd24f7ca9688 | 57 | u_covariancei.base = 0; |
garyservin | 0:fd24f7ca9688 | 58 | u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 0))) << (8 * 0); |
garyservin | 0:fd24f7ca9688 | 59 | u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 1))) << (8 * 1); |
garyservin | 0:fd24f7ca9688 | 60 | u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 2))) << (8 * 2); |
garyservin | 0:fd24f7ca9688 | 61 | u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 3))) << (8 * 3); |
garyservin | 0:fd24f7ca9688 | 62 | u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 4))) << (8 * 4); |
garyservin | 0:fd24f7ca9688 | 63 | u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 5))) << (8 * 5); |
garyservin | 0:fd24f7ca9688 | 64 | u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 6))) << (8 * 6); |
garyservin | 0:fd24f7ca9688 | 65 | u_covariancei.base |= ((uint64_t) (*(inbuffer + offset + 7))) << (8 * 7); |
garyservin | 0:fd24f7ca9688 | 66 | this->covariance[i] = u_covariancei.real; |
garyservin | 0:fd24f7ca9688 | 67 | offset += sizeof(this->covariance[i]); |
garyservin | 0:fd24f7ca9688 | 68 | } |
garyservin | 0:fd24f7ca9688 | 69 | return offset; |
garyservin | 0:fd24f7ca9688 | 70 | } |
garyservin | 0:fd24f7ca9688 | 71 | |
garyservin | 0:fd24f7ca9688 | 72 | const char * getType(){ return "geometry_msgs/TwistWithCovariance"; }; |
garyservin | 0:fd24f7ca9688 | 73 | const char * getMD5(){ return "1fe8a28e6890a4cc3ae4c3ca5c7d82e6"; }; |
garyservin | 0:fd24f7ca9688 | 74 | |
garyservin | 0:fd24f7ca9688 | 75 | }; |
garyservin | 0:fd24f7ca9688 | 76 | |
garyservin | 0:fd24f7ca9688 | 77 | } |
garyservin | 0:fd24f7ca9688 | 78 | #endif |