Class Source

Inheritance Relationships

Derived Types

Class Documentation

class Source

Basic data source class.

Subclassed by nav2_collision_monitor::PointCloud, nav2_collision_monitor::Range, nav2_collision_monitor::Scan

Public Functions

Source(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)

Source 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

virtual ~Source()

Source destructor.

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

Adds latest data from source to the data array. Empty virtual method intended to be used in child implementations.

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.

bool getEnabled() const

Obtains source enabled state.

Returns:

Whether source is enabled

Protected Functions

bool configure()

Source configuration routine.

Returns:

True in case of everything is configured correctly, or false otherwise

void getCommonParameters(std::string &source_topic)

Supporting routine obtaining ROS-parameters common for all data sources.

Parameters:

source_topic – Output name of source subscription topic

bool sourceValid(const rclcpp::Time &source_time, const rclcpp::Time &curr_time) const

Checks whether the source data might be considered as valid.

Parameters:
  • source_time – Timestamp of latest obtained data

  • curr_time – Current node time for source verification

Returns:

True if data source is valid, otherwise false

rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)

Callback executed when a parameter change is detected.

Parameters:

event – ParameterEvent message

Protected Attributes

nav2_util::LifecycleNode::WeakPtr node_

Collision Monitor node.

rclcpp::Logger logger_ = {rclcpp::get_logger("collision_monitor")}

Collision monitor node logger stored for further usage.

rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_

Dynamic parameters handler.

std::string source_name_

Name of data source.

std::shared_ptr<tf2_ros::Buffer> tf_buffer_

TF buffer.

std::string base_frame_id_

Robot base frame ID.

std::string global_frame_id_

Global frame ID for correct transform calculation.

tf2::Duration transform_tolerance_

Transform tolerance.

rclcpp::Duration source_timeout_

Maximum time interval in which data is considered valid.

bool base_shift_correction_

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

bool enabled_

Whether source is enabled.