Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
photo_at_waypoint.cpp
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 #include "nav2_waypoint_follower/plugins/photo_at_waypoint.hpp"
16 
17 #include <string>
18 #include <memory>
19 
20 #include "pluginlib/class_list_macros.hpp"
21 
22 #include "nav2_util/node_utils.hpp"
23 
24 namespace nav2_waypoint_follower
25 {
27 {
28 }
29 
31 {
32 }
33 
35  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
36  const std::string & plugin_name)
37 {
38  auto node = parent.lock();
39 
40  curr_frame_msg_ = std::make_shared<sensor_msgs::msg::Image>();
41 
42  nav2_util::declare_parameter_if_not_declared(
43  node, plugin_name + ".enabled",
44  rclcpp::ParameterValue(true));
45  nav2_util::declare_parameter_if_not_declared(
46  node, plugin_name + ".image_topic",
47  rclcpp::ParameterValue("/camera/color/image_raw"));
48  nav2_util::declare_parameter_if_not_declared(
49  node, plugin_name + ".save_dir",
50  rclcpp::ParameterValue("/tmp/waypoint_images"));
51  nav2_util::declare_parameter_if_not_declared(
52  node, plugin_name + ".image_format",
53  rclcpp::ParameterValue("png"));
54 
55  std::string save_dir_as_string;
56  node->get_parameter(plugin_name + ".enabled", is_enabled_);
57  node->get_parameter(plugin_name + ".image_topic", image_topic_);
58  node->get_parameter(plugin_name + ".save_dir", save_dir_as_string);
59  node->get_parameter(plugin_name + ".image_format", image_format_);
60 
61  // get inputted save directory and make sure it exists, if not log and create it
62  save_dir_ = save_dir_as_string;
63  try {
64  if (!std::filesystem::exists(save_dir_)) {
65  RCLCPP_WARN(
66  logger_,
67  "Provided save directory for photo at waypoint plugin does not exist,"
68  "provided directory is: %s, the directory will be created automatically.",
69  save_dir_.c_str()
70  );
71  if (!std::filesystem::create_directory(save_dir_)) {
72  RCLCPP_ERROR(
73  logger_,
74  "Failed to create directory!: %s required by photo at waypoint plugin, "
75  "exiting the plugin with failure!",
76  save_dir_.c_str()
77  );
78  is_enabled_ = false;
79  }
80  }
81  } catch (const std::exception & e) {
82  RCLCPP_ERROR(
83  logger_, "Exception (%s) thrown while attempting to create image capture directory."
84  " This task executor is being disabled as it cannot save images.", e.what());
85  is_enabled_ = false;
86  }
87 
88  if (!is_enabled_) {
89  RCLCPP_INFO(
90  logger_, "Photo at waypoint plugin is disabled.");
91  } else {
92  RCLCPP_INFO(
93  logger_, "Initializing photo at waypoint plugin, subscribing to camera topic named; %s",
94  image_topic_.c_str());
95  camera_image_subscriber_ = node->create_subscription<sensor_msgs::msg::Image>(
96  image_topic_, rclcpp::SystemDefaultsQoS(),
97  std::bind(&PhotoAtWaypoint::imageCallback, this, std::placeholders::_1));
98  }
99 }
100 
102  const geometry_msgs::msg::PoseStamped & curr_pose, const int & curr_waypoint_index)
103 {
104  if (!is_enabled_) {
105  RCLCPP_WARN(
106  logger_,
107  "Photo at waypoint plugin is disabled. Not performing anything"
108  );
109  return true;
110  }
111  try {
112  // construct the full path to image filename
113  std::filesystem::path file_name = std::to_string(
114  curr_waypoint_index) + "_" +
115  std::to_string(curr_pose.header.stamp.sec) + "." + image_format_;
116  std::filesystem::path full_path_image_path = save_dir_ / file_name;
117 
118  // save the taken photo at this waypoint to given directory
119  std::lock_guard<std::mutex> guard(global_mutex_);
120  cv::Mat curr_frame_mat;
121  deepCopyMsg2Mat(curr_frame_msg_, curr_frame_mat);
122  cv::imwrite(full_path_image_path.c_str(), curr_frame_mat);
123  RCLCPP_INFO(
124  logger_,
125  "Photo has been taken sucessfully at waypoint %i", curr_waypoint_index);
126  } catch (const std::exception & e) {
127  RCLCPP_ERROR(
128  logger_,
129  "Couldn't take photo at waypoint %i! Caught exception: %s \n"
130  "Make sure that the image topic named: %s is valid and active!",
131  curr_waypoint_index,
132  e.what(), image_topic_.c_str());
133  return false;
134  }
135  return true;
136 }
137 
138 void PhotoAtWaypoint::imageCallback(const sensor_msgs::msg::Image::SharedPtr msg)
139 {
140  std::lock_guard<std::mutex> guard(global_mutex_);
141  curr_frame_msg_ = msg;
142 }
143 
145  const sensor_msgs::msg::Image::SharedPtr & msg,
146  cv::Mat & mat)
147 {
148  cv_bridge::CvImageConstPtr cv_bridge_ptr = cv_bridge::toCvShare(msg, msg->encoding);
149  cv::Mat frame = cv_bridge_ptr->image;
150  if (msg->encoding == "rgb8") {
151  cv::cvtColor(frame, frame, cv::COLOR_RGB2BGR);
152  }
153  frame.copyTo(mat);
154 }
155 
156 } // namespace nav2_waypoint_follower
157 PLUGINLIB_EXPORT_CLASS(
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.