From d58352cdc45ee40b4992bdd7d60342aaba360bd5 Mon Sep 17 00:00:00 2001 From: Compiler bot <noreply@clubelek.fr> Date: Wed, 19 Jul 2023 19:31:37 +0000 Subject: [PATCH] autogen lib 2023-07-19T21:28:52+02:00 --- nav_msgs/GetPlan.h | 2 +- pince_srvs/SetPincePosition.h | 28 ++++++++++++++-------------- 2 files changed, 15 insertions(+), 15 deletions(-) diff --git a/nav_msgs/GetPlan.h b/nav_msgs/GetPlan.h index 7a15207..def1793 100644 --- a/nav_msgs/GetPlan.h +++ b/nav_msgs/GetPlan.h @@ -4,8 +4,8 @@ #include <string.h> #include <stdlib.h> #include "ros/msg.h" -#include "geometry_msgs/PoseStamped.h" #include "nav_msgs/Path.h" +#include "geometry_msgs/PoseStamped.h" namespace nav_msgs { diff --git a/pince_srvs/SetPincePosition.h b/pince_srvs/SetPincePosition.h index c572fcc..f551a75 100644 --- a/pince_srvs/SetPincePosition.h +++ b/pince_srvs/SetPincePosition.h @@ -65,12 +65,12 @@ static const char SETPINCEPOSITION[] = "pince_srvs/SetPincePosition"; public: typedef bool _success_type; _success_type success; - typedef const char* _messagea_type; - _messagea_type messagea; + typedef const char* _message_type; + _message_type message; SetPincePositionResponse(): success(0), - messagea("") + message("") { } @@ -84,11 +84,11 @@ static const char SETPINCEPOSITION[] = "pince_srvs/SetPincePosition"; u_success.real = this->success; *(outbuffer + offset + 0) = (u_success.base >> (8 * 0)) & 0xFF; offset += sizeof(this->success); - uint32_t length_messagea = strlen(this->messagea); - varToArr(outbuffer + offset, length_messagea); + uint32_t length_message = strlen(this->message); + varToArr(outbuffer + offset, length_message); offset += 4; - memcpy(outbuffer + offset, this->messagea, length_messagea); - offset += length_messagea; + memcpy(outbuffer + offset, this->message, length_message); + offset += length_message; return offset; } @@ -103,20 +103,20 @@ static const char SETPINCEPOSITION[] = "pince_srvs/SetPincePosition"; u_success.base |= ((uint8_t) (*(inbuffer + offset + 0))) << (8 * 0); this->success = u_success.real; offset += sizeof(this->success); - uint32_t length_messagea; - arrToVar(length_messagea, (inbuffer + offset)); + uint32_t length_message; + arrToVar(length_message, (inbuffer + offset)); offset += 4; - for(unsigned int k= offset; k< offset+length_messagea; ++k){ + for(unsigned int k= offset; k< offset+length_message; ++k){ inbuffer[k-1]=inbuffer[k]; } - inbuffer[offset+length_messagea-1]=0; - this->messagea = (char *)(inbuffer + offset-1); - offset += length_messagea; + inbuffer[offset+length_message-1]=0; + this->message = (char *)(inbuffer + offset-1); + offset += length_message; return offset; } virtual const char * getType() override { return SETPINCEPOSITION; }; - virtual const char * getMD5() override { return "5432453fd335a7d26146e47c175bcb1f"; }; + virtual const char * getMD5() override { return "937c9679a518e3a18d831e57125ea522"; }; }; -- GitLab