Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
opennav_docking::SimpleNonChargingDock Class Reference
Inheritance diagram for opennav_docking::SimpleNonChargingDock:
Inheritance graph
[legend]
Collaboration diagram for opennav_docking::SimpleNonChargingDock:
Collaboration graph
[legend]

Public Member Functions

 SimpleNonChargingDock ()
 Constructor.
 
virtual void configure (const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &name, std::shared_ptr< tf2_ros::Buffer > tf)
 
virtual void cleanup ()
 Method to cleanup resources used on shutdown.
 
virtual void activate ()
 Method to active Behavior and any threads involved in execution.
 
virtual void deactivate ()
 Method to deactive Behavior and any threads involved in execution.
 
virtual geometry_msgs::msg::PoseStamped getStagingPose (const geometry_msgs::msg::Pose &pose, const std::string &frame)
 Method to obtain the dock's staging pose. This method should likely be using TF and the dock's pose information to find the staging pose from a static or parameterized staging pose relative to the docking pose. More...
 
virtual bool getRefinedPose (geometry_msgs::msg::PoseStamped &pose, std::string id)
 Method to obtain the refined pose of the dock, usually based on sensors. More...
 
virtual bool isDocked ()
 Have we made contact with dock? This can be implemented in a variety of ways: by establishing communications with the dock, by monitoring the the drive motor efforts, etc. More...
 
- Public Member Functions inherited from opennav_docking_core::NonChargingDock
virtual ~NonChargingDock ()
 Virtual destructor.
 
bool isCharging () final
 Are we charging? If a charge dock requires any sort of negotiation to begin charging, that should happen inside this function as this function will be called repeatedly after the docking loop to check if successful. More...
 
bool disableCharging () final
 Undocking while current is still flowing can damage a charge dock so some charge docks provide the ability to disable charging before the robot physically disconnects. The undocking action will not command the robot to move until this returns true. More...
 
bool hasStoppedCharging () final
 Similar to isCharging() but called when undocking.
 
bool isCharger () final
 Gets if this is a charging-typed dock.
 
- Public Member Functions inherited from opennav_docking_core::ChargingDock
virtual ~ChargingDock ()
 Virtual destructor.
 
std::string getName ()
 

Protected Member Functions

void jointStateCallback (const sensor_msgs::msg::JointState::SharedPtr state)
 

Protected Attributes

rclcpp::Subscription< geometry_msgs::msg::PoseStamped >::SharedPtr dock_pose_sub_
 
rclcpp::Publisher< geometry_msgs::msg::PoseStamped >::SharedPtr dock_pose_pub_
 
rclcpp::Publisher< geometry_msgs::msg::PoseStamped >::SharedPtr filtered_dock_pose_pub_
 
rclcpp::Publisher< geometry_msgs::msg::PoseStamped >::SharedPtr staging_pose_pub_
 
geometry_msgs::msg::PoseStamped detected_dock_pose_
 
geometry_msgs::msg::PoseStamped dock_pose_
 
rclcpp::Subscription< sensor_msgs::msg::JointState >::SharedPtr joint_state_sub_
 
std::vector< std::string > stall_joint_names_
 
double stall_velocity_threshold_
 
double stall_effort_threshold_
 
bool is_stalled_
 
bool use_external_detection_pose_
 
double external_detection_timeout_
 
tf2::Quaternion external_detection_rotation_
 
double external_detection_translation_x_
 
double external_detection_translation_y_
 
std::shared_ptr< PoseFilterfilter_
 
double docking_threshold_
 
std::string base_frame_id_
 
double staging_x_offset_
 
double staging_yaw_offset_
 
rclcpp_lifecycle::LifecycleNode::SharedPtr node_
 
std::shared_ptr< tf2_ros::Buffer > tf2_buffer_
 
- Protected Attributes inherited from opennav_docking_core::ChargingDock
std::string name_
 

Additional Inherited Members

- Public Types inherited from opennav_docking_core::NonChargingDock
using Ptr = std::shared_ptr< NonChargingDock >
 
- Public Types inherited from opennav_docking_core::ChargingDock
using Ptr = std::shared_ptr< ChargingDock >
 

Detailed Description

Definition at line 34 of file simple_non_charging_dock.hpp.

Member Function Documentation

◆ configure()

void opennav_docking::SimpleNonChargingDock::configure ( const rclcpp_lifecycle::LifecycleNode::WeakPtr &  parent,
const std::string &  name,
std::shared_ptr< tf2_ros::Buffer >  tf 
)
virtual
Parameters
parentpointer to user's node
nameThe name of this planner
tfA pointer to a TF buffer

Implements opennav_docking_core::NonChargingDock.

Definition at line 23 of file simple_non_charging_dock.cpp.

◆ getRefinedPose()

bool opennav_docking::SimpleNonChargingDock::getRefinedPose ( geometry_msgs::msg::PoseStamped &  pose,
std::string  id 
)
virtual

Method to obtain the refined pose of the dock, usually based on sensors.

Parameters
poseThe initial estimate of the dock pose.
frameThe frame of the initial estimate.

Implements opennav_docking_core::NonChargingDock.

Definition at line 151 of file simple_non_charging_dock.cpp.

◆ getStagingPose()

geometry_msgs::msg::PoseStamped opennav_docking::SimpleNonChargingDock::getStagingPose ( const geometry_msgs::msg::Pose &  pose,
const std::string &  frame 
)
virtual

Method to obtain the dock's staging pose. This method should likely be using TF and the dock's pose information to find the staging pose from a static or parameterized staging pose relative to the docking pose.

Parameters
poseDock with pose
frameDock's frame of pose
Returns
PoseStamped of staging pose in the specified frame

Implements opennav_docking_core::NonChargingDock.

Definition at line 123 of file simple_non_charging_dock.cpp.

◆ isDocked()

bool opennav_docking::SimpleNonChargingDock::isDocked ( )
virtual

Have we made contact with dock? This can be implemented in a variety of ways: by establishing communications with the dock, by monitoring the the drive motor efforts, etc.

NOTE: this function is expected to return QUICKLY. Blocking here will block the docking controller loop.

Implements opennav_docking_core::NonChargingDock.

Definition at line 220 of file simple_non_charging_dock.cpp.


The documentation for this class was generated from the following files: