Personal fork
Fork of rosserial_mbed_lib by
nav_msgs/Path.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_Path_h |
nucho | 0:77afd7560544 | 2 | #define ros_Path_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/PoseStamped.h" |
nucho | 0:77afd7560544 | 10 | |
nucho | 0:77afd7560544 | 11 | namespace nav_msgs |
nucho | 0:77afd7560544 | 12 | { |
nucho | 0:77afd7560544 | 13 | |
nucho | 0:77afd7560544 | 14 | class Path : public ros::Msg |
nucho | 0:77afd7560544 | 15 | { |
nucho | 0:77afd7560544 | 16 | public: |
nucho | 0:77afd7560544 | 17 | std_msgs::Header header; |
nucho | 0:77afd7560544 | 18 | unsigned char poses_length; |
nucho | 0:77afd7560544 | 19 | geometry_msgs::PoseStamped st_poses; |
nucho | 0:77afd7560544 | 20 | geometry_msgs::PoseStamped * poses; |
nucho | 0:77afd7560544 | 21 | |
nucho | 0:77afd7560544 | 22 | virtual int serialize(unsigned char *outbuffer) |
nucho | 0:77afd7560544 | 23 | { |
nucho | 0:77afd7560544 | 24 | int offset = 0; |
nucho | 0:77afd7560544 | 25 | offset += this->header.serialize(outbuffer + offset); |
nucho | 0:77afd7560544 | 26 | *(outbuffer + offset++) = poses_length; |
nucho | 0:77afd7560544 | 27 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 28 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 29 | *(outbuffer + offset++) = 0; |
nucho | 0:77afd7560544 | 30 | for( unsigned char i = 0; i < poses_length; i++){ |
nucho | 0:77afd7560544 | 31 | offset += this->poses[i].serialize(outbuffer + offset); |
nucho | 0:77afd7560544 | 32 | } |
nucho | 0:77afd7560544 | 33 | return offset; |
nucho | 0:77afd7560544 | 34 | } |
nucho | 0:77afd7560544 | 35 | |
nucho | 0:77afd7560544 | 36 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 0:77afd7560544 | 37 | { |
nucho | 0:77afd7560544 | 38 | int offset = 0; |
nucho | 0:77afd7560544 | 39 | offset += this->header.deserialize(inbuffer + offset); |
nucho | 0:77afd7560544 | 40 | unsigned char poses_lengthT = *(inbuffer + offset++); |
nucho | 0:77afd7560544 | 41 | if(poses_lengthT > poses_length) |
nucho | 0:77afd7560544 | 42 | this->poses = (geometry_msgs::PoseStamped*)realloc(this->poses, poses_lengthT * sizeof(geometry_msgs::PoseStamped)); |
nucho | 0:77afd7560544 | 43 | offset += 3; |
nucho | 0:77afd7560544 | 44 | poses_length = poses_lengthT; |
nucho | 0:77afd7560544 | 45 | for( unsigned char i = 0; i < poses_length; i++){ |
nucho | 0:77afd7560544 | 46 | offset += this->st_poses.deserialize(inbuffer + offset); |
nucho | 0:77afd7560544 | 47 | memcpy( &(this->poses[i]), &(this->st_poses), sizeof(geometry_msgs::PoseStamped)); |
nucho | 0:77afd7560544 | 48 | } |
nucho | 0:77afd7560544 | 49 | return offset; |
nucho | 0:77afd7560544 | 50 | } |
nucho | 0:77afd7560544 | 51 | |
nucho | 0:77afd7560544 | 52 | virtual const char * getType(){ return "nav_msgs/Path"; }; |
nucho | 0:77afd7560544 | 53 | |
nucho | 0:77afd7560544 | 54 | }; |
nucho | 0:77afd7560544 | 55 | |
nucho | 0:77afd7560544 | 56 | } |
nucho | 0:77afd7560544 | 57 | #endif |