15 #ifndef NAV2_WAYPOINT_FOLLOWER__PLUGINS__PHOTO_AT_WAYPOINT_HPP_
16 #define NAV2_WAYPOINT_FOLLOWER__PLUGINS__PHOTO_AT_WAYPOINT_HPP_
23 #include "rclcpp/rclcpp.hpp"
25 #include "sensor_msgs/msg/image.hpp"
26 #include "nav2_core/waypoint_task_executor.hpp"
27 #include "opencv2/core.hpp"
28 #include "opencv2/opencv.hpp"
29 #include "cv_bridge/cv_bridge.hpp"
30 #include "image_transport/image_transport.hpp"
33 namespace nav2_waypoint_follower
58 const nav2::LifecycleNode::WeakPtr & parent,
59 const std::string & plugin_name);
71 const geometry_msgs::msg::PoseStamped & curr_pose,
const int & curr_waypoint_index);
78 void imageCallback(
const sensor_msgs::msg::Image::SharedPtr msg);
86 static void deepCopyMsg2Mat(
const sensor_msgs::msg::Image::SharedPtr & msg, cv::Mat & mat);
90 std::mutex global_mutex_;
92 std::filesystem::path save_dir_;
94 std::string image_format_;
96 std::string image_topic_;
100 sensor_msgs::msg::Image::SharedPtr curr_frame_msg_;
102 rclcpp::Logger logger_{rclcpp::get_logger(
"nav2_waypoint_follower")};
104 nav2::Subscription<sensor_msgs::msg::Image>::SharedPtr camera_image_subscriber_;
Base class for creating a plugin in order to perform a specific task at waypoint arrivals.
bool processAtWaypoint(const geometry_msgs::msg::PoseStamped &curr_pose, const int &curr_waypoint_index)
Override this to define the body of your task that you would like to execute once the robot arrived t...
static void deepCopyMsg2Mat(const sensor_msgs::msg::Image::SharedPtr &msg, cv::Mat &mat)
given a shared pointer to sensor::msg::Image type, make a deep copy to inputted cv Mat
void initialize(const nav2::LifecycleNode::WeakPtr &parent, const std::string &plugin_name)
declares and loads parameters used
void imageCallback(const sensor_msgs::msg::Image::SharedPtr msg)
PhotoAtWaypoint()
Construct a new Photo At Waypoint object.
~PhotoAtWaypoint()
Destroy the Photo At Waypoint object.