ApplyBodyWrench.h
Go to the documentation of this file.
00001 #ifndef _ROS_SERVICE_ApplyBodyWrench_h
00002 #define _ROS_SERVICE_ApplyBodyWrench_h
00003 #include <stdint.h>
00004 #include <string.h>
00005 #include <stdlib.h>
00006 #include "ros/msg.h"
00007 #include "ros/duration.h"
00008 #include "geometry_msgs/Wrench.h"
00009 #include "ros/time.h"
00010 #include "geometry_msgs/Point.h"
00011 
00012 namespace gazebo_msgs
00013 {
00014 
00015 static const char APPLYBODYWRENCH[] = "gazebo_msgs/ApplyBodyWrench";
00016 
00017   class ApplyBodyWrenchRequest : public ros::Msg
00018   {
00019     public:
00020       const char* body_name;
00021       const char* reference_frame;
00022       geometry_msgs::Point reference_point;
00023       geometry_msgs::Wrench wrench;
00024       ros::Time start_time;
00025       ros::Duration duration;
00026 
00027     virtual int serialize(unsigned char *outbuffer) const
00028     {
00029       int offset = 0;
00030       uint32_t length_body_name = strlen(this->body_name);
00031       memcpy(outbuffer + offset, &length_body_name, sizeof(uint32_t));
00032       offset += 4;
00033       memcpy(outbuffer + offset, this->body_name, length_body_name);
00034       offset += length_body_name;
00035       uint32_t length_reference_frame = strlen(this->reference_frame);
00036       memcpy(outbuffer + offset, &length_reference_frame, sizeof(uint32_t));
00037       offset += 4;
00038       memcpy(outbuffer + offset, this->reference_frame, length_reference_frame);
00039       offset += length_reference_frame;
00040       offset += this->reference_point.serialize(outbuffer + offset);
00041       offset += this->wrench.serialize(outbuffer + offset);
00042       *(outbuffer + offset + 0) = (this->start_time.sec >> (8 * 0)) & 0xFF;
00043       *(outbuffer + offset + 1) = (this->start_time.sec >> (8 * 1)) & 0xFF;
00044       *(outbuffer + offset + 2) = (this->start_time.sec >> (8 * 2)) & 0xFF;
00045       *(outbuffer + offset + 3) = (this->start_time.sec >> (8 * 3)) & 0xFF;
00046       offset += sizeof(this->start_time.sec);
00047       *(outbuffer + offset + 0) = (this->start_time.nsec >> (8 * 0)) & 0xFF;
00048       *(outbuffer + offset + 1) = (this->start_time.nsec >> (8 * 1)) & 0xFF;
00049       *(outbuffer + offset + 2) = (this->start_time.nsec >> (8 * 2)) & 0xFF;
00050       *(outbuffer + offset + 3) = (this->start_time.nsec >> (8 * 3)) & 0xFF;
00051       offset += sizeof(this->start_time.nsec);
00052       *(outbuffer + offset + 0) = (this->duration.sec >> (8 * 0)) & 0xFF;
00053       *(outbuffer + offset + 1) = (this->duration.sec >> (8 * 1)) & 0xFF;
00054       *(outbuffer + offset + 2) = (this->duration.sec >> (8 * 2)) & 0xFF;
00055       *(outbuffer + offset + 3) = (this->duration.sec >> (8 * 3)) & 0xFF;
00056       offset += sizeof(this->duration.sec);
00057       *(outbuffer + offset + 0) = (this->duration.nsec >> (8 * 0)) & 0xFF;
00058       *(outbuffer + offset + 1) = (this->duration.nsec >> (8 * 1)) & 0xFF;
00059       *(outbuffer + offset + 2) = (this->duration.nsec >> (8 * 2)) & 0xFF;
00060       *(outbuffer + offset + 3) = (this->duration.nsec >> (8 * 3)) & 0xFF;
00061       offset += sizeof(this->duration.nsec);
00062       return offset;
00063     }
00064 
00065     virtual int deserialize(unsigned char *inbuffer)
00066     {
00067       int offset = 0;
00068       uint32_t length_body_name;
00069       memcpy(&length_body_name, (inbuffer + offset), sizeof(uint32_t));
00070       offset += 4;
00071       for(unsigned int k= offset; k< offset+length_body_name; ++k){
00072           inbuffer[k-1]=inbuffer[k];
00073       }
00074       inbuffer[offset+length_body_name-1]=0;
00075       this->body_name = (char *)(inbuffer + offset-1);
00076       offset += length_body_name;
00077       uint32_t length_reference_frame;
00078       memcpy(&length_reference_frame, (inbuffer + offset), sizeof(uint32_t));
00079       offset += 4;
00080       for(unsigned int k= offset; k< offset+length_reference_frame; ++k){
00081           inbuffer[k-1]=inbuffer[k];
00082       }
00083       inbuffer[offset+length_reference_frame-1]=0;
00084       this->reference_frame = (char *)(inbuffer + offset-1);
00085       offset += length_reference_frame;
00086       offset += this->reference_point.deserialize(inbuffer + offset);
00087       offset += this->wrench.deserialize(inbuffer + offset);
00088       this->start_time.sec =  ((uint32_t) (*(inbuffer + offset)));
00089       this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00090       this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00091       this->start_time.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00092       offset += sizeof(this->start_time.sec);
00093       this->start_time.nsec =  ((uint32_t) (*(inbuffer + offset)));
00094       this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00095       this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00096       this->start_time.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00097       offset += sizeof(this->start_time.nsec);
00098       this->duration.sec =  ((uint32_t) (*(inbuffer + offset)));
00099       this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00100       this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00101       this->duration.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00102       offset += sizeof(this->duration.sec);
00103       this->duration.nsec =  ((uint32_t) (*(inbuffer + offset)));
00104       this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1);
00105       this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2);
00106       this->duration.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3);
00107       offset += sizeof(this->duration.nsec);
00108      return offset;
00109     }
00110 
00111     const char * getType(){ return APPLYBODYWRENCH; };
00112     const char * getMD5(){ return "e37e6adf97eba5095baa77dffb71e5bd"; };
00113 
00114   };
00115 
00116   class ApplyBodyWrenchResponse : public ros::Msg
00117   {
00118     public:
00119       bool success;
00120       const char* status_message;
00121 
00122     virtual int serialize(unsigned char *outbuffer) const
00123     {
00124       int offset = 0;
00125       union {
00126         bool real;
00127         uint8_t base;
00128       } u_success;
00129       u_success.real = this->success;
00130       *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF;
00131       offset += sizeof(this->success);
00132       uint32_t length_status_message = strlen(this->status_message);
00133       memcpy(outbuffer + offset, &length_status_message, sizeof(uint32_t));
00134       offset += 4;
00135       memcpy(outbuffer + offset, this->status_message, length_status_message);
00136       offset += length_status_message;
00137       return offset;
00138     }
00139 
00140     virtual int deserialize(unsigned char *inbuffer)
00141     {
00142       int offset = 0;
00143       union {
00144         bool real;
00145         uint8_t base;
00146       } u_success;
00147       u_success.base = 0;
00148       u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0);
00149       this->success = u_success.real;
00150       offset += sizeof(this->success);
00151       uint32_t length_status_message;
00152       memcpy(&length_status_message, (inbuffer + offset), sizeof(uint32_t));
00153       offset += 4;
00154       for(unsigned int k= offset; k< offset+length_status_message; ++k){
00155           inbuffer[k-1]=inbuffer[k];
00156       }
00157       inbuffer[offset+length_status_message-1]=0;
00158       this->status_message = (char *)(inbuffer + offset-1);
00159       offset += length_status_message;
00160      return offset;
00161     }
00162 
00163     const char * getType(){ return APPLYBODYWRENCH; };
00164     const char * getMD5(){ return "2ec6f3eff0161f4257b808b12bc830c2"; };
00165 
00166   };
00167 
00168   class ApplyBodyWrench {
00169     public:
00170     typedef ApplyBodyWrenchRequest Request;
00171     typedef ApplyBodyWrenchResponse Response;
00172   };
00173 
00174 }
00175 #endif


ric_mc
Author(s): RoboTiCan
autogenerated on Fri May 20 2016 03:48:54