RCL - RoboCLuedo  v1.0
Francesco Ganci - S4143910 - Experimental Robotics Lab - Assignment 1
cluedo_oracle.cpp
Go to the documentation of this file.
1 
2 
72 #include "ros/ros.h"
73 #include "std_msgs/Empty.h"
74 #include "robocluedo_msgs/Hint.h"
75 #include "robocluedo_msgs/CheckSolution.h"
76 
77 #include <vector>
78 #include <string>
79 #include <random>
80 #include <fstream>
81 #include <algorithm>
82 
83 #define PUBLISHER_HINT "/hint"
84 #define SUBSCRIBER_HINT_SIGNAL "/hint_signal"
85 #define SERVICE_CHECK_SOLUTION "/check_solution"
86 
87 #define PATH_PARAMETER_SERVER_WHERE "cluedo_path_where"
88 #define PATH_PARAMETER_SERVER_WHO "cluedo_path_who"
89 #define PATH_PARAMETER_SERVER_WHAT "cluedo_path_what"
90 
92 #define MAX_NUM_HINTS 2
93 
95 #define MAX_SIZE_HINT 10
96 
97 #define OUTLABEL "[cluedo_oracle] "
98 #define OUTLOG( msg ) ROS_INFO_STREAM( OUTLABEL << msg )
99 #define OUTERR( msg ) OUTLOG( "ERROR: " << msg )
100 #define LOGSQUARE( str ) "[" << str << "] "
101 
102 
103 
105 std::vector<std::string> hints_who;
106 
108 std::vector<std::string> hints_where;
109 
111 std::vector<std::string> hints_what;
112 
114 robocluedo_msgs::Hint solution_who;
115 
117 robocluedo_msgs::Hint solution_where;
118 
120 robocluedo_msgs::Hint solution_what;
121 
123 std::mt19937 rng;
124 
126 ros::Publisher* hint_channel;
127 
129 std::vector<robocluedo_msgs::Hint> mysterylist;
130 
131 
132 
134 int randomIndex( int capmax )
135 {
136  if( capmax == 0 ) return 0;
137 
138  std::uniform_int_distribution<std::mt19937::result_type> randgen( 0, capmax );
139  return randgen( rng );
140 }
141 
142 
143 
144 
157 bool importDataFrom( std::string path, std::vector<std::string>& list )
158 {
159  // open the file
160  OUTLOG( "reading from fiile " << LOGSQUARE( path ) );
161  std::ifstream filestream( path );
162  if( !filestream.is_open( ) )
163  {
164  OUTERR( "no existing file!" );
165  return false;
166  }
167 
168  // read the file
169  // rooms = std::vector<std::string>( );
170  std::string temp = "";
171  int line = 1;
172  while( getline( filestream, temp ) )
173  {
174  OUTLOG( "line" << LOGSQUARE( line ) << "READ " << LOGSQUARE( temp ) );
175  ++line;
176  list.push_back( temp );
177  }
178 
179  // close the file
180  OUTLOG( "closing file ..." );
181  filestream.close( );
182 
183  return true;
184 }
185 
186 
187 
188 
199 std::string chooseHintFrom( std::vector<std::string>& list )
200 {
201  int ridx = randomIndex( list.size()-1 );
202  std::string choice = list[ ridx ];
203 
204  return choice;
205 }
206 
207 
208 
209 
225 void hintCallback( const std_msgs::EmptyConstPtr& emptySignal )
226 {
227  // should the oracle to provide the solution?
228  if( !randomIndex( 1 ) )
229  {
230  ROS_INFO_STREAM( OUTLABEL << "hint requeste refused. " );
231  return;
232  }
233  else if( mysterylist.empty( ) )
234  {
235  ROS_INFO_STREAM( OUTLABEL << "MysteryLIst is empty. " );
236  return;
237  }
238 
239  // get the last message
240  robocluedo_msgs::Hint h = *(mysterylist.end() - 1);
241  mysterylist.pop_back( );
242 
243  // prepare the message and publish it
244  ROS_INFO_STREAM( OUTLABEL << "publishing hint (" << "ID:" << h.HintID << ", PROP:" << h.HintType << ", VALUE:" << h.HintContent << ")" );
245  hint_channel->publish( h );
246 }
247 
248 
249 
250 
264 bool checkSolutionCallback( robocluedo_msgs::CheckSolution::Request& hyp, robocluedo_msgs::CheckSolution::Response& misterySolved )
265 {
266  ROS_INFO_STREAM( OUTLABEL << "evaluating the solution WHERE" << LOGSQUARE( hyp.Where ) << " WHO " << LOGSQUARE( hyp.Who ) << " WHAT " << LOGSQUARE( hyp.What ) );
267  if( (hyp.Who != solution_who.HintContent) || (hyp.Where != solution_where.HintContent) || (hyp.What != solution_what.HintContent) )
268  {
269  ROS_INFO_STREAM( OUTLABEL << "solution wrong. " );
270  misterySolved.MysterySolved = false;
271  }
272  else
273  {
274  ROS_INFO_STREAM( OUTLABEL << "SUCCESS! Found the solution. " );
275  misterySolved.MysterySolved = true;
276  }
277 
278  return true;
279 }
280 
281 
282 
283 
314 void generateMystery( std::vector<std::string> list_who, std::vector<std::string> list_where, std::vector<std::string> list_what, int tot_hints )
315 {
316  ROS_INFO_STREAM( OUTLABEL << "case generation started " );
317 
318  // shuffle the arrays before starting
319  std::random_shuffle( list_who.begin(), list_who.end() );
320  std::random_shuffle( list_where.begin(), list_where.end() );
321  std::random_shuffle( list_what.begin(), list_what.end() );
322 
323  // generate the solution without the ID
324  solution_where.HintType = "where";
325  solution_where.HintContent = chooseHintFrom( list_where );
326 
327  solution_who.HintType = "who";
328  solution_who.HintContent = chooseHintFrom( list_who );
329 
330  solution_what.HintType = "what";
331  solution_what.HintContent = chooseHintFrom( list_what );
332 
333  ROS_INFO_STREAM( OUTLABEL << "the solution is " << "(where:" << solution_where.HintContent << ", who:" << solution_who.HintContent << ", what:" << solution_what.HintContent << ")" );
334 
335  // generate the ID of the solution
336  int solutionID = randomIndex( MAX_NUM_HINTS-1 );
337  solution_who.HintID = solutionID;
338  solution_where.HintID = solutionID;
339  solution_what.HintID = solutionID;
340 
341  ROS_INFO_STREAM( OUTLABEL << "the solution has ID:" << solutionID );
342 
343  // generate the case
344  for( int i=0; i<tot_hints; ++i )
345  {
346  if( i == solutionID )
347  {
348  mysterylist.push_back( solution_what );
349  mysterylist.push_back( solution_where );
350  mysterylist.push_back( solution_who );
351 
352  continue;
353  }
354  else
355  {
357  for( int j=0; j<MAX_SIZE_HINT; ++j )
358  {
359  robocluedo_msgs::Hint h;
360  h.HintID = i;
362  switch( randomIndex( 5 ) )
363  {
364  case 0:
365  h.HintType = "who";
366  h.HintContent = chooseHintFrom( list_who );
367  break;
368  case 1:
369  h.HintType = "where";
370  h.HintContent = chooseHintFrom( list_where );
371  break;
372  case 2:
373  h.HintType = "what";
374  h.HintContent = chooseHintFrom( list_what );
375  break;
376  default:
377  continue;
378  break;
379  }
380 
381  mysterylist.push_back( h );
382  }
383  }
384  }
385 
386  ROS_INFO_STREAM( OUTLABEL << "hints generation finished. Generated: " << mysterylist.size() << " hints" );
387 
388  // final shuffle
389  std::random_shuffle( mysterylist.begin(), mysterylist.end() );
390 }
391 
392 
393 
394 
402 int main( int argc, char* argv[] )
403 {
404  ros::init( argc, argv, "cluedo_oracle" );
405  ros::NodeHandle nh;
406 
407  // get the paths of the config files from the parameter server
408  std::string path_who = "";
409  std::string path_where = "";
410  std::string path_what = "";
411  if( !ros::param::has( PATH_PARAMETER_SERVER_WHO ) )
412  {
413  OUTERR( "unable to find the parameter " << LOGSQUARE( PATH_PARAMETER_SERVER_WHO ) );
414  return 0;
415  }
416  else ros::param::get( PATH_PARAMETER_SERVER_WHO, path_who );
417  if( !ros::param::has( PATH_PARAMETER_SERVER_WHERE ) )
418  {
419  OUTERR( "unable to find the parameter " << LOGSQUARE( PATH_PARAMETER_SERVER_WHERE ) );
420  return 0;
421  }
422  else ros::param::get( PATH_PARAMETER_SERVER_WHERE, path_where );
423  if( !ros::param::has( PATH_PARAMETER_SERVER_WHAT ) )
424  {
425  OUTERR( "unable to find the parameter " << LOGSQUARE( PATH_PARAMETER_SERVER_WHAT ) );
426  return 0;
427  }
428  else ros::param::get( PATH_PARAMETER_SERVER_WHAT, path_what );
429 
430  // load data from who
431  hints_who = std::vector<std::string>();
432  if( !importDataFrom( path_who, hints_who ) )
433  {
434  OUTERR( "unable to locate the data file " << LOGSQUARE( path_who ) );
435  return 0;
436  }
437  // from where
438  hints_where = std::vector<std::string>();
439  if( !importDataFrom( path_where, hints_where ) )
440  {
441  OUTERR( "unable to locate the data file " << LOGSQUARE( path_where ) );
442  return 0;
443  }
444  // and from what
445  hints_what = std::vector<std::string>();
446  if( !importDataFrom( path_what, hints_what ) )
447  {
448  OUTERR( "unable to locate the data file " << LOGSQUARE( path_what ) );
449  return 0;
450  }
451 
452  // setup the random number generator (seed?)
453  std::random_device dev;
454  rng = std::mt19937(dev());
455 
456  // generate the solution of the case
457  if( !ros::param::has( "cluedo_max_hypotheses" ) )
459  else
460  {
461  int tot_hints;
462  ros::param::get( "cluedo_max_hypotheses", tot_hints );
463  ROS_INFO_STREAM( OUTLABEL << "found a max number of hypotheses: " << tot_hints );
464 
466  }
467 
468  // subscriber: hint_signal
469  OUTLOG( "subscribing to the topic " << LOGSQUARE( SUBSCRIBER_HINT_SIGNAL ) << "..." );
470  ros::Subscriber sub_hint_signal = nh.subscribe( SUBSCRIBER_HINT_SIGNAL, 1000, hintCallback );
471  OUTLOG( "subscribing to the topic " << LOGSQUARE( SUBSCRIBER_HINT_SIGNAL ) << "... OK" );
472 
473  // publisher: hint
474  OUTLOG( "Creating publisher " << LOGSQUARE( PUBLISHER_HINT ) << "..." );
475  ros::Publisher pub_hint = nh.advertise<robocluedo_msgs::Hint>( PUBLISHER_HINT, 1000 );
476  hint_channel = &pub_hint;
477  OUTLOG( "Creating publisher " << LOGSQUARE( PUBLISHER_HINT ) << "... OK" );
478 
479  // service: check_solution
480  OUTLOG( "Advertising service " << LOGSQUARE( SERVICE_CHECK_SOLUTION ) << "..." );
481  ros::ServiceServer srv = nh.advertiseService( SERVICE_CHECK_SOLUTION, checkSolutionCallback );
482  OUTLOG( "Advertising service " << LOGSQUARE( SERVICE_CHECK_SOLUTION ) << "... OK" );
483 
484  //spin
485  OUTLOG( "ready!" );
486  ros::spin( );
487 
488  return 0;
489 }
SUBSCRIBER_HINT_SIGNAL
#define SUBSCRIBER_HINT_SIGNAL
Definition: cluedo_oracle.cpp:84
importDataFrom
bool importDataFrom(std::string path, std::vector< std::string > &list)
import entities from file
Definition: cluedo_oracle.cpp:157
checkSolutionCallback
bool checkSolutionCallback(robocluedo_msgs::CheckSolution::Request &hyp, robocluedo_msgs::CheckSolution::Response &misterySolved)
implementation of service SERVICE_CHECK_SOLUTION
Definition: cluedo_oracle.cpp:264
MAX_NUM_HINTS
#define MAX_NUM_HINTS
default maximum number of hint IDs
Definition: cluedo_oracle.cpp:92
PATH_PARAMETER_SERVER_WHERE
#define PATH_PARAMETER_SERVER_WHERE
Definition: cluedo_oracle.cpp:87
MAX_SIZE_HINT
#define MAX_SIZE_HINT
maximum number of hints inside each ID
Definition: cluedo_oracle.cpp:95
generateMystery
void generateMystery(std::vector< std::string > list_who, std::vector< std::string > list_where, std::vector< std::string > list_what, int tot_hints)
generate the solution of the case and the hints
Definition: cluedo_oracle.cpp:314
hints_what
std::vector< std::string > hints_what
vector of hints - what
Definition: cluedo_oracle.cpp:111
hints_where
std::vector< std::string > hints_where
vector of hints - where
Definition: cluedo_oracle.cpp:108
mysterylist
std::vector< robocluedo_msgs::Hint > mysterylist
shuffled list of hypotheses
Definition: cluedo_oracle.cpp:129
PUBLISHER_HINT
#define PUBLISHER_HINT
Definition: cluedo_oracle.cpp:83
SERVICE_CHECK_SOLUTION
#define SERVICE_CHECK_SOLUTION
Definition: cluedo_oracle.cpp:85
LOGSQUARE
#define LOGSQUARE(str)
Definition: cluedo_oracle.cpp:100
OUTLABEL
#define OUTLABEL
Definition: cluedo_oracle.cpp:97
solution_what
robocluedo_msgs::Hint solution_what
SOLUTION - what's the murder weapon.
Definition: cluedo_oracle.cpp:120
main
int main(int argc, char *argv[])
ROS node main - cluedo_oracle.
Definition: cluedo_oracle.cpp:402
hints_who
std::vector< std::string > hints_who
vector of hints - who
Definition: cluedo_oracle.cpp:105
PATH_PARAMETER_SERVER_WHAT
#define PATH_PARAMETER_SERVER_WHAT
Definition: cluedo_oracle.cpp:89
solution_where
robocluedo_msgs::Hint solution_where
SOLUTION - where Dr Black was killed.
Definition: cluedo_oracle.cpp:117
chooseHintFrom
std::string chooseHintFrom(std::vector< std::string > &list)
choose randomly a hint from a list
Definition: cluedo_oracle.cpp:199
PATH_PARAMETER_SERVER_WHO
#define PATH_PARAMETER_SERVER_WHO
Definition: cluedo_oracle.cpp:88
hintCallback
void hintCallback(const std_msgs::EmptyConstPtr &emptySignal)
subscriber to SUBSCRIBER_HINT_SIGNAL and publisher of PUBLISHER_HINT
Definition: cluedo_oracle.cpp:225
solution_who
robocluedo_msgs::Hint solution_who
SOLUTION - who killed Dr Black.
Definition: cluedo_oracle.cpp:114
OUTLOG
#define OUTLOG(msg)
Definition: cluedo_oracle.cpp:98
OUTERR
#define OUTERR(msg)
Definition: cluedo_oracle.cpp:99