Class Controller
- Defined in File controller.hpp 
Class Documentation
- Default control law for approaching a dock target. - Public Functions - Create a controller instance. Configure ROS 2 parameters. - Parameters:
- node – Lifecycle node 
- tf – tf2_ros TF buffer 
- fixed_frame – Fixed frame 
- base_frame – Robot base frame 
 
 
 - A destructor for opennav_docking::Controller. 
 - Compute a velocity command using control law. - Parameters:
- pose – Target pose, in robot centric coordinates. 
- cmd – Command velocity. 
- is_docking – If true, robot is docking. If false, robot is undocking. 
- backward – If true, robot will drive backwards to goal. 
 
- Returns:
- True if command is valid, false otherwise. 
 
 - Protected Functions - Check if a trajectory is collision free. - Parameters:
- target_pose – Target pose, in robot centric coordinates. 
- is_docking – If true, robot is docking. If false, robot is undocking. 
- backward – If true, robot will drive backwards to goal. 
 
- Returns:
- True if trajectory is collision free. 
 
 - Callback executed when a parameter change is detected. - Parameters:
- event – ParameterEvent message 
 
 - Configure the collision checker. - Parameters:
- node – Lifecycle node 
- costmap_topic – Costmap topic 
- footprint_topic – Footprint topic 
- transform_tolerance – Transform tolerance 
 
 
 - Protected Attributes