Class PolygonSource

Inheritance Relationships

Base Type

Class Documentation

class PolygonSource : public nav2_collision_monitor::Source

Implementation for polygon source.

Public Functions

PolygonSource(const nav2_util::LifecycleNode::WeakPtr &node, const std::string &source_name, const std::shared_ptr<tf2_ros::Buffer> tf_buffer, const std::string &base_frame_id, const std::string &global_frame_id, const tf2::Duration &transform_tolerance, const rclcpp::Duration &source_timeout, const bool base_shift_correction)

PolygonSource constructor.

Parameters:
  • node – Collision Monitor node pointer

  • source_name – Name of data source

  • tf_buffer – Shared pointer to a TF buffer

  • base_frame_id – Robot base frame ID. The output data will be transformed into this frame.

  • global_frame_id – Global frame ID for correct transform calculation

  • transform_tolerance – Transform tolerance

  • source_timeout – Maximum time interval in which data is considered valid

  • base_shift_correction – Whether to correct source data towards to base frame movement, considering the difference between current time and latest source time

~PolygonSource()

PolygonSource destructor.

void configure()

Data source configuration routine. Obtains ROS-parameters and creates subscriber.

virtual bool getData(const rclcpp::Time &curr_time, std::vector<Point> &data)

Adds latest data from polygon source to the data array.

Parameters:
  • curr_time – Current node time for data interpolation

  • data – Array where the data from source to be added. Added data is transformed to base_frame_id_ coordinate system at curr_time.

Returns:

false if an invalid source should block the robot

void convertPolygonStampedToPoints(const geometry_msgs::msg::PolygonStamped &polygon, std::vector<Point> &data) const

Converts a PolygonInstanceStamped to a std::vector<Point>

Parameters:
  • polygon – Input Polygon to be converted

  • data – Output vector of Point

Protected Functions

void getParameters(std::string &source_topic)

Getting sensor-specific ROS-parameters.

Parameters:

source_topic – Output name of source subscription topic

void dataCallback(geometry_msgs::msg::PolygonInstanceStamped::ConstSharedPtr msg)

PolygonSource data callback.

Parameters:

msg – Shared pointer to PolygonSource message

Protected Attributes

rclcpp::Subscription<geometry_msgs::msg::PolygonInstanceStamped>::SharedPtr data_sub_

PolygonSource data subscriber.

std::vector<geometry_msgs::msg::PolygonInstanceStamped> data_

Latest data obtained.

double sampling_distance_

distance between sampled points on polygon edges