Class PhotoAtWaypoint

Inheritance Relationships

Base Type

  • public nav2_core::WaypointTaskExecutor

Class Documentation

class PhotoAtWaypoint : public nav2_core::WaypointTaskExecutor

Public Functions

PhotoAtWaypoint()

Construct a new Photo At Waypoint object.

~PhotoAtWaypoint()

Destroy the Photo At Waypoint object.

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

declares and loads parameters used

Parameters:
  • parent – parent node that plugin will be created within

  • plugin_name – should be provided in nav2_params.yaml==> waypoint_follower

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

Parameters:
  • curr_pose – current pose of the robot

  • curr_waypoint_index – current waypoint, that robot just arrived

Returns:

true if task execution was successful

Returns:

false if task execution failed

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

msg

Public Static 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

Parameters:
  • msg

  • mat

Protected Attributes

std::mutex global_mutex_
std::experimental::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_