ROS Serial library for Mbed platforms for ROS Indigo Igloo. Check http://wiki.ros.org/rosserial_mbed/ for more information
Dependents: rosserial_mbed_hello_world_publisher rtos_base_control rosserial_mbed_F64MA ROS-RTOS ... more
GetPlan.h
00001 #ifndef _ROS_SERVICE_GetPlan_h 00002 #define _ROS_SERVICE_GetPlan_h 00003 #include <stdint.h> 00004 #include <string.h> 00005 #include <stdlib.h> 00006 #include "ros/msg.h" 00007 #include "geometry_msgs/PoseStamped.h" 00008 #include "nav_msgs/Path.h" 00009 00010 namespace nav_msgs 00011 { 00012 00013 static const char GETPLAN[] = "nav_msgs/GetPlan"; 00014 00015 class GetPlanRequest : public ros::Msg 00016 { 00017 public: 00018 geometry_msgs::PoseStamped start; 00019 geometry_msgs::PoseStamped goal; 00020 float tolerance; 00021 00022 GetPlanRequest(): 00023 start(), 00024 goal(), 00025 tolerance(0) 00026 { 00027 } 00028 00029 virtual int serialize(unsigned char *outbuffer) const 00030 { 00031 int offset = 0; 00032 offset += this->start.serialize(outbuffer + offset); 00033 offset += this->goal.serialize(outbuffer + offset); 00034 union { 00035 float real; 00036 uint32_t base; 00037 } u_tolerance; 00038 u_tolerance.real = this->tolerance; 00039 *(outbuffer + offset + 0) = (u_tolerance.base >> (8 * 0)) & 0xFF; 00040 *(outbuffer + offset + 1) = (u_tolerance.base >> (8 * 1)) & 0xFF; 00041 *(outbuffer + offset + 2) = (u_tolerance.base >> (8 * 2)) & 0xFF; 00042 *(outbuffer + offset + 3) = (u_tolerance.base >> (8 * 3)) & 0xFF; 00043 offset += sizeof(this->tolerance); 00044 return offset; 00045 } 00046 00047 virtual int deserialize(unsigned char *inbuffer) 00048 { 00049 int offset = 0; 00050 offset += this->start.deserialize(inbuffer + offset); 00051 offset += this->goal.deserialize(inbuffer + offset); 00052 union { 00053 float real; 00054 uint32_t base; 00055 } u_tolerance; 00056 u_tolerance.base = 0; 00057 u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00058 u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00059 u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00060 u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00061 this->tolerance = u_tolerance.real; 00062 offset += sizeof(this->tolerance); 00063 return offset; 00064 } 00065 00066 const char * getType(){ return GETPLAN; }; 00067 const char * getMD5(){ return "e25a43e0752bcca599a8c2eef8282df8"; }; 00068 00069 }; 00070 00071 class GetPlanResponse : public ros::Msg 00072 { 00073 public: 00074 nav_msgs::Path plan; 00075 00076 GetPlanResponse(): 00077 plan() 00078 { 00079 } 00080 00081 virtual int serialize(unsigned char *outbuffer) const 00082 { 00083 int offset = 0; 00084 offset += this->plan.serialize(outbuffer + offset); 00085 return offset; 00086 } 00087 00088 virtual int deserialize(unsigned char *inbuffer) 00089 { 00090 int offset = 0; 00091 offset += this->plan.deserialize(inbuffer + offset); 00092 return offset; 00093 } 00094 00095 const char * getType(){ return GETPLAN; }; 00096 const char * getMD5(){ return "0002bc113c0259d71f6cf8cbc9430e18"; }; 00097 00098 }; 00099 00100 class GetPlan { 00101 public: 00102 typedef GetPlanRequest Request; 00103 typedef GetPlanResponse Response; 00104 }; 00105 00106 } 00107 #endif
Generated on Tue Jul 12 2022 18:39:39 by 1.7.2