catchrobo2022 / Mbed 2 deprecated catchrobo2022_mbed

Dependencies:   mbed

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers SetTransformableMarkerPose.h Source File

SetTransformableMarkerPose.h

00001 #ifndef _ROS_SERVICE_SetTransformableMarkerPose_h
00002 #define _ROS_SERVICE_SetTransformableMarkerPose_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 
00009 namespace jsk_interactive_marker
00010 {
00011 
00012 static const char SETTRANSFORMABLEMARKERPOSE[] = "jsk_interactive_marker/SetTransformableMarkerPose";
00013 
00014   class SetTransformableMarkerPoseRequest : public ros::Msg
00015   {
00016     public:
00017       typedef const char* _target_name_type;
00018       _target_name_type target_name;
00019       typedef geometry_msgs::PoseStamped _pose_stamped_type;
00020       _pose_stamped_type pose_stamped;
00021 
00022     SetTransformableMarkerPoseRequest():
00023       target_name(""),
00024       pose_stamped()
00025     {
00026     }
00027 
00028     virtual int serialize(unsigned char *outbuffer) const
00029     {
00030       int offset = 0;
00031       uint32_t length_target_name = strlen(this->target_name);
00032       varToArr(outbuffer + offset, length_target_name);
00033       offset += 4;
00034       memcpy(outbuffer + offset, this->target_name, length_target_name);
00035       offset += length_target_name;
00036       offset += this->pose_stamped.serialize(outbuffer + offset);
00037       return offset;
00038     }
00039 
00040     virtual int deserialize(unsigned char *inbuffer)
00041     {
00042       int offset = 0;
00043       uint32_t length_target_name;
00044       arrToVar(length_target_name, (inbuffer + offset));
00045       offset += 4;
00046       for(unsigned int k= offset; k< offset+length_target_name; ++k){
00047           inbuffer[k-1]=inbuffer[k];
00048       }
00049       inbuffer[offset+length_target_name-1]=0;
00050       this->target_name = (char *)(inbuffer + offset-1);
00051       offset += length_target_name;
00052       offset += this->pose_stamped.deserialize(inbuffer + offset);
00053      return offset;
00054     }
00055 
00056     virtual const char * getType(){ return SETTRANSFORMABLEMARKERPOSE; };
00057     virtual const char * getMD5(){ return "e19607b29b4528e87feff290fe261191"; };
00058 
00059   };
00060 
00061   class SetTransformableMarkerPoseResponse : public ros::Msg
00062   {
00063     public:
00064 
00065     SetTransformableMarkerPoseResponse()
00066     {
00067     }
00068 
00069     virtual int serialize(unsigned char *outbuffer) const
00070     {
00071       int offset = 0;
00072       return offset;
00073     }
00074 
00075     virtual int deserialize(unsigned char *inbuffer)
00076     {
00077       int offset = 0;
00078      return offset;
00079     }
00080 
00081     virtual const char * getType(){ return SETTRANSFORMABLEMARKERPOSE; };
00082     virtual const char * getMD5(){ return "d41d8cd98f00b204e9800998ecf8427e"; };
00083 
00084   };
00085 
00086   class SetTransformableMarkerPose {
00087     public:
00088     typedef SetTransformableMarkerPoseRequest Request;
00089     typedef SetTransformableMarkerPoseResponse Response;
00090   };
00091 
00092 }
00093 #endif