Skip to content
Snippets Groups Projects
Commit 772fb990 authored by Antonio Andriella's avatar Antonio Andriella
Browse files

adding images and message ser

parent ecb7fbff
No related branches found
No related tags found
No related merge requests found
......@@ -102,16 +102,11 @@ bool RockPaperScissorAlgNode::game_outcomeCallback(
bool tie = false;
bool lose = false;
// start of game loop, the loop will run untill ch == n
ROS_INFO("Press 1 for Rock, 2 for Paper, 3 for Scissors:");
ROS_INFO("Say Rock ..... Paper ...... Scissors.");
this->speech_String_msg_.data =
"Press 1. for Rock, 2. for Paper, 3. for Scissors";
"Say .... either Rock ..... or. Paper ...... or. Scissors";
this->speech_publisher_.publish(this->speech_String_msg_);
cv::Mat OutIm = cv::imread(images_dir + "/images/Rock.PNG");
this->image_Image_msg_ =
*cv_bridge::CvImage(std_msgs::Header(), "bgr8", OutIm).toImageMsg();
this->image_publisher_.publish(this->image_Image_msg_);
do {
std::srand(unsigned(std::time(0)));
......@@ -137,13 +132,13 @@ bool RockPaperScissorAlgNode::game_outcomeCallback(
int ai = rand() % 3 + 1;
switch (ai) {
case 1:
guess = "Rock";
guess = "rock";
break;
case 2:
guess = "Paper";
guess = "paper";
break;
case 3:
guess = "Scissors";
guess = "scissors";
break;
}
......@@ -194,8 +189,10 @@ bool RockPaperScissorAlgNode::game_outcomeCallback(
this->speech_publisher_.publish(this->speech_String_msg_);
cv::Mat OutIm;
cv::Mat Im1 = cv::imread(images_dir + "/figures/tie.jpg");
cv::Mat Im1 = cv::imread(images_dir + "/images/tie.png");
cv::Mat Im2 = cv::imread(images_dir + "/images/" + guess + ".PNG");
ROS_INFO_STREAM("IMg1 size "<<Im1.size()<<" Img2 size "<<Im2.size());
cv::vconcat(Im2, Im1, OutIm);
this->image_Image_msg_ =
*cv_bridge::CvImage(std_msgs::Header(), "bgr8", OutIm).toImageMsg();
......@@ -209,9 +206,13 @@ bool RockPaperScissorAlgNode::game_outcomeCallback(
this->speech_publisher_.publish(this->speech_String_msg_);
cv::Mat OutIm;
cv::Mat Im1 = cv::imread(images_dir + "/figures/won.jpg");
cv::Mat Im1 = cv::imread(images_dir + "/images/won.png");
cv::Mat Im2 = cv::imread(images_dir + "/images/" + guess + ".PNG");
ROS_INFO_STREAM("IMg1 size "<<Im1.rows<<","<<Im1.cols<<" Img2 size "<<Im2.rows<<","<<Im2.cols);
cv::vconcat(Im2, Im1, OutIm);
this->image_Image_msg_ =
*cv_bridge::CvImage(std_msgs::Header(), "bgr8", OutIm).toImageMsg();
this->image_publisher_.publish(this->image_Image_msg_);
......@@ -224,9 +225,12 @@ bool RockPaperScissorAlgNode::game_outcomeCallback(
this->speech_publisher_.publish(this->speech_String_msg_);
cv::Mat OutIm;
cv::Mat Im1 = cv::imread(images_dir + "/figures/lost.jpg");
cv::Mat Im1 = cv::imread(images_dir + "/images/lost.png");
cv::Mat Im2 = cv::imread(images_dir + "/images/" + guess + ".PNG");
ROS_INFO_STREAM("IMg1 size "<<Im1.size()<<" Img2 size "<<Im2.size());
cv::vconcat(Im2, Im1, OutIm);
this->image_Image_msg_ =
*cv_bridge::CvImage(std_msgs::Header(), "bgr8", OutIm).toImageMsg();
this->image_publisher_.publish(this->image_Image_msg_);
......@@ -251,7 +255,6 @@ bool RockPaperScissorAlgNode::game_outcomeCallback(
// this->game_outcome_mutex_exit();
// this->alg_.unlock();
return true;
}
void RockPaperScissorAlgNode::game_outcome_mutex_enter(void) {
......
PAPER
ROCK
SCISSORS
......@@ -2,9 +2,9 @@
<remap from="/recognizer/output" to="/iri_voice_recognizer/spoken_text"/>
<node name="recognizer" pkg="pocketsphinx" type="recognizer.py" output="screen">
<param name="lm" value="$(find iri_voice_recognizer)/dict/rps.lm"/>
<param name="dict" value="$(find iri_voice_recognizer)/dict/rps.dic"/>
</node>
<arg name="_dict" value="_dict:=$(find iri_voice_recognizer)/dict/rps.dic"/>
<arg name="_kws" value="_kws:=$(find iri_voice_recognizer)/dict/rps.kwlist"/>
<node name="pocketsphinx_recognizer" pkg="pocketsphinx" type="recognizer.py" output="screen" args="$(arg _dict) $(arg _kws)" />
</launch>
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment