Just changed OUTPUT_SIZE and INPUT_SIZE in ros/node_handle.h
Dependents: WRS2020_mecanum_node
TestRequestGoal.h
00001 #ifndef _ROS_actionlib_TestRequestGoal_h 00002 #define _ROS_actionlib_TestRequestGoal_h 00003 00004 #include <stdint.h> 00005 #include <string.h> 00006 #include <stdlib.h> 00007 #include "ros/msg.h" 00008 #include "ros/duration.h" 00009 00010 namespace actionlib 00011 { 00012 00013 class TestRequestGoal : public ros::Msg 00014 { 00015 public: 00016 typedef int32_t _terminate_status_type; 00017 _terminate_status_type terminate_status; 00018 typedef bool _ignore_cancel_type; 00019 _ignore_cancel_type ignore_cancel; 00020 typedef const char* _result_text_type; 00021 _result_text_type result_text; 00022 typedef int32_t _the_result_type; 00023 _the_result_type the_result; 00024 typedef bool _is_simple_client_type; 00025 _is_simple_client_type is_simple_client; 00026 typedef ros::Duration _delay_accept_type; 00027 _delay_accept_type delay_accept; 00028 typedef ros::Duration _delay_terminate_type; 00029 _delay_terminate_type delay_terminate; 00030 typedef ros::Duration _pause_status_type; 00031 _pause_status_type pause_status; 00032 enum { TERMINATE_SUCCESS = 0 }; 00033 enum { TERMINATE_ABORTED = 1 }; 00034 enum { TERMINATE_REJECTED = 2 }; 00035 enum { TERMINATE_LOSE = 3 }; 00036 enum { TERMINATE_DROP = 4 }; 00037 enum { TERMINATE_EXCEPTION = 5 }; 00038 00039 TestRequestGoal(): 00040 terminate_status(0), 00041 ignore_cancel(0), 00042 result_text(""), 00043 the_result(0), 00044 is_simple_client(0), 00045 delay_accept(), 00046 delay_terminate(), 00047 pause_status() 00048 { 00049 } 00050 00051 virtual int serialize(unsigned char *outbuffer) const 00052 { 00053 int offset = 0; 00054 union { 00055 int32_t real; 00056 uint32_t base; 00057 } u_terminate_status; 00058 u_terminate_status.real = this->terminate_status; 00059 *(outbuffer + offset + 0) = (u_terminate_status.base >> (8 * 0)) & 0xFF; 00060 *(outbuffer + offset + 1) = (u_terminate_status.base >> (8 * 1)) & 0xFF; 00061 *(outbuffer + offset + 2) = (u_terminate_status.base >> (8 * 2)) & 0xFF; 00062 *(outbuffer + offset + 3) = (u_terminate_status.base >> (8 * 3)) & 0xFF; 00063 offset += sizeof(this->terminate_status); 00064 union { 00065 bool real; 00066 uint8_t base; 00067 } u_ignore_cancel; 00068 u_ignore_cancel.real = this->ignore_cancel; 00069 *(outbuffer + offset + 0) = (u_ignore_cancel.base >> (8 * 0)) & 0xFF; 00070 offset += sizeof(this->ignore_cancel); 00071 uint32_t length_result_text = strlen(this->result_text); 00072 varToArr(outbuffer + offset, length_result_text); 00073 offset += 4; 00074 memcpy(outbuffer + offset, this->result_text, length_result_text); 00075 offset += length_result_text; 00076 union { 00077 int32_t real; 00078 uint32_t base; 00079 } u_the_result; 00080 u_the_result.real = this->the_result; 00081 *(outbuffer + offset + 0) = (u_the_result.base >> (8 * 0)) & 0xFF; 00082 *(outbuffer + offset + 1) = (u_the_result.base >> (8 * 1)) & 0xFF; 00083 *(outbuffer + offset + 2) = (u_the_result.base >> (8 * 2)) & 0xFF; 00084 *(outbuffer + offset + 3) = (u_the_result.base >> (8 * 3)) & 0xFF; 00085 offset += sizeof(this->the_result); 00086 union { 00087 bool real; 00088 uint8_t base; 00089 } u_is_simple_client; 00090 u_is_simple_client.real = this->is_simple_client; 00091 *(outbuffer + offset + 0) = (u_is_simple_client.base >> (8 * 0)) & 0xFF; 00092 offset += sizeof(this->is_simple_client); 00093 *(outbuffer + offset + 0) = (this->delay_accept.sec >> (8 * 0)) & 0xFF; 00094 *(outbuffer + offset + 1) = (this->delay_accept.sec >> (8 * 1)) & 0xFF; 00095 *(outbuffer + offset + 2) = (this->delay_accept.sec >> (8 * 2)) & 0xFF; 00096 *(outbuffer + offset + 3) = (this->delay_accept.sec >> (8 * 3)) & 0xFF; 00097 offset += sizeof(this->delay_accept.sec); 00098 *(outbuffer + offset + 0) = (this->delay_accept.nsec >> (8 * 0)) & 0xFF; 00099 *(outbuffer + offset + 1) = (this->delay_accept.nsec >> (8 * 1)) & 0xFF; 00100 *(outbuffer + offset + 2) = (this->delay_accept.nsec >> (8 * 2)) & 0xFF; 00101 *(outbuffer + offset + 3) = (this->delay_accept.nsec >> (8 * 3)) & 0xFF; 00102 offset += sizeof(this->delay_accept.nsec); 00103 *(outbuffer + offset + 0) = (this->delay_terminate.sec >> (8 * 0)) & 0xFF; 00104 *(outbuffer + offset + 1) = (this->delay_terminate.sec >> (8 * 1)) & 0xFF; 00105 *(outbuffer + offset + 2) = (this->delay_terminate.sec >> (8 * 2)) & 0xFF; 00106 *(outbuffer + offset + 3) = (this->delay_terminate.sec >> (8 * 3)) & 0xFF; 00107 offset += sizeof(this->delay_terminate.sec); 00108 *(outbuffer + offset + 0) = (this->delay_terminate.nsec >> (8 * 0)) & 0xFF; 00109 *(outbuffer + offset + 1) = (this->delay_terminate.nsec >> (8 * 1)) & 0xFF; 00110 *(outbuffer + offset + 2) = (this->delay_terminate.nsec >> (8 * 2)) & 0xFF; 00111 *(outbuffer + offset + 3) = (this->delay_terminate.nsec >> (8 * 3)) & 0xFF; 00112 offset += sizeof(this->delay_terminate.nsec); 00113 *(outbuffer + offset + 0) = (this->pause_status.sec >> (8 * 0)) & 0xFF; 00114 *(outbuffer + offset + 1) = (this->pause_status.sec >> (8 * 1)) & 0xFF; 00115 *(outbuffer + offset + 2) = (this->pause_status.sec >> (8 * 2)) & 0xFF; 00116 *(outbuffer + offset + 3) = (this->pause_status.sec >> (8 * 3)) & 0xFF; 00117 offset += sizeof(this->pause_status.sec); 00118 *(outbuffer + offset + 0) = (this->pause_status.nsec >> (8 * 0)) & 0xFF; 00119 *(outbuffer + offset + 1) = (this->pause_status.nsec >> (8 * 1)) & 0xFF; 00120 *(outbuffer + offset + 2) = (this->pause_status.nsec >> (8 * 2)) & 0xFF; 00121 *(outbuffer + offset + 3) = (this->pause_status.nsec >> (8 * 3)) & 0xFF; 00122 offset += sizeof(this->pause_status.nsec); 00123 return offset; 00124 } 00125 00126 virtual int deserialize(unsigned char *inbuffer) 00127 { 00128 int offset = 0; 00129 union { 00130 int32_t real; 00131 uint32_t base; 00132 } u_terminate_status; 00133 u_terminate_status.base = 0; 00134 u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00135 u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00136 u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00137 u_terminate_status.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00138 this->terminate_status = u_terminate_status.real; 00139 offset += sizeof(this->terminate_status); 00140 union { 00141 bool real; 00142 uint8_t base; 00143 } u_ignore_cancel; 00144 u_ignore_cancel.base = 0; 00145 u_ignore_cancel.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00146 this->ignore_cancel = u_ignore_cancel.real; 00147 offset += sizeof(this->ignore_cancel); 00148 uint32_t length_result_text; 00149 arrToVar(length_result_text, (inbuffer + offset)); 00150 offset += 4; 00151 for(unsigned int k= offset; k< offset+length_result_text; ++k){ 00152 inbuffer[k-1]=inbuffer[k]; 00153 } 00154 inbuffer[offset+length_result_text-1]=0; 00155 this->result_text = (char *)(inbuffer + offset-1); 00156 offset += length_result_text; 00157 union { 00158 int32_t real; 00159 uint32_t base; 00160 } u_the_result; 00161 u_the_result.base = 0; 00162 u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 0))) << (8 * 0); 00163 u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00164 u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00165 u_the_result.base |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00166 this->the_result = u_the_result.real; 00167 offset += sizeof(this->the_result); 00168 union { 00169 bool real; 00170 uint8_t base; 00171 } u_is_simple_client; 00172 u_is_simple_client.base = 0; 00173 u_is_simple_client.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); 00174 this->is_simple_client = u_is_simple_client.real; 00175 offset += sizeof(this->is_simple_client); 00176 this->delay_accept.sec = ((uint32_t) (*(inbuffer + offset))); 00177 this->delay_accept.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00178 this->delay_accept.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00179 this->delay_accept.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00180 offset += sizeof(this->delay_accept.sec); 00181 this->delay_accept.nsec = ((uint32_t) (*(inbuffer + offset))); 00182 this->delay_accept.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00183 this->delay_accept.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00184 this->delay_accept.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00185 offset += sizeof(this->delay_accept.nsec); 00186 this->delay_terminate.sec = ((uint32_t) (*(inbuffer + offset))); 00187 this->delay_terminate.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00188 this->delay_terminate.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00189 this->delay_terminate.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00190 offset += sizeof(this->delay_terminate.sec); 00191 this->delay_terminate.nsec = ((uint32_t) (*(inbuffer + offset))); 00192 this->delay_terminate.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00193 this->delay_terminate.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00194 this->delay_terminate.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00195 offset += sizeof(this->delay_terminate.nsec); 00196 this->pause_status.sec = ((uint32_t) (*(inbuffer + offset))); 00197 this->pause_status.sec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00198 this->pause_status.sec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00199 this->pause_status.sec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00200 offset += sizeof(this->pause_status.sec); 00201 this->pause_status.nsec = ((uint32_t) (*(inbuffer + offset))); 00202 this->pause_status.nsec |= ((uint32_t) (*(inbuffer + offset + 1))) << (8 * 1); 00203 this->pause_status.nsec |= ((uint32_t) (*(inbuffer + offset + 2))) << (8 * 2); 00204 this->pause_status.nsec |= ((uint32_t) (*(inbuffer + offset + 3))) << (8 * 3); 00205 offset += sizeof(this->pause_status.nsec); 00206 return offset; 00207 } 00208 00209 const char * getType(){ return "actionlib/TestRequestGoal"; }; 00210 const char * getMD5(){ return "db5d00ba98302d6c6dd3737e9a03ceea"; }; 00211 00212 }; 00213 00214 } 00215 #endif
Generated on Tue Jul 12 2022 18:49:20 by 1.7.2