ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version

I think you should be able to run the standalone global_planner like so:

<launch>
    <master auto="start"/>
    <node pkg="tf" type="static_transform_publisher" name="base_link_to_map"
        args="0.0 0.0 0.0 0.0 0.0 0.0 /base_link /map 40" />
    <param name="/planner/costmap/width" value="10.0"/>
    <param name="/planner/costmap/height" value="10.0"/>
    <param name="/planner/costmap/origin_x" value="-5.0"/>
    <param name="/planner/costmap/origin_y" value="-5.0"/>
    <param name="/planner/costmap/allow_unknown " value="true"/>
    <param name="/planner/costmap/visualize_potential " value="true"/>

    <node pkg="global_planner" type="planner" respawn="false" name="planner" output="screen"/>
    <!-- OR NAVFN -->
    <!-- <node pkg="navfn" type="navfn_node" respawn="false" name="planner" output="screen" /> -->

    <node pkg="rviz" type="rviz" name="rviz"/>
</launch>

do not forget about change 2D Nav Goal topic (tool properties panel) to /planner/goal .

Minimal move_base roslaunch file can look like:

<launch>
    <node pkg="tf" type="static_transform_publisher" name="base_link_to_map"
        args="0.0 0.0 0.0 0.0 0.0 0.0 /base_link /map 40" />

    <arg name="base_global_planner" default="navfn/NavfnROS"/>
    <arg name="base_local_planner" default="dwa_local_planner/DWAPlannerROS"/>
    <!-- <arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> -->

    <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
        <param name="base_global_planner" value="$(arg base_global_planner)"/>
        <param name="base_local_planner" value="$(arg base_local_planner)"/>  

        <param name="local_costmap/width" value="10.0"/>
        <param name="local_costmap/height" value="10.0"/>
        <param name="local_costmap/origin_x" value="-5.0"/>
        <param name="local_costmap/origin_y" value="-5.0"/>

        <param name="global_costmap/width" value="20.0"/>
        <param name="global_costmap/height" value="20.0"/>
        <param name="global_costmap/origin_x" value="-10.0"/>
        <param name="global_costmap/origin_y" value="-10.0"/>
    </node>
    <node pkg="rviz" type="rviz" name="rviz"/>
</launch>

Have fun!

I think you should be able to run the standalone global_planner like so:

<?xml version="1.0"?>
<launch>
    <master auto="start"/>

    <arg name="global_frame" default="/map"/>
    <arg name="robot_base_frame" default="base_link"/>

    <node pkg="tf" type="static_transform_publisher" name="base_link_to_map"
        args="0.0 0.0 0.0 0.0 0.0 0.0 /base_link /map $(arg robot_base_frame) $(arg global_frame) 40" />
    <param name="/planner/costmap/width" value="10.0"/>
    <param name="/planner/costmap/height" value="10.0"/>
    <param name="/planner/costmap/origin_x" value="-5.0"/>
    <param name="/planner/costmap/origin_y" value="-5.0"/>
    <param name="/planner/costmap/allow_unknown " value="true"/>
    <param name="/planner/costmap/visualize_potential " value="true"/>

    <node pkg="global_planner" type="planner" respawn="false" name="planner" output="screen"/>
    <!-- OR NAVFN -->
    <!--  <node pkg="navfn" type="navfn_node" respawn="false" name="planner" output="screen" output="screen">
        <param name="navfn_planner/visualize_potential" value="true" />
        <param name="navfn_planner/allow_unknown" value="true" />
        <param name="navfn_planner/planner_window_x" value="0.0" />
        <param name="navfn_planner/planner_window_y" value="0.0" />
        <param name="navfn_planner/default_tolerance" value="0.0" />

    <!-- or global_planner -->
     <!--<node pkg="global_planner" type="planner" respawn="false" name="planner" output="screen">
        <param name="planner/old_navfn_behavior" value="false" />
        <param name="planner/use_quadratic" value="true" />
        <param name="planner/use_dijkstra" value="true" />
        <param name="planner/use_grid_path" value="false" />
        <param name="planner/allow_unknown" value="true" />
        <param name="planner/planner_window_x" value="0.0" />
        <param name="planner/planner_window_y" value="0.0" />
        <param name="planner/default_tolerance" value="0.0" />
        <param name="planner/publish_scale" value="100" /> -->

        <remap from="/planner/goal" to="/move_base_simple/goal" />

        <!--costmap-->
            <!--required-->
            <param name="costmap/global_frame" value="$(arg global_frame)"/>
            <param name="costmap/robot_base_frame" value="$(arg robot_base_frame)"/>
            <param name="costmap/origin_x" value="-5.0"/>
            <param name="costmap/origin_y" value="-5.0"/>
            <!--optional-->
            <param name="costmap/width" value="10.0"/>
            <param name="costmap/height" value="10.0"/>
            <param name="costmap/resolution" value="0.05"/>
            <param name="costmap/transform_tolerance" value="0.2"/>
            <param name="costmap/update_frequency" value="5.0"/>
            <param name="costmap/publish_frequency" value="0.0"/>
            <param name="costmap/transform_tolerance" value="0.2"/>
            <param name="costmap/rolling_window" value="false"/>
            <param name="costmap/track_unknown_space" value="false"/>
            <param name="costmap/always_send_full_costmap" value="false"/>
            <param name="costmap/footprint_padding" value="0.0"/>
            <param name="costmap/robot_radius" value="0.5"/>
    </node>

    <node pkg="rviz" type="rviz" name="rviz"/>
</launch>

do not forget about change 2D Nav Goal topic (tool properties panel) to /planner/goal .

Minimal move_base roslaunch file can look like:

<launch>
    <node pkg="tf" type="static_transform_publisher" name="base_link_to_map"
        args="0.0 0.0 0.0 0.0 0.0 0.0 /base_link /map 40" />

    <arg name="base_global_planner" default="navfn/NavfnROS"/>
    <arg name="base_local_planner" default="dwa_local_planner/DWAPlannerROS"/>
    <!-- <arg name="base_local_planner" default="base_local_planner/TrajectoryPlannerROS"/> -->

    <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
        <param name="base_global_planner" value="$(arg base_global_planner)"/>
        <param name="base_local_planner" value="$(arg base_local_planner)"/>  

        <param name="local_costmap/width" value="10.0"/>
        <param name="local_costmap/height" value="10.0"/>
        <param name="local_costmap/origin_x" value="-5.0"/>
        <param name="local_costmap/origin_y" value="-5.0"/>

        <param name="global_costmap/width" value="20.0"/>
        <param name="global_costmap/height" value="20.0"/>
        <param name="global_costmap/origin_x" value="-10.0"/>
        <param name="global_costmap/origin_y" value="-10.0"/>
    </node>
    <node pkg="rviz" type="rviz" name="rviz"/>
</launch>

Have fun!