Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
Implementation for IR/ultrasound range sensor source. More...
#include <nav2_collision_monitor/include/nav2_collision_monitor/range.hpp>
Public Member Functions | |
Range (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) | |
Range constructor. More... | |
~Range () | |
Range destructor. | |
void | configure () |
Data source configuration routine. Obtains ROS-parameters and creates range sensor subscriber. | |
bool | getData (const rclcpp::Time &curr_time, std::vector< Point > &data) |
Adds latest data from range sensor to the data array. More... | |
![]() | |
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. | |
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 (sensor_msgs::msg::Range::ConstSharedPtr msg) |
Range sensor data callback. More... | |
![]() | |
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 | |
rclcpp::Subscription< sensor_msgs::msg::Range >::SharedPtr | data_sub_ |
Range sensor data subscriber. | |
double | obstacles_angle_ |
Angle increment (in rad) between two obstacle points at the range arc. | |
sensor_msgs::msg::Range::ConstSharedPtr | data_ |
Latest data obtained from range sensor. | |
![]() | |
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. | |
nav2_collision_monitor::Range::Range | ( | 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 | ||
) |
Range 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 29 of file range.cpp.
References nav2_collision_monitor::Source::logger_, and nav2_collision_monitor::Source::source_name_.
|
protected |
|
virtual |
Adds latest data from range sensor to the data array.
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. |
Implements nav2_collision_monitor::Source.
Definition at line 70 of file range.cpp.
References data_, nav2_collision_monitor::Source::getTransform(), nav2_collision_monitor::Source::logger_, obstacles_angle_, nav2_collision_monitor::Source::source_name_, and nav2_collision_monitor::Source::sourceValid().
|
protected |
Getting sensor-specific ROS-parameters.
source_topic | Output name of source subscription topic |
Definition at line 131 of file range.cpp.
References nav2_collision_monitor::Source::getCommonParameters(), nav2_collision_monitor::Source::node_, obstacles_angle_, and nav2_collision_monitor::Source::source_name_.
Referenced by configure().