Skip to content
Snippets Groups Projects
Commit 989d80bc authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Updated the launch and configuration files.

parent 369d70b9
No related branches found
No related tags found
No related merge requests found
......@@ -46,8 +46,8 @@ tf = gen.add_group("TF")
add_module_params(gen,"head_module")
move_base_action=add_module_action_params(gen,"move_base")
move_base_action.add("mb_frame_id",str_t, 0, "Reference frame of the position goals","/map")
move_base_action.add("mb_cancel_prev", bool_t, 0, "Cancel previous action", True)
move_base_action.add("move_base_frame_id",str_t, 0, "Reference frame of the position goals","map")
move_base_action.add("move_base_cancel_prev", bool_t, 0, "Cancel previous action", True)
poi_action=add_module_action_params(gen,"move_poi")
......@@ -58,8 +58,8 @@ odom.add("odom_watchdog_time_s", double_t, 0,
tf.add("tf_timeout_time_s", double_t, 0, "Maximum time to wait for transform",5, 0.01, 50)
costmap=add_module_service_params(gen,"clear_costmap")
costmap.add("cm_enable_auto_clear",bool_t, 0, "Periodically clear the costmaps",False)
costmap.add("cm_auto_clear_rate_hz",double_t, 0, "Clear costmaps period", 0.1, 0.01, 1.0)
costmap.add("clear_costmap_enable_auto_clear",bool_t, 0, "Periodically clear the costmaps",False)
costmap.add("clear_costmap_auto_clear_rate_hz",double_t, 0, "Clear costmaps period", 0.1, 0.01, 1.0)
map=add_module_service_params(gen,"change_map")
......
rate_hz: 1.0
mb_max_retries: 1
mb_feedback_watchdog_time_s: 1.0
mb_enable_watchdog: True
mb_timeout_s: 1.0
mb_enable_timeout: True
mb_frame_id: "/map"
mb_enabled: True
mb_cancel_prev: True
poi_max_retries: 1
poi_feedback_watchdog_time_s: 1.0
poi_enable_watchdog: True
poi_timeout_s: 1.0
poi_enable_timeout: True
poi_enabled: True
wp_max_retries: 1
wp_feedback_watchdog_time_s: 1.0
wp_enable_watchdog: True
wp_timeout_s: 1.0
wp_enable_timeout: True
wp_enabled: True
odom_watchdog_time_s: 1.0
tf_timeout_time_s: 5.0
cm_max_retries: 1.0
cm_enable_auto_clear: False
cm_auto_clear_rate_hz: 0.1
cm_enabled: True
map_max_retries: 1
map_enabled: True
op_mode_max_retries: 1
op_mode_enabled: True
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_enable_timeout: True
move_base_frame_id: "map"
move_base_enabled: True
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_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_enable_timeout: True
move_waypoint_enabled: True
odom_watchdog_time_s: 1.0
tf_timeout_time_s: 5.0
clear_costmaps_max_retries: 1.0
clear_costmaps_enable_auto_clear: False
clear_costmaps_auto_clear_rate_hz: 0.1
clear_costmaps_enabled: True
change_map_max_retries: 1
change_map_enabled: True
set_op_mode_max_retries: 1
set_op_mode_enabled: True
<launch>
<!-- launch the play motion client node -->
<node name="nav_client"
pkg="nav_client"
type="nav_client"
output="screen"
ns="/tiago">
<remap from="~/nav_module/move_base"
to="/move_base"/>
<remap from="~/nav_module/move_poi"
to="/poi_navigation_server/go_to_poi"/>
<remap from="~/nav_module/move_waypoint"
to="/pal_waypoint/navigate"/>
<remap from="~/nav_module/odom"
to="/mobile_base_controller/odom"/>
<remap from="~/nav_module/clear_costmaps"
to="/move_base/clear_costmaps"/>
<remap from="~/nav_module/change_map"
to="/pal_map_manager/change_map"/>
<remap from="~/nav_module/set_op_mode"
to="/pal_navigation_sm"/>
<remap from="~/nav_module/move_base_reconf"
to="/move_base/PalLocalPlanner/set_parameters"/>
<rosparam file="$(find tiago_modules)/config/nav_module_default.yaml" command="load" ns="nav_module" />
</node>
<!-- launch dynamic reconfigure -->
<node name="rqt_reconfigure" pkg="rqt_reconfigure" type="rqt_reconfigure" respawn="false"
output="screen"/>
</launch>
<launch>
<include file="$(find tiago_2dnav_gazebo)/launch/tiago_navigation.launch"/>
<include file="$(find tiago_laser_sensors)/launch/rgbd_cloud_laser.launch"/>
<include file="$(find nav_client)/launch/nav_client.launch"/>
</launch>
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="node_name" default="head_client" />
<arg name="output" default="log" />
<arg name="launch_prefix" default="" />
<arg name="config_file" default="$(find tiago_nav_module)/config/tiago_nav_module_default.yaml" />
<arg name="move_base_action" default="/move_base"/>
<arg name="move_poi_action" default="/poi_navigation_server/go_to_poi"/>
<arg name="move_waypoint_action" default="/pal_waypoint/navigate"/>
<arg name="odom_topic" default="/mobile_base_controller/odom"/>
<arg name="clear_costmaps_service" default="/move_base/clear_costmaps"/>
<arg name="change_map_service" default="/pal_map_manager/change_map"/>
<arg name="set_op_mode_service" default="/pal_navigation_sm"/>
<arg name="move_base_dyn_reconf" default="/move_base/PalLocalPlanner/set_parameters"/>
<!-- launch the play motion client node -->
<node name="$(arg node_name)"
pkg="tiago_nav_module"
type="tiago_nav_client"
output="$(arg output)"
launch-prefix="$(arg launch_prefix)">
<remap from="~/nav_module/move_base"
to="$(arg move_base_action)"/>
<remap from="~/nav_module/move_poi"
to="$(arg move_poi_action)"/>
<remap from="~/nav_module/move_waypoint"
to="$(arg move_waypoint_action)"/>
<remap from="~/nav_module/odom"
to="$(arg odom_topic)"/>
<remap from="~/nav_module/clear_costmaps"
to="$(arg clear_costmaps_service)"/>
<remap from="~/nav_module/change_map"
to="$(arg change_map_service)"/>
<remap from="~/nav_module/set_op_mode"
to="$(arg set_op_mode_service)"/>
<remap from="~/nav_module/move_base_reconf"
to="$(arg move_base_dyn_reconf)"/>
<rosparam file="$(arg config_file)" command="load" ns="nav_module" />
</node>
<!-- launch dynamic reconfigure -->
<node name="rqt_reconfigure" pkg="rqt_reconfigure" type="rqt_reconfigure" respawn="false"
output="screen"/>
</launch>
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="node_name" default="head_client" />
<arg name="output" default="log" />
<arg name="launch_prefix" default="" />
<arg name="config_file" default="$(find tiago_nav_module)/config/tiago_nav_module_default.yaml" />
<arg name="move_base_action" default="/move_base"/>
<arg name="move_poi_action" default="/poi_navigation_server/go_to_poi"/>
<arg name="move_waypoint_action" default="/pal_waypoint/navigate"/>
<arg name="odom_topic" default="/mobile_base_controller/odom"/>
<arg name="clear_costmaps_service" default="/move_base/clear_costmaps"/>
<arg name="change_map_service" default="/pal_map_manager/change_map"/>
<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_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="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)"/>
<arg name="odom_topic" value="$(arg odom_topic)"/>
<arg name="clear_costmaps_service" value="$(arg clear_costmaps_service)"/>
<arg name="change_map_service" value="$(arg change_map_service)"/>
<arg name="set_op_mode_service" value="$(arg set_op_mode_service)"/>
<arg name="move_base_dyn_reconf" value="$(arg move_base_dyn_reconf)"/>
</include>
</launch>
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