1 #ifndef _ROS_SERVICE_GetPlan_h
2 #define _ROS_SERVICE_GetPlan_h
13 static const char GETPLAN[] =
"nav_msgs/GetPlan";
29 virtual int serialize(
unsigned char *outbuffer)
const
39 *(outbuffer + offset + 0) = (u_tolerance.base >> (8 * 0)) & 0xFF;
40 *(outbuffer + offset + 1) = (u_tolerance.base >> (8 * 1)) & 0xFF;
41 *(outbuffer + offset + 2) = (u_tolerance.base >> (8 * 2)) & 0xFF;
42 *(outbuffer + offset + 3) = (u_tolerance.base >> (8 * 3)) & 0xFF;
57 u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0);
58 u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
59 u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
60 u_tolerance.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
67 const char *
getMD5(){
return "e25a43e0752bcca599a8c2eef8282df8"; };
81 virtual int serialize(
unsigned char *outbuffer)
const
96 const char *
getMD5(){
return "0002bc113c0259d71f6cf8cbc9430e18"; };
virtual int serialize(unsigned char *outbuffer) const
Definition: Path.h:28
const char * getType()
Definition: GetPlan.h:95
nav_msgs::Path plan
Definition: GetPlan.h:74
geometry_msgs::PoseStamped start
Definition: GetPlan.h:18
GetPlanResponse()
Definition: GetPlan.h:76
virtual int deserialize(unsigned char *inbuffer)
Definition: GetPlan.h:47
static const char GETPLAN[]
Definition: GetPlan.h:13
virtual int deserialize(unsigned char *inbuffer)
Definition: Path.h:42
virtual int deserialize(unsigned char *inbuffer)
Definition: PoseStamped.h:34
GetPlanRequest()
Definition: GetPlan.h:22
Definition: PoseStamped.h:14
GetPlanRequest Request
Definition: GetPlan.h:102
const char * getMD5()
Definition: GetPlan.h:96
GetPlanResponse Response
Definition: GetPlan.h:103
Definition: GetPlan.h:100
const char * getType()
Definition: GetPlan.h:66
virtual int serialize(unsigned char *outbuffer) const
Definition: PoseStamped.h:26
const char * getMD5()
Definition: GetPlan.h:67
virtual int serialize(unsigned char *outbuffer) const
Definition: GetPlan.h:81
geometry_msgs::PoseStamped goal
Definition: GetPlan.h:19
virtual int deserialize(unsigned char *inbuffer)
Definition: GetPlan.h:88
float tolerance
Definition: GetPlan.h:20
virtual int serialize(unsigned char *outbuffer) const
Definition: GetPlan.h:29