15 #ifndef OPENNAV_DOCKING__SIMPLE_NON_CHARGING_DOCK_HPP_
16 #define OPENNAV_DOCKING__SIMPLE_NON_CHARGING_DOCK_HPP_
22 #include "std_srvs/srv/trigger.hpp"
23 #include "geometry_msgs/msg/pose_stamped.hpp"
24 #include "sensor_msgs/msg/battery_state.hpp"
25 #include "sensor_msgs/msg/joint_state.hpp"
26 #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
27 #include "tf2/utils.hpp"
28 #include "nav2_ros_common/lifecycle_node.hpp"
30 #include "opennav_docking_core/non_charging_dock.hpp"
31 #include "opennav_docking/pose_filter.hpp"
33 namespace opennav_docking
52 const nav2::LifecycleNode::WeakPtr & parent,
53 const std::string & name, std::shared_ptr<tf2_ros::Buffer> tf);
79 const geometry_msgs::msg::Pose & pose,
const std::string & frame);
86 virtual bool getRefinedPose(geometry_msgs::msg::PoseStamped & pose, std::string
id);
104 void jointStateCallback(
const sensor_msgs::msg::JointState::SharedPtr state);
107 nav2::Subscription<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_sub_;
108 nav2::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr dock_pose_pub_;
109 nav2::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr filtered_dock_pose_pub_;
110 nav2::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr staging_pose_pub_;
112 geometry_msgs::msg::PoseStamped detected_dock_pose_;
115 geometry_msgs::msg::PoseStamped dock_pose_;
118 nav2::Subscription<sensor_msgs::msg::JointState>::SharedPtr joint_state_sub_;
119 std::vector<std::string> stall_joint_names_;
120 double stall_velocity_threshold_, stall_effort_threshold_;
124 bool use_external_detection_pose_;
125 double external_detection_timeout_;
126 tf2::Quaternion external_detection_rotation_;
127 double external_detection_translation_x_;
128 double external_detection_translation_y_;
131 std::shared_ptr<PoseFilter> filter_;
134 double docking_threshold_;
135 std::string base_frame_id_;
137 double staging_x_offset_;
138 double staging_yaw_offset_;
140 nav2::LifecycleNode::SharedPtr node_;
141 std::shared_ptr<tf2_ros::Buffer> tf2_buffer_;
144 std::string detector_service_name_;
145 double detector_service_timeout_{5.0};
146 bool subscribe_toggle_{
false};
149 nav2::ServiceClient<std_srvs::srv::Trigger>::SharedPtr detector_client_;
152 bool detection_active_{
false};
153 bool initial_pose_received_{
false};
bool stopDetectionProcess() override
Stop external detection process.
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...
bool startDetectionProcess() override
Start external detection process (service call + subscribe).
SimpleNonChargingDock()
Constructor.
void cleanup() override
Method to cleanup resources used on shutdown.
void activate() override
Method to active 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.
void deactivate() override
Method to deactivate Behavior and any threads involved in execution.
Abstract interface for a non-charging dock for the docking framework.