Class RotationShimController

Inheritance Relationships

Base Type

  • public nav2_core::Controller

Class Documentation

class RotationShimController : public nav2_core::Controller

Rotate to rough path heading controller shim plugin.

Public Functions

RotationShimController()

Constructor for nav2_rotation_shim_controller::RotationShimController.

~RotationShimController() override = default

Destrructor for nav2_rotation_shim_controller::RotationShimController.

virtual void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr<tf2_ros::Buffer> tf, std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override

Configure controller state machine.

Parameters:
  • parent – WeakPtr to node

  • name – Name of plugin

  • tf – TF buffer

  • costmap_ros – Costmap2DROS object of environment

virtual void cleanup() override

Cleanup controller state machine.

virtual void activate() override

Activate controller state machine.

virtual void deactivate() override

Deactivate controller state machine.

virtual geometry_msgs::msg::TwistStamped computeVelocityCommands(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker*) override

Compute the best command given the current pose and velocity.

Parameters:
  • pose – Current robot pose

  • velocity – Current robot velocity

  • goal_checker – Ptr to the goal checker for this task in case useful in computing commands

Returns:

Best command

virtual void setPlan(const nav_msgs::msg::Path &path) override

nav2_core setPlan - Sets the global plan

Parameters:

path – The global plan

virtual void setSpeedLimit(const double &speed_limit, const bool &percentage) override

Limits the maximum linear speed of the robot.

Parameters:
  • speed_limit – expressed in absolute value (in m/s) or in percentage from maximum robot speed.

  • percentage – Setting speed limit in percentage if true or in absolute values in false case.

Protected Functions

geometry_msgs::msg::PoseStamped getSampledPathPt()

Finds the point on the path that is roughly the sampling point distance away from the robot for use. May throw exception if a point at least that far away cannot be found.

Returns:

pt location of the output point

geometry_msgs::msg::Pose transformPoseToBaseFrame(const geometry_msgs::msg::PoseStamped &pt)

Uses TF to find the location of the sampled path point in base frame.

Parameters:

pt – location of the sampled path point

Returns:

location of the pose in base frame

geometry_msgs::msg::TwistStamped computeRotateToHeadingCommand(const double &angular_distance, const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity)

Rotates the robot to the rough heading.

Parameters:
  • angular_distance – Angular distance to the goal remaining

  • pose – Starting pose of robot

  • velocity – Starting velocity of robot

Returns:

Twist command for rotation to rough heading

void isCollisionFree(const geometry_msgs::msg::TwistStamped &cmd_vel, const double &angular_distance_to_heading, const geometry_msgs::msg::PoseStamped &pose)

Checks if rotation is safe.

Parameters:
  • cmd_vel – Velocity to check over

  • angular_distance_to_heading – Angular distance to heading requested

  • pose – Starting pose of robot

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

Callback executed when a parameter change is detected.

Parameters:

event – ParameterEvent message

Protected Attributes

rclcpp_lifecycle::LifecycleNode::WeakPtr node_
std::shared_ptr<tf2_ros::Buffer> tf_
std::string plugin_name_
rclcpp::Logger logger_ = {rclcpp::get_logger("RotationShimController")}
rclcpp::Clock::SharedPtr clock_
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_
std::unique_ptr<nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D*>> collision_checker_
pluginlib::ClassLoader<nav2_core::Controller> lp_loader_
nav2_core::Controller::Ptr primary_controller_
bool path_updated_
nav_msgs::msg::Path current_path_
double forward_sampling_distance_
double angular_dist_threshold_
double rotate_to_heading_angular_vel_
double max_angular_accel_
double control_duration_
double simulate_ahead_time_
std::mutex mutex_
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_