Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
An object the call navigation to obtain initial staging pose. More...
#include <nav2_docking/opennav_docking/include/opennav_docking/navigator.hpp>
Public Types | |
using | Nav2Pose = nav2_msgs::action::NavigateToPose |
using | ActionClient = rclcpp_action::Client< Nav2Pose > |
Public Member Functions | |
Navigator (const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent) | |
A constructor for opennav_docking::Navigator. More... | |
~Navigator ()=default | |
A destructor for opennav_docking::Navigator. | |
void | activate () |
An activation method. | |
void | deactivate () |
An deactivation method. | |
void | goToPose (const geometry_msgs::msg::PoseStamped &pose, rclcpp::Duration remaining_staging_duration, std::function< bool()> isPreempted, bool recursed=false) |
An method to go to a particular pose May throw exception if fails to navigate or communicate Blocks until completion. More... | |
An object the call navigation to obtain initial staging pose.
Definition at line 39 of file navigator.hpp.
|
explicit |
A constructor for opennav_docking::Navigator.
parent | Weakptr to the node to use to get interances and parameters |
Definition at line 23 of file navigator.cpp.
void opennav_docking::Navigator::goToPose | ( | const geometry_msgs::msg::PoseStamped & | pose, |
rclcpp::Duration | remaining_staging_duration, | ||
std::function< bool()> | isPreempted, | ||
bool | recursed = false |
||
) |
An method to go to a particular pose May throw exception if fails to navigate or communicate Blocks until completion.
pose | Pose to go to |
remaining_staging_duration | Remaining time to get to the staging pose |
isPreempted | Function to check if preempted |
recursed | True if recursed (used to retry once) |
Definition at line 53 of file navigator.cpp.