Contents Menu Expand Light mode Dark mode Auto light/dark mode
This is the documentation of ROS 2 PAL OS edge. For ROS 1, please visit the PAL OS 23.12 documentation.
PAL OS 25.01 documentation
Logo
PAL OS 25.01 documentation

Capabilities and API

  • 🏁 Getting started
  • 🛠 Robot management
  • 📜 Developing applications
  • ⚙️ Robot hardware
  • 👋 Gestures and motions
  • 🧭 Navigation
  • 🦾 Manipulation
  • 👥 Social perception
  • 💬 Communication
  • 😄 Expressive interactions
  • 💡 Knowledge and reasoning
  • 🖥️ User interfaces

Reference

  • PAL OS edge Highlights
  • Frequently Asked Questions
  • Glossary
  • Index
  • Index of tutorials
  • 🚧 Demos
  • List of ROS Topics
  • List of ROS Actions
  • List of ROS Services
  • List of ROS Nodes
  • List of ROS Parameters
Back to top

../_images/tiagopro-icon.png ../_images/tiago-icon.png ../_images/triago-icon.png ../_images/mobile-bases-icon.png

🎮 Nav2 Controllers Extensions¶

Section

🧭 Navigation - high-level documentation

The pal_nav2_controllers package extends the nav2_controllers package, providing implementations of controller modules which act as plugins of the nav2 base class nav2_core::Controller, also known as Local Planners.
These controller plugins are loaded by the Nav2 Controller Server and are used when calling the /follow_path.

PID Controller¶

The PID Controller implements a motion planning algorithm that can be used for path following or for pose tracking.
It implements a simple PID Control
strategy to minimize the distance of the robot from any given path or any give goal.
../_images/pid_omni_controller.gif
Apart from being used as a Nav2 Controller Plugin, it can also be used within the Target Navigation framework as a Target Tracker.
It accepts a nav_msgs::msg::Path with just one Pose and reaches it by minimizing at the same time the x, y, and theta error from the given Pose.
../_images/pid_omni_tracker.gif

Alternatively, this functionality can also be triggered by sending an action goal to the /follow_path.

Send a goal from the command-line¶
  ros2 action send_goal /follow_path nav2_msgs/action/FollowPath "path:
     header:
        stamp:
           sec: 0
           nanosec: 0
        frame_id: 'base_footprint'
     poses:
       - header:
           stamp:
             sec: 0
             nanosec: 0
           frame_id: 'base_footprint'
         pose:
           position:
             x: 0.0
             y: 0.0
             z: 0.0
           orientation:
             x: 0.0
             y: 0.0
             z: 0.0
             w: 1.0
     controller_id: 'TrackPose'
     goal_checker_id: ''"

You can set the usage of the PID Controller by setting the controller_id field to 'TrackPose' and change the pose.position and the pose.orientation values to the desired pose. Furthermore, by setting the frame_id to the base_footprint, this works as a Cartesian Controller that moves the robot to a goal expressed relative to its base frame. In this configuration, it can also be used for Instruction-based Navigation (e.g. move three meters forward, then turn right).

Obstacle Avoidance¶

This controller implements a basic collision detection algorithm that before sending a velocity commands to the robot, simulates its consequences (e.g. where will the robot be after this command). If a collision is detected, the robot is stopped.

../_images/pid_obstacle_avoidance.gif

Configuration¶

Parameter

Description

simulate_ahead_time

The time (in seconds) to project the velocity when looking for collisions.

max_linear_vel

Maximum linear velocity (m/s) allowed by the controller.

max_angular_vel

Maximum angular velocity (rad/s) allowed by the controller.

kp_gain

Proportional Gain of the PID controller.

ki_gain

Integral Gain of the PID controller.

kd_gain

Derivative Gain of the PID controller.

antiwindup

Whether to enable the antiwindup.

integration_clamp

Max Integral error allowed.

step_size

Sampling size of the path. Lower values correspond to stricter path following.

motion_model

Desired motion model used for motion planning. Options are: 'DiffDrive', 'OmniDrive'.

transform_tolerance

Time tolerance for data transformations with TF (in seconds).

All the parameters above are dynamic, and can be changed at runtime producing a change in the behavior of the controller.

Copyright © 2024, PAL Robotics
Made with Sphinx and @pradyunsg's Furo
On this page
  • 🎮 Nav2 Controllers Extensions
    • PID Controller
      • Obstacle Avoidance
    • Configuration
🛠 Getting support