Navigation Menu

Skip to content

Commit

Permalink
Use std random generators for better portability (#1356)
Browse files Browse the repository at this point in the history
run_tests failed on Windows due to random(), which is replaced by C++ alternatives from std library.
  • Loading branch information
seanyen authored and rhaschke committed Mar 19, 2019
1 parent 81e1b1f commit 1b5064f
Showing 1 changed file with 4 additions and 1 deletion.
5 changes: 4 additions & 1 deletion src/test/send_images.cpp
Expand Up @@ -28,6 +28,7 @@
*/

#include <string>
#include <random>
#include "stdlib.h"
#include "ros/ros.h"
#include "sensor_msgs/Image.h"
Expand Down Expand Up @@ -66,14 +67,16 @@ 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++ )
{
for( int y = 0; y < height; y++ )
{
int index = (x + y * width) * 3;
long int rand = random();
std::uniform_int_distribution<int> uniform(0, RAND_MAX);
auto rand = uniform(random_generator);
msg.data[ index ] = rand & 0xff;
index++;
msg.data[ index ] = (rand >> 8) & 0xff;
Expand Down

0 comments on commit 1b5064f

Please sign in to comment.