Class ImagePerceptionHandler

Inheritance Relationships

Base Type

Class Documentation

class ImagePerceptionHandler : public easynav::PerceptionHandler

Handles the creation and updating of ImagePerception instances from sensor_msgs::msg::Image messages.

This class provides methods to register subscriptions to image topics, decode incoming messages into cv::Mat using cv_bridge, and update target ImagePerception instances.

Public Functions

inline virtual std::string group() const override

Returns the group managed by this handler.

Returns:

The string literal “image”.

inline virtual std::shared_ptr<PerceptionBase> create(const std::string&) override

Creates a new empty ImagePerception instance.

Parameters:

sensor_id – Name or identifier of the sensor. Currently unused, reserved for future extensions.

Returns:

Shared pointer to a newly created ImagePerception.

virtual rclcpp::SubscriptionBase::SharedPtr create_subscription(rclcpp_lifecycle::LifecycleNode &node, const std::string &topic, const std::string &type, std::shared_ptr<PerceptionBase> target, rclcpp::CallbackGroup::SharedPtr cb_group) override

Creates a subscription to an image topic that updates a target ImagePerception.

The subscription receives sensor_msgs::msg::Image messages on topic, converts them to cv::Mat, fills ImagePerception::data, and updates inherited metadata (stamp, frame_id).

Parameters:
  • node – Lifecycle node used to create the subscription.

  • topic – Topic name to subscribe to.

  • type – ROS message type name. It must be “sensor_msgs/msg/Image”.

  • target – Shared pointer to the ImagePerception to be updated.

  • cb_group – Callback group for executor-level concurrency control.

Returns:

Shared pointer to the created subscription.