From 1b5064fb051017414dcd068a72df259710bd0472 Mon Sep 17 00:00:00 2001 From: "Sean Yen [MSFT]" Date: Tue, 19 Mar 2019 09:54:04 -0700 Subject: [PATCH] Use std random generators for better portability (#1356) run_tests failed on Windows due to random(), which is replaced by C++ alternatives from std library. --- src/test/send_images.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/test/send_images.cpp b/src/test/send_images.cpp index f89d2ab05f..1581387534 100644 --- a/src/test/send_images.cpp +++ b/src/test/send_images.cpp @@ -28,6 +28,7 @@ */ #include +#include #include "stdlib.h" #include "ros/ros.h" #include "sensor_msgs/Image.h" @@ -66,6 +67,7 @@ int main( int argc, char **argv ) msg.step = width * 3; int count = 0; + std::default_random_engine random_generator; while( ros::ok() ) { for( int x = 0; x < width; x++ ) @@ -73,7 +75,8 @@ int main( int argc, char **argv ) for( int y = 0; y < height; y++ ) { int index = (x + y * width) * 3; - long int rand = random(); + std::uniform_int_distribution uniform(0, RAND_MAX); + auto rand = uniform(random_generator); msg.data[ index ] = rand & 0xff; index++; msg.data[ index ] = (rand >> 8) & 0xff;