added 1 custom message
Fork of ros_lib_kinetic by
Diff: std_srvs/SetBool.h
- Revision:
- 0:9e9b7db60fd5
diff -r 000000000000 -r 9e9b7db60fd5 std_srvs/SetBool.h --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/std_srvs/SetBool.h Sat Dec 31 00:48:34 2016 +0000 @@ -0,0 +1,123 @@ +#ifndef _ROS_SERVICE_SetBool_h +#define _ROS_SERVICE_SetBool_h +#include <stdint.h> +#include <string.h> +#include <stdlib.h> +#include "ros/msg.h" + +namespace std_srvs +{ + +static const char SETBOOL[] = "std_srvs/SetBool"; + + class SetBoolRequest : public ros::Msg + { + public: + typedef bool _data_type; + _data_type data; + + SetBoolRequest(): + data(0) + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_data; + u_data.real = this->data; + *(outbuffer + offset + 0) = (u_data.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->data); + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_data; + u_data.base = 0; + u_data.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->data = u_data.real; + offset += sizeof(this->data); + return offset; + } + + const char * getType(){ return SETBOOL; }; + const char * getMD5(){ return "8b94c1b53db61fb6aed406028ad6332a"; }; + + }; + + class SetBoolResponse : public ros::Msg + { + public: + typedef bool _success_type; + _success_type success; + typedef const char* _message_type; + _message_type message; + + SetBoolResponse(): + success(0), + message("") + { + } + + virtual int serialize(unsigned char *outbuffer) const + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.real = this->success; + *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; + offset += sizeof(this->success); + uint32_t length_message = strlen(this->message); + varToArr(outbuffer + offset, length_message); + offset += 4; + memcpy(outbuffer + offset, this->message, length_message); + offset += length_message; + return offset; + } + + virtual int deserialize(unsigned char *inbuffer) + { + int offset = 0; + union { + bool real; + uint8_t base; + } u_success; + u_success.base = 0; + u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); + this->success = u_success.real; + offset += sizeof(this->success); + uint32_t length_message; + arrToVar(length_message, (inbuffer + offset)); + offset += 4; + for(unsigned int k= offset; k< offset+length_message; ++k){ + inbuffer[k-1]=inbuffer[k]; + } + inbuffer[offset+length_message-1]=0; + this->message = (char *)(inbuffer + offset-1); + offset += length_message; + return offset; + } + + const char * getType(){ return SETBOOL; }; + const char * getMD5(){ return "937c9679a518e3a18d831e57125ea522"; }; + + }; + + class SetBool { + public: + typedef SetBoolRequest Request; + typedef SetBoolResponse Response; + }; + +} +#endif