Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
photo_at_waypoint.hpp
1 // Copyright (c) 2020 Fetullah Atas
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_WAYPOINT_FOLLOWER__PLUGINS__PHOTO_AT_WAYPOINT_HPP_
16 #define NAV2_WAYPOINT_FOLLOWER__PLUGINS__PHOTO_AT_WAYPOINT_HPP_
17 
18 #include <filesystem>
19 #include <mutex>
20 #include <string>
21 #include <exception>
22 
23 #include "rclcpp/rclcpp.hpp"
24 
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"
31 
32 
33 namespace nav2_waypoint_follower
34 {
35 
37 {
38 public:
44 
50 
57  void initialize(
58  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
59  const std::string & plugin_name);
60 
61 
70  bool processAtWaypoint(
71  const geometry_msgs::msg::PoseStamped & curr_pose, const int & curr_waypoint_index);
72 
78  void imageCallback(const sensor_msgs::msg::Image::SharedPtr msg);
79 
86  static void deepCopyMsg2Mat(const sensor_msgs::msg::Image::SharedPtr & msg, cv::Mat & mat);
87 
88 protected:
89  // to ensure safety when accessing global var curr_frame_
90  std::mutex global_mutex_;
91  // the taken photos will be saved under this directory
92  std::filesystem::path save_dir_;
93  // .png ? .jpg ? or some other well known format
94  std::string image_format_;
95  // the topic to subscribe in order capture a frame
96  std::string image_topic_;
97  // whether plugin is enabled
98  bool is_enabled_;
99  // current frame;
100  sensor_msgs::msg::Image::SharedPtr curr_frame_msg_;
101  // global logger
102  rclcpp::Logger logger_{rclcpp::get_logger("nav2_waypoint_follower")};
103  // ros subscriber to get camera image
104  rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr camera_image_subscriber_;
105 };
106 } // namespace nav2_waypoint_follower
107 
108 #endif // NAV2_WAYPOINT_FOLLOWER__PLUGINS__PHOTO_AT_WAYPOINT_HPP_
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 rclcpp_lifecycle::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.