This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial. This program contains an example.
Dependencies: rosserial_mbed_lib mbed Servo
nav_msgs/GetPlan.h@0:06fc856e99ca, 2011-08-19 (annotated)
- Committer:
- nucho
- Date:
- Fri Aug 19 09:06:16 2011 +0000
- Revision:
- 0:06fc856e99ca
- Child:
- 3:dff241b66f84
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
nucho | 0:06fc856e99ca | 1 | #ifndef ros_SERVICE_GetPlan_h |
nucho | 0:06fc856e99ca | 2 | #define ros_SERVICE_GetPlan_h |
nucho | 0:06fc856e99ca | 3 | #include <stdint.h> |
nucho | 0:06fc856e99ca | 4 | #include <string.h> |
nucho | 0:06fc856e99ca | 5 | #include <stdlib.h> |
nucho | 0:06fc856e99ca | 6 | #include "../ros/msg.h" |
nucho | 0:06fc856e99ca | 7 | #include "geometry_msgs/PoseStamped.h" |
nucho | 0:06fc856e99ca | 8 | #include "nav_msgs/Path.h" |
nucho | 0:06fc856e99ca | 9 | |
nucho | 0:06fc856e99ca | 10 | namespace nav_msgs |
nucho | 0:06fc856e99ca | 11 | { |
nucho | 0:06fc856e99ca | 12 | |
nucho | 0:06fc856e99ca | 13 | static const char GETPLAN[] = "nav_msgs/GetPlan"; |
nucho | 0:06fc856e99ca | 14 | |
nucho | 0:06fc856e99ca | 15 | class GetPlanRequest : public ros::Msg |
nucho | 0:06fc856e99ca | 16 | { |
nucho | 0:06fc856e99ca | 17 | public: |
nucho | 0:06fc856e99ca | 18 | geometry_msgs::PoseStamped start; |
nucho | 0:06fc856e99ca | 19 | geometry_msgs::PoseStamped goal; |
nucho | 0:06fc856e99ca | 20 | float tolerance; |
nucho | 0:06fc856e99ca | 21 | |
nucho | 0:06fc856e99ca | 22 | virtual int serialize(unsigned char *outbuffer) |
nucho | 0:06fc856e99ca | 23 | { |
nucho | 0:06fc856e99ca | 24 | int offset = 0; |
nucho | 0:06fc856e99ca | 25 | offset += this->start.serialize(outbuffer + offset); |
nucho | 0:06fc856e99ca | 26 | offset += this->goal.serialize(outbuffer + offset); |
nucho | 0:06fc856e99ca | 27 | union { |
nucho | 0:06fc856e99ca | 28 | float real; |
nucho | 0:06fc856e99ca | 29 | unsigned long base; |
nucho | 0:06fc856e99ca | 30 | } u_tolerance; |
nucho | 0:06fc856e99ca | 31 | u_tolerance.real = this->tolerance; |
nucho | 0:06fc856e99ca | 32 | *(outbuffer + offset + 0) = (u_tolerance.base >> (8 * 0)) & 0xFF; |
nucho | 0:06fc856e99ca | 33 | *(outbuffer + offset + 1) = (u_tolerance.base >> (8 * 1)) & 0xFF; |
nucho | 0:06fc856e99ca | 34 | *(outbuffer + offset + 2) = (u_tolerance.base >> (8 * 2)) & 0xFF; |
nucho | 0:06fc856e99ca | 35 | *(outbuffer + offset + 3) = (u_tolerance.base >> (8 * 3)) & 0xFF; |
nucho | 0:06fc856e99ca | 36 | offset += sizeof(this->tolerance); |
nucho | 0:06fc856e99ca | 37 | return offset; |
nucho | 0:06fc856e99ca | 38 | } |
nucho | 0:06fc856e99ca | 39 | |
nucho | 0:06fc856e99ca | 40 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 0:06fc856e99ca | 41 | { |
nucho | 0:06fc856e99ca | 42 | int offset = 0; |
nucho | 0:06fc856e99ca | 43 | offset += this->start.deserialize(inbuffer + offset); |
nucho | 0:06fc856e99ca | 44 | offset += this->goal.deserialize(inbuffer + offset); |
nucho | 0:06fc856e99ca | 45 | union { |
nucho | 0:06fc856e99ca | 46 | float real; |
nucho | 0:06fc856e99ca | 47 | unsigned long base; |
nucho | 0:06fc856e99ca | 48 | } u_tolerance; |
nucho | 0:06fc856e99ca | 49 | u_tolerance.base = 0; |
nucho | 0:06fc856e99ca | 50 | u_tolerance.base |= ((typeof(u_tolerance.base)) (*(inbuffer + offset + 0))) << (8 * 0); |
nucho | 0:06fc856e99ca | 51 | u_tolerance.base |= ((typeof(u_tolerance.base)) (*(inbuffer + offset + 1))) << (8 * 1); |
nucho | 0:06fc856e99ca | 52 | u_tolerance.base |= ((typeof(u_tolerance.base)) (*(inbuffer + offset + 2))) << (8 * 2); |
nucho | 0:06fc856e99ca | 53 | u_tolerance.base |= ((typeof(u_tolerance.base)) (*(inbuffer + offset + 3))) << (8 * 3); |
nucho | 0:06fc856e99ca | 54 | this->tolerance = u_tolerance.real; |
nucho | 0:06fc856e99ca | 55 | offset += sizeof(this->tolerance); |
nucho | 0:06fc856e99ca | 56 | return offset; |
nucho | 0:06fc856e99ca | 57 | } |
nucho | 0:06fc856e99ca | 58 | |
nucho | 0:06fc856e99ca | 59 | const char * getType(){ return GETPLAN; }; |
nucho | 0:06fc856e99ca | 60 | |
nucho | 0:06fc856e99ca | 61 | }; |
nucho | 0:06fc856e99ca | 62 | |
nucho | 0:06fc856e99ca | 63 | class GetPlanResponse : public ros::Msg |
nucho | 0:06fc856e99ca | 64 | { |
nucho | 0:06fc856e99ca | 65 | public: |
nucho | 0:06fc856e99ca | 66 | nav_msgs::Path plan; |
nucho | 0:06fc856e99ca | 67 | |
nucho | 0:06fc856e99ca | 68 | virtual int serialize(unsigned char *outbuffer) |
nucho | 0:06fc856e99ca | 69 | { |
nucho | 0:06fc856e99ca | 70 | int offset = 0; |
nucho | 0:06fc856e99ca | 71 | offset += this->plan.serialize(outbuffer + offset); |
nucho | 0:06fc856e99ca | 72 | return offset; |
nucho | 0:06fc856e99ca | 73 | } |
nucho | 0:06fc856e99ca | 74 | |
nucho | 0:06fc856e99ca | 75 | virtual int deserialize(unsigned char *inbuffer) |
nucho | 0:06fc856e99ca | 76 | { |
nucho | 0:06fc856e99ca | 77 | int offset = 0; |
nucho | 0:06fc856e99ca | 78 | offset += this->plan.deserialize(inbuffer + offset); |
nucho | 0:06fc856e99ca | 79 | return offset; |
nucho | 0:06fc856e99ca | 80 | } |
nucho | 0:06fc856e99ca | 81 | |
nucho | 0:06fc856e99ca | 82 | virtual const char * getType(){ return GETPLAN; }; |
nucho | 0:06fc856e99ca | 83 | |
nucho | 0:06fc856e99ca | 84 | }; |
nucho | 0:06fc856e99ca | 85 | |
nucho | 0:06fc856e99ca | 86 | } |
nucho | 0:06fc856e99ca | 87 | #endif |