Órdenes y confirmación mediante voz (sphinx+festival)
Pasos previos
Comenzaremos recopilando el software necesario. Para reconocimiento de voz emplearemos CMU Pocket Sphinx desarrollado en Carnegie Mellon University, y para la locución de texto emplearemos Festival Speech Synthesis System desarrollado en University of Edinburgh.
Actualmente se encuentra disponible para las versiones groovy e hydro de ROS el package pocketsphinx, que podemos instalar simplemente ejecutando en un terminal el siguiente comando:
sudo apt-get install ros-"groovy o hydro"-pocketsphinx
Para versiones anteriores necesitamos instalar el package para ubuntu de CMU Pocket Sphinx. Para instalarlo ejecutaremos el siguiente comando en un terminal:
sudo apt-get install gstreamer0.10-pocketsphinx
Para obtener el package para ROS de CMU Pocket Sphinx, usaremos el stack "rharmony" de University of Albany. En un terminal, nos situaremos en el directorio de nuestro espacio de trabajo, y ejecutaremos la siguiente secuencia de comandos:
svn checkout http://albany-ros-pkg.googlecode.com/svn/trunk/rharmony
rosmake --rosdep-install pocketsphinx
Festival Speech Synthesis System se encuentra integrado en el package de ROS sound_play.
Reconocimiento de voz
Comenzaremos creando el package que va a contener nuestros programas de control mediante la voz. Crearemos un package llamado "voz_fer" con las siguientes dependencias: pocketsphinx sound_play std_msgs roscpp. Ahora tenemos que que establecer las ordenes de voz que vamos a emplear para el control, pueden ser palabras u oraciones (en inglés), el uso de oraciones reduce la aparición de falsos positivos de reconocimiento. El vocabulario seleccionado es el siguiente, que guardaremos en el directorio "config" del package creado, en un archivo llamado "comandos_voz.txt", donde cada palabra u oración irá en una nueva línea:
start speech
stop speech
go forward
go back
turn left
turn right
speed up
slow down
rotate left
rotate right
stop
point beer
point cocacola
fold arm
Para generar este vocabulario para el reconocimiento debemos subir nuestro archivo comandos_voz.txt al siguiente enlace y compilarlo:
Descargaremos los archivos generados al directorio "config" del package creado y los renombraremos como "comandos_voz.*". Vamos a crear un launcher para poder ejecutar el programa de reconocimiento usando el vocabulario que hemos creado. En el directorio "launch" el package crearemos un archivo llamado "comandos_voz.launch" con el siguiente contenido:
<launch>
<node name="recognizer" pkg="pocketsphinx" type="recognizer.py" output="screen">
<param name="lm" value="$(find voz_fer)/config/comandos.lm"/>
<param name="dict" value="$(find voz_fer)/config/comandos.dic"/>
</node>
</launch>
Para iniciar el reconocimiento de voz simplemente debemos ejecutar en un terminal el siguiente comando:
roslaunch voz_fer comandos_voz.launch
Los resultados de reconocimiento de voz se publican en el topic "recognizer/output", en un mensaje tipo std_msgs/String. Podemos ver el resultado producido al hablar ejecutando el siguiente comando en otro terminal:
rostopic echo recognizer/output
Locución de texto
Para poder realizar la locución de texto desde nuestro programa necesitamos hacer uso de la clase sound_play::SoundClient, en la cul se definen las siguientes funciones públicas:
Sound builtinSound (int id)
Create a builtin Sound.
void play (int sound)
Play a buildin sound.
void playWave (const std::string &s)
Plays a WAV or OGG file.
void repeat (const std::string &s)
Say a string repeatedly.
void say (const std::string &s, const std::string &voice="voice_kal_diphone")
Say a string.
void setQuiet (bool state)
Turns warning messages on or off.
SoundClient (ros::NodeHandle &nh, const std::string &topic)
Create a SoundClient that publishes on the given topic.
SoundClient ()
Create a SoundClient with the default topic.
void start (int sound)
Play a buildin sound repeatedly.
void startWave (const std::string &s)
Plays a WAV or OGG file repeatedly.
void stop (int sound)
Stop playing a built-in sound.
void stopAll ()
Stop all currently playing sounds.
void stopSaying (const std::string &s)
Stop saying a string.
void stopWave (const std::string &s)
Stop playing a WAV or OGG file.
Sound voiceSound (const std::string &s)
Create a voice Sound.
Sound waveSound (const std::string &s)
La función que vamos a emplear es "say", que pronuncia una cadena de texto una sola vez, usando la voz por defecto "voice_kal_diphone". Para completar la reproducción de un archivo o cadena de texto es necesario hacer una pausa en la ejecución de nuestro código usando la función "sleep(segundos)".
Programa de control MYRAbot
Este programa permite teleoperar mediante la voz el MYRAbot, así como dar una serie de órdenes para el señalado de objetos presentes en la escena. El programa crea un nodo llamado "control_voz" el cual se suscribe al topic "recognizer/output", publicado por pocketsphinx, y publica los topics "cmd_vel", para el control de los movimientos de la base, y "selected_object", para la selección de opciones de apuntado del brazo, al que está suscrito el programa escoja. En el directorio "src" de nuestro package crearemos un archivo llamado "control_voz.cpp", con el siguiente contenido:
#include "std_msgs/Int16.h"
#include "std_msgs/String.h"
#include "geometry_msgs/Twist.h"
#include "sound_play/sound_play.h"
int inicio = 0;
int rotate = 0;
int turn = 0;
int start = 0;
int stop = 1;
float linear_vel = 0.0;
float angular_vel = 0.0;
std_msgs::String comando_voz;
void sleepok(int t, ros::NodeHandle &n)
{
if (n.ok())
sleep(t);
}
void speech(const std_msgs::String& voz)
{
::comando_voz = voz;
ros::NodeHandle n;
ros::Publisher object_pub_=n.advertise<std_msgs::Int16>("selected_object", 1);
ros::Publisher move_base_pub_=n.advertise<geometry_msgs::Twist>("cmd_vel", 1);
std_msgs::Int16 objeto;
geometry_msgs::Twist mover_base;
if (::comando_voz.data == "start speech")
{
inicio = 1;
}
else if (::comando_voz.data == "stop speech")
{
inicio = 0;
}
else if (inicio == 1)
{
if (::comando_voz.data == "stop")
{
::linear_vel = 0.0;
::angular_vel = 0.0;
}
else if (::comando_voz.data == "go forward")
{
::linear_vel = 0.1;
::angular_vel = 0.0;
}
else if (::comando_voz.data == "go back")
{
::linear_vel = -0.1;
::angular_vel = 0.0;
}
else if (::comando_voz.data == "turn left")
{
if (::angular_vel <= 0 || ::rotate == 1)
{
::angular_vel = 0.1;
::rotate = 0;
::turn = 1;
}
else
{
::angular_vel = ::angular_vel + 0.1;
}
}
else if (::comando_voz.data == "turn right")
{
if (::angular_vel >= 0 || ::rotate == 1)
{
::angular_vel = -0.1;
::rotate = 0;
::turn = 1;
}
else
{
::angular_vel = ::angular_vel - 0.1;
}
}
else if (::comando_voz.data == "rotate left")
{
if (::angular_vel <= 0 || ::turn == 1)
{
::angular_vel = 0.1;
::turn = 0;
::rotate = 1;
}
::linear_vel = 0.0;
}
else if (::comando_voz.data == "rotate right")
{
if (::angular_vel >= 0 || ::turn == 1)
{
::angular_vel = -0.1;
::turn = 0;
::rotate = 1;
}
::linear_vel = 0.0;
}
else if (::comando_voz.data == "speed up")
{
if (::linear_vel == 0)
{
if (::angular_vel > 0 && ::rotate == 1)
{
::angular_vel= ::angular_vel + 0.05;
}
else if (::rotate == 1)
{
::angular_vel = ::angular_vel - 0.05;
}
}
else
{
if (::linear_vel > 0)
{
::linear_vel = ::linear_vel + 0.05;
}
else
{
::linear_vel = ::linear_vel - 0.05;
}
}
}
else if (::comando_voz.data == "slow down")
{
if (::linear_vel == 0)
{
if (::angular_vel > 0 && ::rotate == 1)
{
::angular_vel = ::angular_vel - 0.05;
}
else if (::rotate == 1)
{
::angular_vel = ::angular_vel + 0.05;
}
}
else
{
if (::linear_vel > 0)
{
::linear_vel = ::linear_vel - 0.05;
}
else
{
::linear_vel = ::linear_vel + 0.05;
}
}
}
else if (::comando_voz.data == "point beer")
{
objeto.data = 1;
object_pub_.publish(objeto);
}
else if (::comando_voz.data == "point cocacola")
{
objeto.data = 2;
object_pub_.publish(objeto);
}
else if (::comando_voz.data == "fold arm")
{
objeto.data = 100;
object_pub_.publish(objeto);
}
}
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "control_voz");
ros::NodeHandle n;
ros::Subscriber speech_sub_= n.subscribe("/recognizer/output", 1, speech);
ros::Publisher object_pub_=n.advertise<std_msgs::Int16>("selected_object", 1);
ros::Publisher move_base_pub_=n.advertise<geometry_msgs::Twist>("cmd_vel", 1);
ros::Rate loop_rate(10);
geometry_msgs::Twist mover_base;
sound_play::SoundClient voz_robot;
sleepok(1, n);
while (ros::ok())
{
mover_base.linear.x = ::linear_vel;
mover_base.angular.z = ::angular_vel;
move_base_pub_.publish(mover_base);
if (::comando_voz.data == "start speech" && ::start == 0)
{
voz_robot.say("bep bep. I am listening you");
sleepok(4, n);
::start = 1;
::stop = 0;
}
else if (::comando_voz.data == "stop speech" && ::stop == 0)
{
voz_robot.say("bep bep. I stop listening");
sleepok(4, n);
::stop = 1;
::start = 0;
}
ros::spinOnce();
loop_rate.sleep();
}
ros::spin();
return 0;
}
Para poder compilar y generar el ejecutable del programa añadiremos la siguiente línea de código al final del archivo "CMakeLists.txt" de nuestro package:
rosbuild_add_executable(control_voz src/control_voz.cpp)
Para comenzar la compilación debemos ejecutar en un terminal la siguiente secuencia de comandos:
roscd voz_fer
make
Con el programa compilado y creado el ejecutable, vamos a crear un launcher para lanzar todos los programas necesarios para su ejecución. Crearemos en el directorio "launch" del package un archivo llamado "control_voz.launch" con el siguiente contenido:
<launch>
<include file="$(find voz_fer)/launch/comandos_voz.launch"/>
<node name="soundplay_node" pkg="sound_play" type="soundplay_node.py"/>
<node name="control_voz" pkg="voz_fer" type="control_voz" />
<include file="$(find brazo_fer)/launch/escoja.launch"/>
</launch>
Para iniciar el launcher simplemente deberemos ejecutar el siguiente comando:
roslaunch voz_fer control_voz.launch
En el siguiente vídeo puede verse el modelo del MYRAbot en gazebo, mientras es teleoperado usando los comandos de voz del vocabulario seleccionado: