diff --git a/CMakeLists.txt b/CMakeLists.txt index a8056ba7beb9765398e2496705a0298d0549ad78..5036e2fe2f5f1749db0863f5feddff93d7749616 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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) +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) ## System dependencies are found with CMake's conventions # find_package(Boost REQUIRED COMPONENTS system) @@ -92,6 +92,7 @@ generate_dynamic_reconfigure_options( cfg/PlayMotionModule.cfg cfg/HeadModule.cfg cfg/NavModule.cfg + cfg/TTSModule.cfg ) ################################### @@ -105,8 +106,8 @@ generate_dynamic_reconfigure_options( ## DEPENDS: system dependencies of this project that dependent projects also need catkin_package( INCLUDE_DIRS include - LIBRARIES gripper_module play_motion_module head_module torso_module nav_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 + 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 # DEPENDS system_lib ) @@ -211,6 +212,21 @@ target_link_libraries(nav_module ${iriutils_LIBRARY}) ## either from message generation or dynamic reconfigure add_dependencies(nav_module ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) +## Declare a C++ library +add_library(tts_module + src/tts_module.cpp +) + +target_link_libraries(tts_module ${catkin_LIBRARIES}) +target_link_libraries(tts_module ${iriutils_LIBRARY}) +##Link to other modules +##target_link_libraries(new_module <module path>/lib<module_name>.so) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +add_dependencies(tts_module ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + ## Declare a C++ executable ## With catkin_make all packages are built within a single CMake context ## The recommended prefix ensures that target names across packages don't collide diff --git a/cfg/PlayMotionModule.cfg b/cfg/PlayMotionModule.cfg index 06f0129ce02c56eff9026d658d6b200570fb705d..67ddc2461d92ea6f4f3a2431d16dea0cd0011806 100755 --- a/cfg/PlayMotionModule.cfg +++ b/cfg/PlayMotionModule.cfg @@ -43,7 +43,7 @@ play_action = gen.add_group("Play motion action") #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, "Gripper 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("action_max_retries",int_t, 0, "Maximum number of retries for 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) diff --git a/include/tiago_modules/play_motion_module.h b/include/tiago_modules/play_motion_module.h index e299e0116795e1e7f4d1593cadfdfd0d4282cbb0..16c4dd1532067bffa970802403d964bf355e7688 100644 --- a/include/tiago_modules/play_motion_module.h +++ b/include/tiago_modules/play_motion_module.h @@ -58,7 +58,6 @@ class CPlayMotionModule : public CModule<play_motion_module::PlayMotionModuleCon void reconfigure_callback(play_motion_module::PlayMotionModuleConfig &config, uint32_t level); public: - //CPlayMotionModule(const std::string &name); CPlayMotionModule(const std::string &name,const std::string &name_space=std::string("")); void execute_motion(play_motion_ids motion_id); void stop(void); diff --git a/package.xml b/package.xml index 15f3a223ae018dc2a6877de684b0ecc2550ff6ca..6f243bd56f0ee4ab09823b9380794a618f5dcddd 100644 --- a/package.xml +++ b/package.xml @@ -52,6 +52,7 @@ <build_depend>nav_msgs</build_depend> <build_depend>pal_navigation_msgs</build_depend> <build_depend>pal_waypoint_msgs</build_depend> + <build_depend>pal_interaction_msgs</build_depend> <build_depend>tf</build_depend> <!-- new dependencies --> <!--<build_depend>new build dependency</build_depend>--> @@ -67,6 +68,7 @@ <run_depend>nav_msgs</run_depend> <run_depend>pal_navigation_msgs</run_depend> <run_depend>pal_waypoint_msgs</run_depend> + <run_depend>pal_interaction_msgs</run_depend> <run_depend>tf</run_depend> <!-- new dependencies --> <!--<run_depend>new run dependency</run_depend>-->