Personal fork
Fork of rosserial_mbed_lib by
nav_msgs/Odometry.h@0:77afd7560544, 2011-08-19 (annotated)
- Committer:
- nucho
- Date:
- Fri Aug 19 09:06:30 2011 +0000
- Revision:
- 0:77afd7560544
- Child:
- 1:ff0ec969dad1
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
nucho | 0:77afd7560544 | 1 | #ifndef ros_Odometry_h |
nucho | 0:77afd7560544 | 2 | #define ros_Odometry_h |
nucho | 0:77afd7560544 | 3 | |
nucho | 0:77afd7560544 | 4 | #include <stdint.h> |
nucho | 0:77afd7560544 | 5 | #include <string.h> |
nucho | 0:77afd7560544 | 6 | #include <stdlib.h> |
nucho | 0:77afd7560544 | 7 | #include "../ros/msg.h" |
nucho | 0:77afd7560544 | 8 | #include "std_msgs/Header.h" |
nucho | 0:77afd7560544 | 9 | #include "geometry_msgs/PoseWithCovariance.h" |
nucho | 0:77afd7560544 | 10 | #include "geometry_msgs/TwistWithCovariance.h" |
nucho | 0:77afd7560544 | 11 | |
nucho | 0:77afd7560544 | 12 | namespace nav_msgs |
nucho | 0:77afd7560544 | 13 | { |
nucho | 0:77afd7560544 | 14 | |
nucho | 0:77afd7560544 | 15 | class Odometry : public ros::Msg |
nucho | 0:77afd7560544 | 16 | { |
nucho | 0:77afd7560544 | 17 | public: |
nucho | 0:77afd7560544 | 18 | std_msgs::Header header; |
nucho | 0:77afd7560544 | 19 | char * child_frame_id; |
nucho | 0:77afd7560544 | 20 | geometry_msgs::PoseWithCovariance pose; |
nucho | 0:77afd7560544 | 21 | geometry_msgs::TwistWithCovariance twist; |
nucho | 0:77afd7560544 | 22 | |
nucho | 0:77afd7560544 | 23 | virtual int serialize(unsigned char *outbuffer) |
nucho | 0:77afd7560544 | 24 | { |
nucho | 0:77afd7560544 | 25 | int offset = 0; |
nucho | 0:77afd7560544 | 26 | offset += this->header.serialize(outbuffer + offset); |
nucho | 0:77afd7560544 | 27 | long * length_child_frame_id = (long *)(outbuffer + offset); |
nucho | 0:77afd7560544 | 28 | *length_child_frame_id = strlen( (const char*) this->child_frame_id); |
nucho | 0:77afd7560544 | 29 | offset += 4; |
nucho | 0:77afd7560544 | 30 | memcpy(outbuffer + offset, this->child_frame_id, *length_child_frame_id); |
nucho | 0:77afd7560544 | 31 | offset += *length_child_frame_id; |
nucho | 0:77afd7560544 | 32 | offset += this->pose.serialize(outbuffer + offset); |
nucho | 0:77afd7560544 | 33 | offset += this->twist.serialize(outbuffer + offset); |
nucho | 0:77afd7560544 | 34 | return offset; |
nucho | 0:77afd7560544 | 35 | } |
nucho | 0:77afd7560544 | 36 | |
nucho | 0:77afd7560544 | 37 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 0:77afd7560544 | 38 | { |
nucho | 0:77afd7560544 | 39 | int offset = 0; |
nucho | 0:77afd7560544 | 40 | offset += this->header.deserialize(inbuffer + offset); |
nucho | 0:77afd7560544 | 41 | uint32_t length_child_frame_id = *(uint32_t *)(inbuffer + offset); |
nucho | 0:77afd7560544 | 42 | offset += 4; |
nucho | 0:77afd7560544 | 43 | for(unsigned int k= offset; k< offset+length_child_frame_id; ++k){ |
nucho | 0:77afd7560544 | 44 | inbuffer[k-1]=inbuffer[k]; |
nucho | 0:77afd7560544 | 45 | } |
nucho | 0:77afd7560544 | 46 | inbuffer[offset+length_child_frame_id-1]=0; |
nucho | 0:77afd7560544 | 47 | this->child_frame_id = (char *)(inbuffer + offset-1); |
nucho | 0:77afd7560544 | 48 | offset += length_child_frame_id; |
nucho | 0:77afd7560544 | 49 | offset += this->pose.deserialize(inbuffer + offset); |
nucho | 0:77afd7560544 | 50 | offset += this->twist.deserialize(inbuffer + offset); |
nucho | 0:77afd7560544 | 51 | return offset; |
nucho | 0:77afd7560544 | 52 | } |
nucho | 0:77afd7560544 | 53 | |
nucho | 0:77afd7560544 | 54 | virtual const char * getType(){ return "nav_msgs/Odometry"; }; |
nucho | 0:77afd7560544 | 55 | |
nucho | 0:77afd7560544 | 56 | }; |
nucho | 0:77afd7560544 | 57 | |
nucho | 0:77afd7560544 | 58 | } |
nucho | 0:77afd7560544 | 59 | #endif |