15 #ifndef OPENNAV_DOCKING__SIMPLE_NON_CHARGING_DOCK_HPP_
16 #define OPENNAV_DOCKING__SIMPLE_NON_CHARGING_DOCK_HPP_
22 #include "geometry_msgs/msg/pose_stamped.hpp"
23 #include "sensor_msgs/msg/battery_state.hpp"
24 #include "sensor_msgs/msg/joint_state.hpp"
25 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
26 #include "tf2/utils.hpp"
27 #include "nav2_ros_common/lifecycle_node.hpp"
29 #include "opennav_docking_core/non_charging_dock.hpp"
30 #include "opennav_docking/pose_filter.hpp"
32 namespace opennav_docking
51 const nav2::LifecycleNode::WeakPtr & parent,
52 const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf);
78 const geometry_msgs::msg::Pose & pose,
const std::string & frame);
85 virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped & pose, std::string
id);
93 void jointStateCallback(
const sensor_msgs::msg::JointState::SharedPtr state);
96 nav2::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_sub_;
97 rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_pub_;
98 rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr filtered_dock_pose_pub_;
99 rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr staging_pose_pub_;
101 geometry_msgs::msg::PoseStamped detected_dock_pose_;
104 geometry_msgs::msg::PoseStamped dock_pose_;
107 nav2::Subscription<sensor_msgs::msg::JointState>::SharedPtr joint_state_sub_;
108 std::vector<std::string> stall_joint_names_;
109 double stall_velocity_threshold_, stall_effort_threshold_;
113 bool use_external_detection_pose_;
114 double external_detection_timeout_;
115 tf2::Quaternion external_detection_rotation_;
116 double external_detection_translation_x_;
117 double external_detection_translation_y_;
120 std::shared_ptr<PoseFilter> filter_;
123 double docking_threshold_;
124 std::string base_frame_id_;
126 double staging_x_offset_;
127 double staging_yaw_offset_;
129 nav2::LifecycleNode::SharedPtr node_;
130 std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
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 i...
virtual void configure(const nav2::LifecycleNode::WeakPtr &parent, const std::string &name, std::shared_ptr< tf2_ros::Buffer > tf)
virtual bool isDocked()
Have we made contact with dock? This can be implemented in a variety of ways: by establishing communi...
virtual void activate()
Method to active Behavior and any threads involved in execution.
SimpleNonChargingDock()
Constructor.
virtual void deactivate()
Method to deactivate Behavior and any threads involved in execution.
virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped &pose, std::string id)
Method to obtain the refined pose of the dock, usually based on sensors.
virtual void cleanup()
Method to cleanup resources used on shutdown.
Abstract interface for a non-charging dock for the docking framework.