RCL - RoboCLuedo  v1.0
Francesco Ganci - S4143910 - Experimental Robotics Lab - Assignment 1
cluedo_random_room.cpp
Go to the documentation of this file.
1 
2 
40 #include "ros/ros.h"
41 #include "robocluedo_msgs/RandomRoom.h"
42 
43 #include <vector>
44 #include <string>
45 #include <random>
46 #include <fstream>
47 
48 #define PATH_PARAMETER_SERVER_WHERE "cluedo_path_where"
49 #define SERVICE_RANDOM_ROOM "/random_room"
50 #define OUTLOG std::cout << "[cluedo_random_room] "
51 #define LOGSQUARE( str ) "[" << str << "] "
52 
53 
54 
56 std::vector<std::string> rooms;
57 
59 std::uniform_int_distribution<std::mt19937::result_type> randgen;
60 
62 std::mt19937 rng;
63 
64 
65 
66 
75 bool ImportNamesOfRooms( const std::string& path )
76 {
77  // open the file
78  OUTLOG << "reading from fiile " << LOGSQUARE( path ) << std::endl;
79  std::ifstream filestream( path );
80  if( !filestream.is_open( ) )
81  {
82  OUTLOG << "ERROR: no existing file!" << std::endl;
83  return false;
84  }
85 
86  // read the file
87  rooms = std::vector<std::string>( );
88  std::string temp = "";
89  int line = 1;
90  while( getline( filestream, temp ) )
91  {
92  OUTLOG << "line" << LOGSQUARE( line ) << "READ " << LOGSQUARE( temp ) << std::endl;
93  ++line;
94  rooms.push_back( temp );
95  }
96 
97  // close the file
98  OUTLOG << "closing file ..." << std::endl;
99  filestream.close( );
100 
101  return true;
102 }
103 
104 
105 
106 
113 std::string Choose( )
114 {
115  int generated_random_number = randgen( rng );
116  ROS_INFO( "generated: %d", generated_random_number );
117 
118  return rooms[ generated_random_number ];
119 }
120 
121 
122 
123 
138 bool ChooseRoomRandom( robocluedo_msgs::RandomRoom::Request& empty, robocluedo_msgs::RandomRoom::Response& room )
139 {
140  room.room = Choose( );
141  return true;
142 }
143 
144 
145 
146 
153 int main( int argc, char* argv[] )
154 {
155  ros::init( argc, argv, "cluedo_random_room" );
156  ros::NodeHandle nh;
157 
158  // init the list of rooms
159  if( !ros::param::has( PATH_PARAMETER_SERVER_WHERE ) )
160  {
161  // ERRORE il param non esiste nel server
162  return 0;
163  }
164  std::string path;
165  ros::param::get( PATH_PARAMETER_SERVER_WHERE, path );
166  if( !ImportNamesOfRooms( path ) )
167  {
168  // ERRORE il path non esiste
169  return 0;
170  }
171  int nRooms = rooms.size( );
172 
173  // setup the random number generator
174  std::random_device dev;
175  // seed?
176  rng = std::mt19937(dev());
177  randgen = std::uniform_int_distribution<std::mt19937::result_type>( 0, nRooms-1 );
178 
179  // expose the service
180  OUTLOG << "Advertising service " << LOGSQUARE( SERVICE_RANDOM_ROOM ) << "..." << std::endl;
181  ros::ServiceServer srv = nh.advertiseService( SERVICE_RANDOM_ROOM, ChooseRoomRandom );
182  OUTLOG << "Advertising service " << LOGSQUARE( SERVICE_RANDOM_ROOM ) << "... OK" << std::endl;
183 
184  // spin and wait
185  OUTLOG << "ready!" << std::endl;
186  ros::spin();
187 
188  return 0;
189 }
Choose
std::string Choose()
get randomly the name of one room from the list rooms .
Definition: cluedo_random_room.cpp:113
ChooseRoomRandom
bool ChooseRoomRandom(robocluedo_msgs::RandomRoom::Request &empty, robocluedo_msgs::RandomRoom::Response &room)
implementation of service SERVICE_RANDOM_ROOM
Definition: cluedo_random_room.cpp:138
PATH_PARAMETER_SERVER_WHERE
#define PATH_PARAMETER_SERVER_WHERE
Definition: cluedo_random_room.cpp:48
ImportNamesOfRooms
bool ImportNamesOfRooms(const std::string &path)
import names of the rooms from file
Definition: cluedo_random_room.cpp:75
SERVICE_RANDOM_ROOM
#define SERVICE_RANDOM_ROOM
Definition: cluedo_random_room.cpp:49
LOGSQUARE
#define LOGSQUARE(str)
Definition: cluedo_random_room.cpp:51
rooms
std::vector< std::string > rooms
the set of rooms
Definition: cluedo_random_room.cpp:56
OUTLOG
#define OUTLOG
Definition: cluedo_random_room.cpp:50
main
int main(int argc, char *argv[])
ROS node main - cluedo_random_room.
Definition: cluedo_random_room.cpp:153