[Documentation] [TitleIndex] [WordIndex

Overview

The tedusar_daf_path_follower is a simple but efficient path follower for skid-steered/differential drive mobile robots as part of tedusar_ros_pkg repository. To control path follower a tedusar_nav_msgs package is needed which define control messages.

Dynamic Arc Fitting Path Follower

The DAF Path Follower provide control commands (linear and rotational velocity) based on given path designated to follow. Behaviour of the DAF path follower can be adapted to your needs with given Parameters.

ROS Parameters

- base_link (string):

- pub_cmd_hz (double):

- path_topic (nav_msgs/Path):

- pose_update_topic (nav_msgs/Odometry):

- imu_data (sensor_msgs/Imu):

- out_cmd_vel (geometry_msgs/Twist):

- max_lin_vel (double):

- min_lin_vel (double):

- max_rot_vel (double):

- min_rot_vel (double):

- executin_period (double):

- global_goal_tolerance (double):

- enable_angle_compensation (bool):

- enable_ground_compensation (bool):

- enable_velocity_compensation (bool):

- stability_angle (double):

- show_local_path_planning (bool):

Launch File Examples

Start a tedusar_path_follower process with default parameter setings.

 $ roslaunch tedusar_daf_path_follower daf_path_follower_default.launch

Other Documentation

Publication:


2024-06-15 13:48