Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
Basic data source class. More...
#include <nav2_collision_monitor/include/nav2_collision_monitor/source.hpp>
Public Member 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. More... | |
virtual | ~Source () |
Source destructor. | |
virtual bool | getData (const rclcpp::Time &curr_time, std::vector< Point > &data)=0 |
Adds latest data from source to the data array. Empty virtual method intended to be used in child implementations. More... | |
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 | |
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_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. | |
Basic data source class.
Definition at line 37 of file source.hpp.
nav2_collision_monitor::Source::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.
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 |
Definition at line 27 of file source.cpp.
|
protected |
Source configuration routine.
Definition at line 47 of file source.cpp.
References dyn_params_handler_, dynamicParametersCallback(), and node_.
Referenced by nav2_collision_monitor::PointCloud::configure(), nav2_collision_monitor::PolygonSource::configure(), nav2_collision_monitor::Range::configure(), and nav2_collision_monitor::Scan::configure().
|
protected |
Callback executed when a parameter change is detected.
event | ParameterEvent message |
Definition at line 116 of file source.cpp.
References enabled_, and source_name_.
Referenced by configure().
|
protected |
Supporting routine obtaining ROS-parameters common for all data sources.
source_topic | Output name of source subscription topic |
Definition at line 58 of file source.cpp.
References enabled_, node_, source_name_, and source_timeout_.
Referenced by nav2_collision_monitor::Scan::configure(), nav2_collision_monitor::PointCloud::getParameters(), nav2_collision_monitor::PolygonSource::getParameters(), and nav2_collision_monitor::Range::getParameters().
|
pure virtual |
Adds latest data from source to the data array. Empty virtual method intended to be used in child implementations.
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. |
Implemented in nav2_collision_monitor::Scan, nav2_collision_monitor::Range, nav2_collision_monitor::PolygonSource, and nav2_collision_monitor::PointCloud.
bool nav2_collision_monitor::Source::getEnabled | ( | ) | const |
Obtains source enabled state.
Definition at line 100 of file source.cpp.
References enabled_.
std::string nav2_collision_monitor::Source::getSourceName | ( | ) | const |
Obtains the name of the data source.
Definition at line 105 of file source.cpp.
References source_name_.
rclcpp::Duration nav2_collision_monitor::Source::getSourceTimeout | ( | ) | const |
Obtains the source_timeout parameter of the data source.
Definition at line 110 of file source.cpp.
References source_timeout_.
|
protected |
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.
curr_time | Current node time |
data_header | Current header which contains the frame_id and the stamp |
tf_transform | Output source->base_frame_id_ transform |
Definition at line 137 of file source.cpp.
References base_frame_id_, base_shift_correction_, global_frame_id_, tf_buffer_, and transform_tolerance_.
Referenced by nav2_collision_monitor::PointCloud::getData(), nav2_collision_monitor::Range::getData(), and nav2_collision_monitor::Scan::getData().
|
protected |
Checks whether the source data might be considered as valid.
source_time | Timestamp of latest obtained data |
curr_time | Current node time for source verification |
Definition at line 81 of file source.cpp.
References logger_, source_name_, and source_timeout_.
Referenced by nav2_collision_monitor::PointCloud::getData(), nav2_collision_monitor::Range::getData(), and nav2_collision_monitor::Scan::getData().