diff --git a/cfg/TiagoNavClient.cfg b/cfg/TiagoNavClient.cfg index b5fc86e763479a7005d371e3bdb13f23680660b1..cc49d7b81a0f6a7a23e39fe1f7447f5dc4ee0a50 100755 --- a/cfg/TiagoNavClient.cfg +++ b/cfg/TiagoNavClient.cfg @@ -50,7 +50,7 @@ move_base.add("mb_y_pos", double_t, 0, " move_base.add("mb_xy_tol", double_t, 0, "Target XY tolerance", -1.0, -1.0, 10.0) move_base.add("mb_yaw", double_t, 0, "Target Yaw angle", 0.0, -3.14159,3.14159) move_base.add("mb_yaw_tol", double_t, 0, "Target Yaw tolerance", -1.0, -1.0, 1.0) -move_base.add("mb_frame_id", str_t, 0, "Target pose frame identifier", "/base_link") +move_base.add("mb_frame_id", str_t, 0, "Target pose frame identifier", "map") map.add("map_name", str_t, 0, "Name of the map to use", "iri_map") map.add("map_change", bool_t, 0, "Update the desired map", False) diff --git a/config/tiago_nav_module_default.yaml b/config/tiago_nav_module_default.yaml index 54718f239b63a4c98c226f941d19752fbaf7e6af..31c469828f95999863e5ed9616984828ab3b0128 100644 --- a/config/tiago_nav_module_default.yaml +++ b/config/tiago_nav_module_default.yaml @@ -3,7 +3,7 @@ nav_module_rate_hz: 1.0 move_base_max_retries: 1 move_base_feedback_watchdog_time_s: 1.0 move_base_enable_watchdog: True -move_base_timeout_s: 1.0 +move_base_timeout_s: 100.0 move_base_enable_timeout: True move_base_frame_id: "map" move_base_enabled: True @@ -12,14 +12,14 @@ move_base_cancel_prev: True move_poi_max_retries: 1 move_poi_feedback_watchdog_time_s: 1.0 move_poi_enable_watchdog: True -move_poi_timeout_s: 1.0 +move_poi_timeout_s: 100.0 move_poi_enable_timeout: True move_poi_enabled: True move_waypoint_max_retries: 1 move_waypoint_feedback_watchdog_time_s: 1.0 move_waypoint_enable_watchdog: True -move_waypoint_timeout_s: 1.0 +move_waypoint_timeout_s: 100.0 move_waypoint_enable_timeout: True move_waypoint_enabled: True diff --git a/launch/tiago_nav_client_sim.launch b/launch/tiago_nav_client_sim.launch index 7b32600187f58a43818d1c4405241677a1e555d4..22db9fc9dc5ca5bc1a213e611f25df619de487fe 100644 --- a/launch/tiago_nav_client_sim.launch +++ b/launch/tiago_nav_client_sim.launch @@ -13,15 +13,16 @@ <arg name="set_op_mode_service" default="/pal_navigation_sm"/> <arg name="move_base_dyn_reconf" default="/move_base/PalLocalPlanner/set_parameters"/> - <include file="$(find tiago_2dnav_gazebo)/launch/tiago_navigation.launch"/> - - <include file="$(find tiago_laser_sensors)/launch/rgbd_cloud_laser.launch"/> + <include file="$(find tiago_2dnav_gazebo)/launch/tiago_navigation.launch"> + <arg name="public_sim" value="true" /> + <arg name="robot" value="steel" /> + </include> <include file="$(find tiago_nav_module)/launch/tiago_nav_client.launch"> <arg name="node_name" value="$(arg node_name)" /> <arg name="output" value="$(arg output)" /> <arg name="launch_prefix" value="$(arg launch_prefix)" /> - <arg name="config_file" value="$(arg_config_file)" /> + <arg name="config_file" value="$(arg config_file)" /> <arg name="move_base_action" value="$(arg move_base_action)"/> <arg name="move_poi_action" value="$(arg move_poi_action)"/> <arg name="move_waypoint_action" value="$(arg move_waypoint_action)"/>