/tts
#
/tts
Quick Facts
- Category
- Message type
The TTS engine can be accessed via a ROS action server named
/tts
. The action type is pal_interaction_msgs/Tts.
Goal definition fields:
I18nText text
TtsText rawtext
string speakerName
float64 wait_before_speaking
Result definition fields:
string text
string msg
Feedback message:
uint16 event_type
time timestamp
string text_said
string next_word
string viseme_id
TtsMark marks
Text to speech goals need to have either the rawtext
or the text
fields
defined, as specified in the sections below.
The field wait_before_speaking
can be used to specify a certain amount of time (in seconds) the system
has to wait before speaking aloud the text specified. It may be used to generate
delayed synthesis.
Sending a raw text goal
The rawtext field of type TtsText has the following format:
string text
string lang_id
The rawtext
field needs to be filled with the text utterance the robot has
to pronounce and the text’s language should to be specified in the lang_id
field. The language Id must follow the format language_country
specified
in the RFC 3066 document (i.e., en_GB, es_ES, …).
Sending a I18nText goal
The text field of type I18nText has the following format:
string section
string key
string lang_id
I18nArgument[] arguments
I18n
stands for Internationalization, this is used to send a pair of
section and key that identifies a sentence or a piece of text stored inside the
robot.
In this case the lang_id
and arguments
fields are optional. This allows
the user to send a sentence without the need of specifying which language must
be used, the robot will pick the language it’s currently speaking and say the
sentence in that language.
Refer to the ROS manual you can find examples about how to create an action client that uses these message definitions to generate speech.
Quick snippets#
$ rostopic pub /tts/goal pal_interaction_msgs/TtsActionGoal # press Tab to complete the message prototype
How to use in your code#
#!/usr/bin/env python
import rospy
import actionlib
from pal_interaction_msgs.msg import *
if __name__ == "__main__":
client = actionlib.SimpleActionClient("/tts", pal_interaction_msgs.msg.TtsAction)
client.wait_for_server()
# check https://github.com/pal-robotics/pal_msgs/tree/indigo-devel/pal_interaction_msgs/action/Tts.action
# for the possible goal parameters
goal = pal_interaction_msgs.msg.TtsGoal(param1=..., param2=...)
client.send_goal(goal)
client.wait_for_result()
rospy.loginfo("Action returned: %s" % client.get_result())
#include <ros/ros.h>
#include <actionlib/client/simple_action_client.h>
#include <actionlib/client/terminal_state.h>
#include <pal_interaction_msgs/TtsAction.h>
int main (int argc, char **argv)
{
ros::init(argc, argv, "tts_action_client");
// create the action client
// true causes the client to spin its own thread
actionlib::SimpleActionClient<:pal_interaction_msgs::TtsAction> ac("/tts", true);
ROS_INFO("Waiting for action server to start.");
// wait for the action server to start
ac.waitForServer(); //will wait for infinite time
ROS_INFO("Action server started, sending goal.");
// send a goal to the action
pal_interaction_msgs::TtsGoal goal;
// check https://github.com/pal-robotics/pal_msgs/tree/indigo-devel/pal_interaction_msgs/action/Tts.action
// for the possible goal parameters
// goal.... = ...;
ac.sendGoal(goal);
//wait for the action to return
bool finished_before_timeout = ac.waitForResult(ros::Duration(30.0));
if (finished_before_timeout)
{
actionlib::SimpleClientGoalState state = ac.getState();
ROS_INFO("Action finished: %s",state.toString().c_str());
}
else
{
ROS_INFO("Action did not finish before the time out.");
ac.cancelGoal();
}
return 0;
}
You can also access this action from a webpage displayed on the robot’s touchscreen via this endpoint:
http://<robot>-0c/action/tts
(replace <robot>-0c
by the serial number of your own robot).
See REST interface for the general documentation of the REST endpoints and code samples.