15 #include "nav2_collision_monitor/range.hpp"
21 #include "tf2/transform_datatypes.hpp"
23 #include "nav2_ros_common/node_utils.hpp"
24 #include "nav2_util/robot_utils.hpp"
26 namespace nav2_collision_monitor
30 const nav2::LifecycleNode::WeakPtr & node,
31 const std::string & source_name,
32 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
33 const std::string & base_frame_id,
34 const std::string & global_frame_id,
35 const tf2::Duration & transform_tolerance,
36 const rclcpp::Duration & source_timeout,
37 const bool base_shift_correction)
39 node, source_name, tf_buffer, base_frame_id, global_frame_id,
40 transform_tolerance, source_timeout, base_shift_correction),
55 auto node =
node_.lock();
57 throw std::runtime_error{
"Failed to lock node"};
60 std::string source_topic;
64 data_sub_ = node->create_subscription<sensor_msgs::msg::Range>(
71 const rclcpp::Time & curr_time,
72 std::vector<Point> & data)
76 if (
data_ ==
nullptr) {
87 "[%s]: Data range %fm is out of {%f..%f} sensor span. Ignoring...",
92 tf2::Transform tf_transform;
100 angle = -
data_->field_of_view / 2;
101 angle < data_->field_of_view / 2;
106 data_->range * std::cos(angle),
107 data_->range * std::sin(angle),
109 tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
112 data.push_back({p_v3_b.x(), p_v3_b.y()});
116 angle =
data_->field_of_view / 2;
120 data_->range * std::cos(angle),
121 data_->range * std::sin(angle),
123 tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
126 data.push_back({p_v3_b.x(), p_v3_b.y()});
133 auto node =
node_.lock();
135 throw std::runtime_error{
"Failed to lock node"};
140 nav2::declare_parameter_if_not_declared(
141 node,
source_name_ +
".obstacles_angle", rclcpp::ParameterValue(M_PI / 180));
A QoS profile for best-effort sensor data with a history of 10 messages.
Range(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)
Range constructor.
bool getData(const rclcpp::Time &curr_time, std::vector< Point > &data)
Adds latest data from range sensor to the data array.
sensor_msgs::msg::Range::ConstSharedPtr data_
Latest data obtained from range sensor.
void configure()
Data source configuration routine. Obtains ROS-parameters and creates range sensor subscriber.
void dataCallback(sensor_msgs::msg::Range::ConstSharedPtr msg)
Range sensor data callback.
~Range()
Range destructor.
nav2::Subscription< sensor_msgs::msg::Range >::SharedPtr data_sub_
Range sensor data subscriber.
void getParameters(std::string &source_topic)
Getting sensor-specific ROS-parameters.
double obstacles_angle_
Angle increment (in rad) between two obstacle points at the range arc.
nav2::LifecycleNode::WeakPtr node_
Collision Monitor node.
rclcpp::Logger logger_
Collision monitor node logger stored for further usage.
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 a...
void getCommonParameters(std::string &source_topic)
Supporting routine obtaining ROS-parameters common for all data sources.
bool configure()
Source configuration routine.
std::string source_name_
Name of data source.
bool sourceValid(const rclcpp::Time &source_time, const rclcpp::Time &curr_time) const
Checks whether the source data might be considered as valid.