(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Setup the navigation for asr_ftc_local_planner.

Description: Here you have a point by point description with parameters and components you must set up to use the asr_ftc_local_planner.

Tutorial Level: BEGINNER

Next Tutorial: Learn how to find the right parameters for your robot here.

Tutorial

1. Clone the asr_ftc package to your catkin_workspace source folder: https://github.com/asr-ros/asr_ftc_local_planner.git

2. Clone asr_move_base to your catkin_workspace source folder: https://github.com/asr-ros/asr_move_base.git

3. Clone asr_nav_core to your catkin_workspace source folder: https://github.com/asr-ros/asr_nav_core.git

4. Compile the packages with catkin_make.

5. Adapt your move_base.launch (where you start your move_base node, example in "asr_mild_navigation/launch/navigation.launch") or create a new one with these parameters:

<node name="move_base" pkg="asr_move_base_base" type="move_base" respawn="false" output="screen">

<param name="controller_frequency" value="5"/>
<param name="planner_frequency" value="5"/>
<param name="base_local_planner" value="ftc_local_planner/FTCPlanner" /> <rosparam file="$(find package)/...global_costmap_params.yaml" command="load"/>
<rosparam file="$(find package)/.../ftc_local_planner_params.yaml" command="load"/>

</node>

Set the controller and planner frequency to a value higher than 0. The base local planner parameter must be set to the ftc_planner and you need the two yaml files for ftc_planner parameters and global costmap parameters.

The pkg name of move_base must set to "asr_move_base" if you use the asr_move_base package.

6. Adapt or create your global_costmap_params.yaml and place the path to this in the move_base.yaml (see above 5.):

global_costmap:
    update_frequency: 2.0
    publish_frequency: 2.0
    static_map: true

global_costmap/obstacle_layer:
    enabled: true

You must set the update frequency higher than 0. And to drive around obstacles you must activate the obstacle layer.

7. Create a ftc_local_planner_params.yaml and place the path to this in the move_base.yaml (see above 5.):

FTCPlanner:
    max_x_vel: 0.5
    max_rotation_vel: 1.0
    min_rotation_vel: 0.4
    acceleration_x: 0.5
    acceleration_z: 0.5
    position_accuracy: 0.04
    rotation_accuracy: 0.03
    slow_down_factor: 2.5
    sim_time: 0.6
    local_planner_frequence: 5
    join_obstacle: false

Look at the next tutorial on how to set all parameters.

8. Launch the move_base launch file with roslaunch.

Have a look at the navigation tutorial to set up all other components to start the whole navigation e.g. load the map.

Set Camera Focus Point

Level

Intermediate

Description

This tutorial shows you, how to make use of the "set_focus_point" script, allowing you to make the robots camera focus a certain point on the map just by clicking it.

Setup

Before beginning, make sure you have all of the following processes up and running:

Package

Launch-File

Launch-File Simulation

AsrFlirPtuDriver

ptu_left.launch

ptu_left_mock.launch

AsrFlirPtuController

ptu_controller.launch

ptu_controller.launch

AsrMildNavigation

navigation.launch

simulation_*.launch

AsrRobotModelServices

RobotModelServiceReal.launch

RobotModelServiceSim.launch

Tutorial

Once all required processes are set up, start the set_focus_point script via

roslaunch asr_robot_model_services set_focus_point.launch

Now you can send commands to the script using rviz.

PublishPoint.png

Use the Publish Point tool to select a focus point on the map.

LookAt.png

The robot will then try focus the selected point on the map and move the PTU joints accordingly.

If you have activated the visualizeIK option and have selected the visualization topic (default: /asr_robot_model_services/IK_Visualization),

you can also see the resulting view vector in RViz.

Common mistakes

The ptu is not moving after I selected a focus point

Make sure, that all processes are up and running correctly.

Also, check asr_flir_ptu_driver and asr_flir_ptu_controller to make sure, that the calculated angles were within the bounds of the PTU.

Wiki: asr_ftc_local_planner/SetupNavigationForFTCPlanner (last edited 2017-05-28 18:12:06 by FelixMarek)