From 85d643b62cea8f5c7e96a5f3ce168d8208fee897 Mon Sep 17 00:00:00 2001
From: Compiler bot <noreply@clubelek.fr>
Date: Wed, 19 Jul 2023 19:32:06 +0000
Subject: [PATCH] autogen lib 2023-07-19T21:28:52+02:00

---
 nav_msgs/SetMap.h | 2 +-
 ros/msg.h         | 6 +++---
 2 files changed, 4 insertions(+), 4 deletions(-)

diff --git a/nav_msgs/SetMap.h b/nav_msgs/SetMap.h
index f829f8c..db7f048 100644
--- a/nav_msgs/SetMap.h
+++ b/nav_msgs/SetMap.h
@@ -4,8 +4,8 @@
 #include <string.h>
 #include <stdlib.h>
 #include "ros/msg.h"
-#include "geometry_msgs/PoseWithCovarianceStamped.h"
 #include "nav_msgs/OccupancyGrid.h"
+#include "geometry_msgs/PoseWithCovarianceStamped.h"
 
 namespace nav_msgs
 {
diff --git a/ros/msg.h b/ros/msg.h
index b9f6201..9e349c3 100644
--- a/ros/msg.h
+++ b/ros/msg.h
@@ -37,7 +37,7 @@
 
 #include <stdint.h>
 #include <stddef.h>
-#include <string.h>
+#include <cstring>
 
 namespace ros
 {
@@ -65,7 +65,7 @@ public:
   static int serializeAvrFloat64(unsigned char* outbuffer, const float f)
   {
     int32_t val;
-    memcpy(&val, &f, sizeof(val));
+    std::memcpy(&val, &f, sizeof(val));
 
     int16_t exp = ((val >> 23) & 255);
     uint32_t mantissa = val & 0x7FFFFF;
@@ -179,7 +179,7 @@ public:
     // Copy negative sign.
     val |= (static_cast<uint32_t>(*(inbuffer++)) & 0x80) << 24;
 
-    memcpy(f, &val, sizeof(val));
+    std::memcpy(f, &val, sizeof(val));
     return 8;
   }
 
-- 
GitLab