Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
Public Member Functions | Static Public Member Functions | Protected Attributes | List of all members
nav2_waypoint_follower::PhotoAtWaypoint Class Reference
Inheritance diagram for nav2_waypoint_follower::PhotoAtWaypoint:
Inheritance graph
[legend]
Collaboration diagram for nav2_waypoint_follower::PhotoAtWaypoint:
Collaboration graph
[legend]

Public Member Functions

 PhotoAtWaypoint ()
 Construct a new Photo At Waypoint object.
 
 ~PhotoAtWaypoint ()
 Destroy the Photo At Waypoint object.
 
void initialize (const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, const std::string &plugin_name)
 declares and loads parameters used More...
 
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 to waypoint. More...
 
void imageCallback (const sensor_msgs::msg::Image::SharedPtr msg)
 
- Public Member Functions inherited from nav2_core::WaypointTaskExecutor
 WaypointTaskExecutor ()
 Construct a new Simple Task Execution At Waypoint Base object.
 
virtual ~WaypointTaskExecutor ()
 Destroy the Simple Task Execution At Waypoint Base object.
 

Static Public Member Functions

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 More...
 

Protected Attributes

std::mutex global_mutex_
 
std::filesystem::path save_dir_
 
std::string image_format_
 
std::string image_topic_
 
bool is_enabled_
 
sensor_msgs::msg::Image::SharedPtr curr_frame_msg_
 
rclcpp::Logger logger_ {rclcpp::get_logger("nav2_waypoint_follower")}
 
rclcpp::Subscription< sensor_msgs::msg::Image >::SharedPtr camera_image_subscriber_
 

Detailed Description

Definition at line 44 of file photo_at_waypoint.hpp.

Member Function Documentation

◆ deepCopyMsg2Mat()

void nav2_waypoint_follower::PhotoAtWaypoint::deepCopyMsg2Mat ( const sensor_msgs::msg::Image::SharedPtr &  msg,
cv::Mat &  mat 
)
static

given a shared pointer to sensor::msg::Image type, make a deep copy to inputted cv Mat

Parameters
msg
mat

Definition at line 144 of file photo_at_waypoint.cpp.

Referenced by processAtWaypoint().

Here is the caller graph for this function:

◆ imageCallback()

void nav2_waypoint_follower::PhotoAtWaypoint::imageCallback ( const sensor_msgs::msg::Image::SharedPtr  msg)
Parameters
msg

Definition at line 138 of file photo_at_waypoint.cpp.

Referenced by initialize().

Here is the caller graph for this function:

◆ initialize()

void nav2_waypoint_follower::PhotoAtWaypoint::initialize ( const rclcpp_lifecycle::LifecycleNode::WeakPtr &  parent,
const std::string &  plugin_name 
)
virtual

declares and loads parameters used

Parameters
parentparent node that plugin will be created within
plugin_nameshould be provided in nav2_params.yaml==> waypoint_follower

Implements nav2_core::WaypointTaskExecutor.

Definition at line 34 of file photo_at_waypoint.cpp.

References imageCallback().

Here is the call graph for this function:

◆ processAtWaypoint()

bool nav2_waypoint_follower::PhotoAtWaypoint::processAtWaypoint ( const geometry_msgs::msg::PoseStamped &  curr_pose,
const int &  curr_waypoint_index 
)
virtual

Override this to define the body of your task that you would like to execute once the robot arrived to waypoint.

Parameters
curr_posecurrent pose of the robot
curr_waypoint_indexcurrent waypoint, that robot just arrived
Returns
true if task execution was successful
false if task execution failed

Implements nav2_core::WaypointTaskExecutor.

Definition at line 101 of file photo_at_waypoint.cpp.

References deepCopyMsg2Mat().

Here is the call graph for this function:

The documentation for this class was generated from the following files: