Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
AddDiagnostics.h
00001 #ifndef _ROS_SERVICE_AddDiagnostics_h 00002 #define _ROS_SERVICE_AddDiagnostics_h 00003 #include <stdint.h> 00004 #include <string.h> 00005 #include <stdlib.h> 00006 #include "ros/msg.h" 00007 00008 namespace diagnostic_msgs 00009 { 00010 00011 static const char ADDDIAGNOSTICS[] = "diagnostic_msgs/AddDiagnostics"; 00012 00013 class AddDiagnosticsRequest : public ros::Msg 00014 { 00015 public: 00016 typedef const char* _load_namespace_type; 00017 _load_namespace_type load_namespace; 00018 00019 AddDiagnosticsRequest(): 00020 load_namespace("") 00021 { 00022 } 00023 00024 virtual int serialize(unsigned char *outbuffer) const 00025 { 00026 int offset = 0; 00027 uint32_t length_load_namespace = strlen(this->load_namespace); 00028 varToArr(outbuffer + offset, length_load_namespace); 00029 offset += 4; 00030 memcpy(outbuffer + offset, this->load_namespace, length_load_namespace); 00031 offset += length_load_namespace; 00032 return offset; 00033 } 00034 00035 virtual int deserialize(unsigned char *inbuffer) 00036 { 00037 int offset = 0; 00038 uint32_t length_load_namespace; 00039 arrToVar(length_load_namespace, (inbuffer + offset)); 00040 offset += 4; 00041 for(unsigned int k= offset; k< offset+length_load_namespace; ++k){ 00042 inbuffer[k-1]=inbuffer[k]; 00043 } 00044 inbuffer[offset+length_load_namespace-1]=0; 00045 this->load_namespace = (char *)(inbuffer + offset-1); 00046 offset += length_load_namespace; 00047 return offset; 00048 } 00049 00050 const char * getType(){ return ADDDIAGNOSTICS; }; 00051 const char * getMD5(){ return "c26cf6e164288fbc6050d74f838bcdf0"; }; 00052 00053 }; 00054 00055 class AddDiagnosticsResponse : public ros::Msg 00056 { 00057 public: 00058 typedef bool _success_type; 00059 _success_type success; 00060 typedef const char* _message_type; 00061 _message_type message; 00062 00063 AddDiagnosticsResponse(): 00064 success(0), 00065 message("") 00066 { 00067 } 00068 00069 virtual int serialize(unsigned char *outbuffer) const 00070 { 00071 int offset = 0; 00072 union { 00073 bool real; 00074 uint8_t base; 00075 } u_success; 00076 u_success.real = this->success; 00077 *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; 00078 offset += sizeof(this->success); 00079 uint32_t length_message = strlen(this->message); 00080 varToArr(outbuffer + offset, length_message); 00081 offset += 4; 00082 memcpy(outbuffer + offset, this->message, length_message); 00083 offset += length_message; 00084 return offset; 00085 } 00086 00087 virtual int deserialize(unsigned char *inbuffer) 00088 { 00089 int offset = 0; 00090 union { 00091 bool real; 00092 uint8_t base; 00093 } u_success; 00094 u_success.base = 0; 00095 u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00096 this->success = u_success.real; 00097 offset += sizeof(this->success); 00098 uint32_t length_message; 00099 arrToVar(length_message, (inbuffer + offset)); 00100 offset += 4; 00101 for(unsigned int k= offset; k< offset+length_message; ++k){ 00102 inbuffer[k-1]=inbuffer[k]; 00103 } 00104 inbuffer[offset+length_message-1]=0; 00105 this->message = (char *)(inbuffer + offset-1); 00106 offset += length_message; 00107 return offset; 00108 } 00109 00110 const char * getType(){ return ADDDIAGNOSTICS; }; 00111 const char * getMD5(){ return "937c9679a518e3a18d831e57125ea522"; }; 00112 00113 }; 00114 00115 class AddDiagnostics { 00116 public: 00117 typedef AddDiagnosticsRequest Request; 00118 typedef AddDiagnosticsResponse Response; 00119 }; 00120 00121 } 00122 #endif
Generated on Wed Jul 13 2022 23:30:17 by
