Skip to content
Snippets Groups Projects
Commit f3e03727 authored by Irene Garcia Camacho's avatar Irene Garcia Camacho
Browse files

Merge branch 'tts_module' of...

Merge branch 'tts_module' of ssh://gitlab.iri.upc.edu:2202/nen/modules/tiago_modules into tts_module
parents 6345748c 2ed04979
No related branches found
No related tags found
No related merge requests found
......@@ -7,7 +7,7 @@ project(tiago_modules)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS roscpp dynamic_reconfigure iri_ros_tools actionlib play_motion_msgs control_msgs geometry_msgs std_srvs move_base_msgs tf nav_msgs pal_navigation_msgs pal_waypoint_msgs pal_interaction_msgs)
find_package(catkin REQUIRED COMPONENTS roscpp dynamic_reconfigure iri_ros_tools actionlib play_motion_msgs control_msgs geometry_msgs std_srvs move_base_msgs tf nav_msgs pal_navigation_msgs pal_waypoint_msgs pal_interaction_msgs moveit_msgs)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
......@@ -92,7 +92,7 @@ generate_dynamic_reconfigure_options(
cfg/PlayMotionModule.cfg
cfg/HeadModule.cfg
cfg/NavModule.cfg
cfg/TtsModule.cfg
cfg/TTSModule.cfg
)
###################################
......@@ -107,7 +107,7 @@ generate_dynamic_reconfigure_options(
catkin_package(
INCLUDE_DIRS include
LIBRARIES gripper_module play_motion_module head_module torso_module nav_module tts_module#leds_module
CATKIN_DEPENDS roscpp dynamic_reconfigure iri_ros_tools actionlib play_motion_msgs control_msgs geometry_msgs std_srvs move_base_msgs tf nav_msgs pal_navigation_msgs pal_waypoint_msgs pal_interaction_msgs
CATKIN_DEPENDS roscpp dynamic_reconfigure iri_ros_tools actionlib play_motion_msgs control_msgs geometry_msgs std_srvs move_base_msgs tf nav_msgs pal_navigation_msgs pal_waypoint_msgs pal_interaction_msgs moveit_msgs
# DEPENDS system_lib
)
......
......@@ -37,15 +37,15 @@ from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator()
play_action = gen.add_group("Play motion action")
tts = gen.add_group("Text to speech action")
# Name Type Reconfiguration level Description Default Min Max
#gen.add("velocity_scale_factor", double_t, 0, "Maximum velocity scale factor", 0.5, 0.0, 1.0)
gen.add("rate_hz", double_t, 0, "TTS module rate in Hz", 1.0, 1.0, 100.0)
play_action.add("action_max_retries",int_t, 0, "Maximum number of retries fro the action start", 1, 1, 10)
play_action.add("feedback_watchdog_time_s",double_t, 0, "Maximum time between feedback messages", 1, 0.01, 50)
play_action.add("timeout_s", double_t, 0, "Maximum time allowed to complete the action", 1, 0.1, 30)
play_action.add("enable_timeout",bool_t, 0, "Enable action timeout ", True)
tts.add("action_max_retries", int_t, 0, "Maximum number of retries fro the action start", 1, 1, 10)
tts.add("feedback_watchdog_time_s",double_t, 0, "Maximum time between feedback messages", 1, 0.01, 50)
tts.add("timeout_s", double_t, 0, "Maximum time allowed to complete the action", 1, 0.1, 30)
tts.add("enable_timeout", bool_t, 0, "Enable action timeout ", True)
exit(gen.generate(PACKAGE, "TTSModuleAlgorithm", "TTSModule"))
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