73 #include "std_msgs/Empty.h"
74 #include "robocluedo_msgs/Hint.h"
75 #include "robocluedo_msgs/CheckSolution.h"
83 #define PUBLISHER_HINT "/hint"
84 #define SUBSCRIBER_HINT_SIGNAL "/hint_signal"
85 #define SERVICE_CHECK_SOLUTION "/check_solution"
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"
92 #define MAX_NUM_HINTS 2
95 #define MAX_SIZE_HINT 10
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 << "] "
126 ros::Publisher* hint_channel;
134 int randomIndex(
int capmax )
136 if( capmax == 0 )
return 0;
138 std::uniform_int_distribution<std::mt19937::result_type> randgen( 0, capmax );
139 return randgen( rng );
161 std::ifstream filestream( path );
162 if( !filestream.is_open( ) )
164 OUTERR(
"no existing file!" );
170 std::string temp =
"";
172 while( getline( filestream, temp ) )
176 list.push_back( temp );
180 OUTLOG(
"closing file ..." );
201 int ridx = randomIndex( list.size()-1 );
202 std::string choice = list[ ridx ];
228 if( !randomIndex( 1 ) )
230 ROS_INFO_STREAM(
OUTLABEL <<
"hint requeste refused. " );
235 ROS_INFO_STREAM(
OUTLABEL <<
"MysteryLIst is empty. " );
240 robocluedo_msgs::Hint h = *(
mysterylist.end() - 1);
244 ROS_INFO_STREAM(
OUTLABEL <<
"publishing hint (" <<
"ID:" << h.HintID <<
", PROP:" << h.HintType <<
", VALUE:" << h.HintContent <<
")" );
245 hint_channel->publish( h );
264 bool checkSolutionCallback( robocluedo_msgs::CheckSolution::Request& hyp, robocluedo_msgs::CheckSolution::Response& misterySolved )
269 ROS_INFO_STREAM(
OUTLABEL <<
"solution wrong. " );
270 misterySolved.MysterySolved =
false;
274 ROS_INFO_STREAM(
OUTLABEL <<
"SUCCESS! Found the solution. " );
275 misterySolved.MysterySolved =
true;
314 void generateMystery( std::vector<std::string> list_who, std::vector<std::string> list_where, std::vector<std::string> list_what,
int tot_hints )
316 ROS_INFO_STREAM(
OUTLABEL <<
"case generation started " );
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() );
341 ROS_INFO_STREAM(
OUTLABEL <<
"the solution has ID:" << solutionID );
344 for(
int i=0; i<tot_hints; ++i )
346 if( i == solutionID )
359 robocluedo_msgs::Hint h;
362 switch( randomIndex( 5 ) )
369 h.HintType =
"where";
386 ROS_INFO_STREAM(
OUTLABEL <<
"hints generation finished. Generated: " <<
mysterylist.size() <<
" hints" );
402 int main(
int argc,
char* argv[] )
404 ros::init( argc, argv,
"cluedo_oracle" );
408 std::string path_who =
"";
409 std::string path_where =
"";
410 std::string path_what =
"";
441 OUTERR(
"unable to locate the data file " <<
LOGSQUARE( path_where ) );
453 std::random_device dev;
454 rng = std::mt19937(dev());
457 if( !ros::param::has(
"cluedo_max_hypotheses" ) )
462 ros::param::get(
"cluedo_max_hypotheses", tot_hints );
463 ROS_INFO_STREAM(
OUTLABEL <<
"found a max number of hypotheses: " << tot_hints );
475 ros::Publisher pub_hint = nh.advertise<robocluedo_msgs::Hint>(
PUBLISHER_HINT, 1000 );
476 hint_channel = &pub_hint;