Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_collision_monitor::PolygonSource Class Reference

Implementation for polygon source. More...

#include <nav2_collision_monitor/include/nav2_collision_monitor/polygon_source.hpp>

Inheritance diagram for nav2_collision_monitor::PolygonSource:
Inheritance graph
[legend]
Collaboration diagram for nav2_collision_monitor::PolygonSource:
Collaboration graph
[legend]

Public Member Functions

 PolygonSource (const nav2::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. More...
 
 ~PolygonSource ()
 PolygonSource destructor.
 
void configure ()
 Data source configuration routine. Obtains ROS-parameters and creates subscriber.
 
bool getData (const rclcpp::Time &curr_time, std::vector< Point > &data)
 Adds latest data from polygon source to the data array. More...
 
void convertPolygonStampedToPoints (const geometry_msgs::msg::PolygonStamped &polygon, std::vector< Point > &data) const
 Converts a PolygonInstanceStamped to a std::vector<Point> More...
 
- Public Member Functions inherited from nav2_collision_monitor::Source
 Source (const nav2::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. More...
 
virtual ~Source ()
 Source destructor.
 
bool getEnabled () const
 Obtains source enabled state. More...
 
std::string getSourceName () const
 Obtains the name of the data source. More...
 
rclcpp::Duration getSourceTimeout () const
 Obtains the source_timeout parameter of the data source. More...
 

Protected Member Functions

void getParameters (std::string &source_topic)
 Getting sensor-specific ROS-parameters. More...
 
void dataCallback (geometry_msgs::msg::PolygonInstanceStamped::ConstSharedPtr msg)
 PolygonSource data callback. More...
 
- Protected Member Functions inherited from nav2_collision_monitor::Source
bool configure ()
 Source configuration routine. More...
 
void getCommonParameters (std::string &source_topic)
 Supporting routine obtaining ROS-parameters common for all data sources. More...
 
bool sourceValid (const rclcpp::Time &source_time, const rclcpp::Time &curr_time) const
 Checks whether the source data might be considered as valid. More...
 
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback (std::vector< rclcpp::Parameter > parameters)
 Callback executed when a parameter change is detected. More...
 
bool getTransform (const rclcpp::Time &curr_time, const std_msgs::msg::Header &data_header, tf2::Transform &tf_transform) const
 Obtain the transform to get data from source frame and time where it was received to the base frame and current time (if base_shift_correction_ is true) or the transform without time shift considered which is less accurate but much more faster option not dependent on state estimation frames. More...
 

Protected Attributes

nav2::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
 
- Protected Attributes inherited from nav2_collision_monitor::Source
nav2::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.
 

Detailed Description

Implementation for polygon source.

Definition at line 33 of file polygon_source.hpp.

Constructor & Destructor Documentation

◆ PolygonSource()

nav2_collision_monitor::PolygonSource::PolygonSource ( const nav2::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
nodeCollision Monitor node pointer
source_nameName of data source
tf_bufferShared pointer to a TF buffer
base_frame_idRobot base frame ID. The output data will be transformed into this frame.
global_frame_idGlobal frame ID for correct transform calculation
transform_toleranceTransform tolerance
source_timeoutMaximum time interval in which data is considered valid
base_shift_correctionWhether to correct source data towards to base frame movement, considering the difference between current time and latest source time

Definition at line 30 of file polygon_source.cpp.

Member Function Documentation

◆ convertPolygonStampedToPoints()

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

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

Parameters
polygonInput Polygon to be converted
dataOutput vector of Point

Definition at line 121 of file polygon_source.cpp.

References sampling_distance_.

Referenced by getData().

Here is the caller graph for this function:

◆ dataCallback()

void nav2_collision_monitor::PolygonSource::dataCallback ( geometry_msgs::msg::PolygonInstanceStamped::ConstSharedPtr  msg)
protected

PolygonSource data callback.

Parameters
msgShared pointer to PolygonSource message

Definition at line 168 of file polygon_source.cpp.

References data_, and nav2_collision_monitor::Source::node_.

Referenced by configure().

Here is the caller graph for this function:

◆ getData()

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

Adds latest data from polygon source to the data array.

Parameters
curr_timeCurrent node time for data interpolation
dataArray 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

Implements nav2_collision_monitor::Source.

Definition at line 68 of file polygon_source.cpp.

References nav2_collision_monitor::Source::base_frame_id_, nav2_collision_monitor::Source::base_shift_correction_, convertPolygonStampedToPoints(), data_, nav2_collision_monitor::Source::global_frame_id_, nav2_collision_monitor::Source::tf_buffer_, and nav2_collision_monitor::Source::transform_tolerance_.

Here is the call graph for this function:

◆ getParameters()

void nav2_collision_monitor::PolygonSource::getParameters ( std::string &  source_topic)
protected

Getting sensor-specific ROS-parameters.

Parameters
source_topicOutput name of source subscription topic

Definition at line 154 of file polygon_source.cpp.

References nav2_collision_monitor::Source::getCommonParameters(), nav2_collision_monitor::Source::node_, sampling_distance_, and nav2_collision_monitor::Source::source_name_.

Referenced by configure().

Here is the call graph for this function:
Here is the caller graph for this function:

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