Class Controller

Class Documentation

class Controller

Default control law for approaching a dock target.

Public Functions

Controller(const rclcpp_lifecycle::LifecycleNode::SharedPtr &node, std::shared_ptr<tf2_ros::Buffer> tf, std::string fixed_frame, std::string base_frame)

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

~Controller()

A destructor for opennav_docking::Controller.

bool computeVelocityCommand(const geometry_msgs::msg::Pose &pose, geometry_msgs::msg::Twist &cmd, bool is_docking, bool backward = false)

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

bool isTrajectoryCollisionFree(const geometry_msgs::msg::Pose &target_pose, bool is_docking, bool backward = false)

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.

rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)

Callback executed when a parameter change is detected.

Parameters:

event – ParameterEvent message

void configureCollisionChecker(const rclcpp_lifecycle::LifecycleNode::SharedPtr &node, std::string costmap_topic, std::string footprint_topic, double transform_tolerance)

Configure the collision checker.

Parameters:
  • node – Lifecycle node

  • costmap_topic – Costmap topic

  • footprint_topic – Footprint topic

  • transform_tolerance – Transform tolerance

Protected Attributes

rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
std::mutex dynamic_params_lock_
rclcpp::Logger logger_ = {rclcpp::get_logger("Controller")}
rclcpp::Clock::SharedPtr clock_
std::unique_ptr<nav2_graceful_controller::SmoothControlLaw> control_law_
double k_phi_
double k_delta_
double beta_
double lambda_
double slowdown_radius_
double v_linear_min_
double v_linear_max_
double v_angular_max_
rclcpp::Publisher<nav_msgs::msg::Path>::SharedPtr trajectory_pub_
bool use_collision_detection_
double projection_time_
double simulation_time_step_
double dock_collision_threshold_
double transform_tolerance_
std::shared_ptr<tf2_ros::Buffer> tf2_buffer_
std::unique_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_
std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_
std::shared_ptr<nav2_costmap_2d::CostmapTopicCollisionChecker> collision_checker_
std::string fixed_frame_
std::string base_frame_