-
Notifications
You must be signed in to change notification settings - Fork 1.8k
nav2_way_point_follower; introduce photo at waypoint arrivals plugin #2041
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from all commits
9451abe
43c0e86
57da3ae
c4c92f7
8992cbd
db8ccd2
4cadb90
511e064
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,109 @@ | ||
| // Copyright (c) 2020 Fetullah Atas | ||
| // | ||
| // Licensed under the Apache License, Version 2.0 (the "License"); | ||
| // you may not use this file except in compliance with the License. | ||
| // You may obtain a copy of the License at | ||
| // | ||
| // http://www.apache.org/licenses/LICENSE-2.0 | ||
| // | ||
| // Unless required by applicable law or agreed to in writing, software | ||
| // distributed under the License is distributed on an "AS IS" BASIS, | ||
| // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
| // See the License for the specific language governing permissions and | ||
| // limitations under the License. | ||
|
|
||
| #ifndef NAV2_WAYPOINT_FOLLOWER__PLUGINS__PHOTO_AT_WAYPOINT_HPP_ | ||
| #define NAV2_WAYPOINT_FOLLOWER__PLUGINS__PHOTO_AT_WAYPOINT_HPP_ | ||
|
|
||
| #include <experimental/filesystem> | ||
| #include <mutex> | ||
| #include <string> | ||
| #include <exception> | ||
|
|
||
| #include "rclcpp/rclcpp.hpp" | ||
| #include "rclcpp_components/register_node_macro.hpp" | ||
|
|
||
| #include "sensor_msgs/msg/image.hpp" | ||
| #include "nav2_core/waypoint_task_executor.hpp" | ||
| #include "opencv4/opencv2/core.hpp" | ||
| #include "opencv4/opencv2/opencv.hpp" | ||
| #include "cv_bridge/cv_bridge.h" | ||
| #include "image_transport/image_transport.hpp" | ||
|
|
||
|
|
||
| namespace nav2_waypoint_follower | ||
| { | ||
|
|
||
| class PhotoAtWaypoint : public nav2_core::WaypointTaskExecutor | ||
| { | ||
| public: | ||
| /** | ||
| * @brief Construct a new Photo At Waypoint object | ||
| * | ||
| */ | ||
| PhotoAtWaypoint(); | ||
|
|
||
| /** | ||
| * @brief Destroy the Photo At Waypoint object | ||
| * | ||
| */ | ||
| ~PhotoAtWaypoint(); | ||
|
|
||
| /** | ||
| * @brief declares and loads parameters used | ||
| * | ||
| * @param parent parent node that plugin will be created within | ||
| * @param plugin_name should be provided in nav2_params.yaml==> waypoint_follower | ||
| */ | ||
| void initialize( | ||
| const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, | ||
| const std::string & plugin_name); | ||
|
|
||
|
|
||
| /** | ||
| * @brief Override this to define the body of your task that you would like to execute once the robot arrived to waypoint | ||
| * | ||
| * @param curr_pose current pose of the robot | ||
| * @param curr_waypoint_index current waypoint, that robot just arrived | ||
| * @return true if task execution was successful | ||
| * @return false if task execution failed | ||
| */ | ||
| bool processAtWaypoint( | ||
| const geometry_msgs::msg::PoseStamped & curr_pose, const int & curr_waypoint_index); | ||
|
|
||
| /** | ||
| * @brief | ||
| * | ||
| * @param msg | ||
| */ | ||
| void imageCallback(const sensor_msgs::msg::Image::SharedPtr msg); | ||
|
|
||
| /** | ||
| * @brief given a shared pointer to sensor::msg::Image type, make a deep copy to inputted cv Mat | ||
| * | ||
| * @param msg | ||
| * @param mat | ||
| */ | ||
| static void deepCopyMsg2Mat(const sensor_msgs::msg::Image::SharedPtr & msg, cv::Mat & mat); | ||
|
|
||
| protected: | ||
| // to ensure safety when accessing global var curr_frame_ | ||
| std::mutex global_mutex_; | ||
| // the taken photos will be saved under this directory | ||
| std::experimental::filesystem::path save_dir_; | ||
| // .png ? .jpg ? or some other well known format | ||
| std::string image_format_; | ||
| // the topic to subscribe in order capture a frame | ||
| std::string image_topic_; | ||
| // whether plugin is enabled | ||
| bool is_enabled_; | ||
| // current frame; | ||
| sensor_msgs::msg::Image::SharedPtr curr_frame_msg_; | ||
| // global logger | ||
| rclcpp::Logger logger_{rclcpp::get_logger("nav2_waypoint_follower")}; | ||
| // ros susbcriber to get camera image | ||
| rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr camera_image_subscriber_; | ||
| }; | ||
| } // namespace nav2_waypoint_follower | ||
|
|
||
| #endif // NAV2_WAYPOINT_FOLLOWER__PLUGINS__PHOTO_AT_WAYPOINT_HPP_ |
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,146 @@ | ||
| // Copyright (c) 2020 Fetullah Atas | ||
| // | ||
| // Licensed under the Apache License, Version 2.0 (the "License"); | ||
| // you may not use this file except in compliance with the License. | ||
| // You may obtain a copy of the License at | ||
| // | ||
| // http://www.apache.org/licenses/LICENSE-2.0 | ||
| // | ||
| // Unless required by applicable law or agreed to in writing, software | ||
| // distributed under the License is distributed on an "AS IS" BASIS, | ||
| // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
| // See the License for the specific language governing permissions and | ||
| // limitations under the License. | ||
|
|
||
| #include "nav2_waypoint_follower/plugins/photo_at_waypoint.hpp" | ||
| #include <pluginlib/class_list_macros.hpp> | ||
|
|
||
| #include <string> | ||
| #include <memory> | ||
|
|
||
|
|
||
| namespace nav2_waypoint_follower | ||
| { | ||
| PhotoAtWaypoint::PhotoAtWaypoint() | ||
| { | ||
| } | ||
|
|
||
| PhotoAtWaypoint::~PhotoAtWaypoint() | ||
| { | ||
| } | ||
|
|
||
| void PhotoAtWaypoint::initialize( | ||
| const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, | ||
| const std::string & plugin_name) | ||
| { | ||
| auto node = parent.lock(); | ||
|
|
||
| curr_frame_msg_ = std::make_shared<sensor_msgs::msg::Image>(); | ||
|
|
||
| node->declare_parameter(plugin_name + ".enabled", rclcpp::ParameterValue(true)); | ||
| node->declare_parameter( | ||
| plugin_name + ".image_topic", | ||
| rclcpp::ParameterValue("/camera/color/image_raw")); | ||
| node->declare_parameter( | ||
| plugin_name + ".save_dir", | ||
| rclcpp::ParameterValue("/tmp/waypoint_images")); | ||
| node->declare_parameter(plugin_name + ".image_format", rclcpp::ParameterValue("png")); | ||
|
|
||
| std::string save_dir_as_string; | ||
| node->get_parameter(plugin_name + ".enabled", is_enabled_); | ||
| node->get_parameter(plugin_name + ".image_topic", image_topic_); | ||
| node->get_parameter(plugin_name + ".save_dir", save_dir_as_string); | ||
| node->get_parameter(plugin_name + ".image_format", image_format_); | ||
|
|
||
| // get inputted save directory and make sure it exists, if not log and create it | ||
| save_dir_ = save_dir_as_string; | ||
| if (!std::experimental::filesystem::exists(save_dir_)) { | ||
| RCLCPP_WARN( | ||
| logger_, | ||
| "Provided save directory for photo at waypoint plugin does not exist," | ||
| "provided directory is: %s, the directory will be created automatically.", | ||
| save_dir_.c_str() | ||
| ); | ||
| if (!std::experimental::filesystem::create_directory(save_dir_)) { | ||
| RCLCPP_ERROR( | ||
| logger_, | ||
| "Failed to create directory!: %s required by photo at waypoint plugin, " | ||
| "exiting the plugin with failure!", | ||
| save_dir_.c_str() | ||
| ); | ||
| is_enabled_ = false; | ||
| } | ||
| } | ||
|
|
||
| if (!is_enabled_) { | ||
| RCLCPP_INFO( | ||
| logger_, "Photo at waypoint plugin is disabled."); | ||
| } else { | ||
| RCLCPP_INFO( | ||
| logger_, "Initializing photo at waypoint plugin, subscribing to camera topic named; %s", | ||
| image_topic_.c_str()); | ||
| camera_image_subscriber_ = node->create_subscription<sensor_msgs::msg::Image>( | ||
| image_topic_, rclcpp::SystemDefaultsQoS(), | ||
| std::bind(&PhotoAtWaypoint::imageCallback, this, std::placeholders::_1)); | ||
| } | ||
| } | ||
|
|
||
| bool PhotoAtWaypoint::processAtWaypoint( | ||
|
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Have you run tests to make sure this all works as expected and images are saved where you think they should be?
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. yes, here is a video where i do shelf inspection with this plugin;
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Oh very cool! This is a feature actually I was planning on highlighting at ROS World. If you had time in the next 24 hours, would you be open to creating a 1 minute (2-3x speed) video of your robot doing some inspection task and at the end showing an example image? I have something similar to this I made https://www.youtube.com/watch?v=u7b68kbf500 but I'd always rather use user-submitted videos! Timeframe is because I need to record tomorrow afternoon and submit by Monday 😆
Member
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Even if you can't do it in the next day, it would still be useful to have done for the tutorial either way!
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. No problem, at moment I cant do with the real robot though, only simulation
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Here is 4K video, it is 4X speed otherwise it would take more than a minute, |
||
| const geometry_msgs::msg::PoseStamped & curr_pose, const int & curr_waypoint_index) | ||
| { | ||
| if (!is_enabled_) { | ||
| RCLCPP_WARN( | ||
| logger_, | ||
| "Photo at waypoint plugin is disabled. Not performing anything" | ||
| ); | ||
| return true; | ||
| } | ||
| try { | ||
| // construct the full path to image filename | ||
| std::experimental::filesystem::path file_name = std::to_string( | ||
| curr_waypoint_index) + "_" + | ||
| std::to_string(curr_pose.header.stamp.sec) + "." + image_format_; | ||
| std::experimental::filesystem::path full_path_image_path = save_dir_ / file_name; | ||
|
|
||
| // save the taken photo at this waypoint to given directory | ||
| std::lock_guard<std::mutex> guard(global_mutex_); | ||
| cv::Mat curr_frame_mat; | ||
| deepCopyMsg2Mat(curr_frame_msg_, curr_frame_mat); | ||
| cv::imwrite(full_path_image_path.c_str(), curr_frame_mat); | ||
| RCLCPP_INFO( | ||
| logger_, | ||
| "Photo has been taken sucessfully at waypoint %i", curr_waypoint_index); | ||
| } catch (const std::exception & e) { | ||
|
jediofgever marked this conversation as resolved.
SteveMacenski marked this conversation as resolved.
|
||
| RCLCPP_ERROR( | ||
|
jediofgever marked this conversation as resolved.
|
||
| logger_, | ||
| "Couldn't take photo at waypoint %i! Caught exception: %s \n" | ||
| "Make sure that the image topic named: %s is valid and active!", | ||
| curr_waypoint_index, | ||
| e.what(), image_topic_.c_str()); | ||
| return false; | ||
| } | ||
| return true; | ||
| } | ||
|
|
||
| void PhotoAtWaypoint::imageCallback(const sensor_msgs::msg::Image::SharedPtr msg) | ||
| { | ||
| std::lock_guard<std::mutex> guard(global_mutex_); | ||
| curr_frame_msg_ = msg; | ||
| } | ||
|
|
||
| void PhotoAtWaypoint::deepCopyMsg2Mat( | ||
| const sensor_msgs::msg::Image::SharedPtr & msg, | ||
| cv::Mat & mat) | ||
| { | ||
| cv_bridge::CvImageConstPtr cv_bridge_ptr = cv_bridge::toCvShare(msg, msg->encoding); | ||
|
jediofgever marked this conversation as resolved.
|
||
| cv::Mat frame = cv_bridge_ptr->image; | ||
| if (msg->encoding == "rgb8") { | ||
| cv::cvtColor(frame, frame, cv::COLOR_RGB2BGR); | ||
| } | ||
| frame.copyTo(mat); | ||
| } | ||
|
|
||
| } // namespace nav2_waypoint_follower | ||
| PLUGINLIB_EXPORT_CLASS( | ||
| nav2_waypoint_follower::PhotoAtWaypoint, | ||
| nav2_core::WaypointTaskExecutor) | ||
Uh oh!
There was an error while loading. Please reload this page.