16 #include "nav2_collision_monitor/collision_detector_node.hpp"
22 #include "tf2_ros/create_timer_ros.hpp"
24 #include "nav2_ros_common/node_utils.hpp"
26 using namespace std::chrono_literals;
28 namespace nav2_collision_monitor
31 CollisionDetector::CollisionDetector(
const rclcpp::NodeOptions & options)
32 : nav2::LifecycleNode(
"collision_detector", options)
45 RCLCPP_INFO(get_logger(),
"Configuring");
48 tf_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
49 auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
50 this->get_node_base_interface(),
51 this->get_node_timers_interface());
52 tf_buffer_->setCreateTimerInterface(timer_interface);
55 state_pub_ = this->create_publisher<nav2_msgs::msg::CollisionDetectorState>(
56 "collision_detector_state");
59 "~/collision_points_marker");
64 return nav2::CallbackReturn::FAILURE;
67 return nav2::CallbackReturn::SUCCESS;
73 RCLCPP_INFO(get_logger(),
"Activating");
80 for (std::shared_ptr<Polygon> polygon :
polygons_) {
85 timer_ = this->create_timer(
86 std::chrono::duration<double>{1.0 /
frequency_},
92 return nav2::CallbackReturn::SUCCESS;
98 RCLCPP_INFO(get_logger(),
"Deactivating");
108 for (std::shared_ptr<Polygon> polygon :
polygons_) {
109 polygon->deactivate();
115 return nav2::CallbackReturn::SUCCESS;
121 RCLCPP_INFO(get_logger(),
"Cleaning up");
132 return nav2::CallbackReturn::SUCCESS;
138 RCLCPP_INFO(get_logger(),
"Shutting down");
139 return nav2::CallbackReturn::SUCCESS;
144 std::string base_frame_id, odom_frame_id;
145 tf2::Duration transform_tolerance;
146 rclcpp::Duration source_timeout(2.0, 0.0);
150 nav2::declare_parameter_if_not_declared(
151 node,
"frequency", rclcpp::ParameterValue(10.0));
152 frequency_ = get_parameter(
"frequency").as_double();
153 nav2::declare_parameter_if_not_declared(
154 node,
"base_frame_id", rclcpp::ParameterValue(
"base_footprint"));
155 base_frame_id = get_parameter(
"base_frame_id").as_string();
156 nav2::declare_parameter_if_not_declared(
157 node,
"odom_frame_id", rclcpp::ParameterValue(
"odom"));
158 odom_frame_id = get_parameter(
"odom_frame_id").as_string();
159 nav2::declare_parameter_if_not_declared(
160 node,
"transform_tolerance", rclcpp::ParameterValue(0.1));
161 transform_tolerance =
162 tf2::durationFromSec(get_parameter(
"transform_tolerance").as_double());
163 nav2::declare_parameter_if_not_declared(
164 node,
"source_timeout", rclcpp::ParameterValue(2.0));
166 rclcpp::Duration::from_seconds(get_parameter(
"source_timeout").as_double());
167 nav2::declare_parameter_if_not_declared(
168 node,
"base_shift_correction", rclcpp::ParameterValue(
true));
169 const bool base_shift_correction =
170 get_parameter(
"base_shift_correction").as_bool();
173 base_frame_id, odom_frame_id, transform_tolerance, source_timeout,
174 base_shift_correction))
187 const std::string & base_frame_id,
188 const tf2::Duration & transform_tolerance)
194 nav2::declare_parameter_if_not_declared(
195 node,
"polygons", rclcpp::PARAMETER_STRING_ARRAY);
196 std::vector<std::string> polygon_names = get_parameter(
"polygons").as_string_array();
197 for (std::string polygon_name : polygon_names) {
199 nav2::declare_parameter_if_not_declared(
200 node, polygon_name +
".type", rclcpp::PARAMETER_STRING);
201 const std::string polygon_type = get_parameter(polygon_name +
".type").as_string();
203 if (polygon_type ==
"polygon") {
205 std::make_shared<Polygon>(
206 node, polygon_name,
tf_buffer_, base_frame_id, transform_tolerance));
207 }
else if (polygon_type ==
"circle") {
209 std::make_shared<Circle>(
210 node, polygon_name,
tf_buffer_, base_frame_id, transform_tolerance));
211 }
else if (polygon_type ==
"velocity_polygon") {
213 std::make_shared<VelocityPolygon>(
214 node, polygon_name,
tf_buffer_, base_frame_id, transform_tolerance));
218 "[%s]: Unknown polygon type: %s",
219 polygon_name.c_str(), polygon_type.c_str());
229 auto action_type =
polygons_.back()->getActionType();
230 if (action_type != DO_NOTHING) {
233 "[%s]: The action_type of the polygon is different than \"none\" which is "
234 "not supported in the collision detector.",
235 polygon_name.c_str());
239 }
catch (
const std::exception & ex) {
240 RCLCPP_ERROR(get_logger(),
"Error while getting parameters: %s", ex.what());
248 const std::string & base_frame_id,
249 const std::string & odom_frame_id,
250 const tf2::Duration & transform_tolerance,
251 const rclcpp::Duration & source_timeout,
252 const bool base_shift_correction)
258 nav2::declare_parameter_if_not_declared(
259 node,
"observation_sources", rclcpp::PARAMETER_STRING_ARRAY);
260 std::vector<std::string> source_names = get_parameter(
"observation_sources").as_string_array();
261 for (std::string source_name : source_names) {
262 nav2::declare_parameter_if_not_declared(
263 node, source_name +
".type",
264 rclcpp::ParameterValue(
"scan"));
265 const std::string source_type = get_parameter(source_name +
".type").as_string();
267 if (source_type ==
"scan") {
268 std::shared_ptr<Scan> s = std::make_shared<Scan>(
269 node, source_name,
tf_buffer_, base_frame_id, odom_frame_id,
270 transform_tolerance, source_timeout, base_shift_correction);
275 }
else if (source_type ==
"pointcloud") {
276 std::shared_ptr<PointCloud> p = std::make_shared<PointCloud>(
277 node, source_name,
tf_buffer_, base_frame_id, odom_frame_id,
278 transform_tolerance, source_timeout, base_shift_correction);
283 }
else if (source_type ==
"range") {
284 std::shared_ptr<Range> r = std::make_shared<Range>(
285 node, source_name,
tf_buffer_, base_frame_id, odom_frame_id,
286 transform_tolerance, source_timeout, base_shift_correction);
291 }
else if (source_type ==
"polygon") {
292 std::shared_ptr<PolygonSource> ps = std::make_shared<PolygonSource>(
293 node, source_name,
tf_buffer_, base_frame_id, odom_frame_id,
294 transform_tolerance, source_timeout, base_shift_correction);
301 "[%s]: Unknown source type: %s",
302 source_name.c_str(), source_type.c_str());
306 }
catch (
const std::exception & ex) {
307 RCLCPP_ERROR(get_logger(),
"Error while getting parameters: %s", ex.what());
317 rclcpp::Time curr_time = this->now();
320 std::vector<Point> collision_points;
322 std::unique_ptr<nav2_msgs::msg::CollisionDetectorState> state_msg =
323 std::make_unique<nav2_msgs::msg::CollisionDetectorState>();
326 for (std::shared_ptr<Source> source :
sources_) {
327 if (source->getEnabled()) {
328 if (!source->getData(curr_time, collision_points) &&
329 source->getSourceTimeout().seconds() != 0.0)
333 "Invalid source %s detected."
334 " Either due to data not published yet, or to lack of new data received within the"
335 " sensor timeout, or if impossible to transform data to base frame",
336 source->getSourceName().c_str());
343 auto marker_array = std::make_unique<visualization_msgs::msg::MarkerArray>();
344 visualization_msgs::msg::Marker marker;
345 marker.header.frame_id = get_parameter(
"base_frame_id").as_string();
346 marker.header.stamp = rclcpp::Time(0, 0);
347 marker.ns =
"collision_points";
349 marker.type = visualization_msgs::msg::Marker::POINTS;
350 marker.action = visualization_msgs::msg::Marker::ADD;
351 marker.scale.x = 0.02;
352 marker.scale.y = 0.02;
353 marker.color.r = 1.0;
354 marker.color.a = 1.0;
355 marker.lifetime = rclcpp::Duration(0, 0);
356 marker.frame_locked =
true;
358 for (
const auto & point : collision_points) {
359 geometry_msgs::msg::Point p;
363 marker.points.push_back(p);
365 marker_array->markers.push_back(marker);
369 for (std::shared_ptr<Polygon> polygon :
polygons_) {
370 if (!polygon->getEnabled()) {
373 state_msg->polygons.push_back(polygon->getName());
374 state_msg->detections.push_back(
375 polygon->getPointsInside(
376 collision_points) >= polygon->getMinPoints());
387 for (std::shared_ptr<Polygon> polygon :
polygons_) {
388 if (polygon->getEnabled()) {
396 #include "rclcpp_components/register_node_macro.hpp"
void destroyBond()
Destroy bond connection to lifecycle manager.
nav2::LifecycleNode::SharedPtr shared_from_this()
Get a shared pointer of this.
void createBond()
Create bond connection to lifecycle manager.
Collision Monitor ROS2 node.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
: Activates LifecyclePublishers, polygons and main processor, creates bond connection
nav2::Publisher< visualization_msgs::msg::MarkerArray >::SharedPtr collision_points_marker_pub_
Collision points marker publisher.
bool getParameters()
Supporting routine obtaining all ROS-parameters.
bool configureSources(const std::string &base_frame_id, const std::string &odom_frame_id, const tf2::Duration &transform_tolerance, const rclcpp::Duration &source_timeout, const bool base_shift_correction)
Supporting routine creating and configuring all data sources.
void process()
Main processing routine.
void publishPolygons() const
Polygons publishing routine. Made for visualization.
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called in shutdown state.
nav2::Publisher< nav2_msgs::msg::CollisionDetectorState >::SharedPtr state_pub_
collision monitor state publisher
~CollisionDetector()
Destructor for the nav2_collision_monitor::CollisionDetector.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
: Resets all subscribers/publishers, polygons/data sources arrays
std::vector< std::shared_ptr< Source > > sources_
Data sources array.
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
TF buffer.
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
TF listener.
bool configurePolygons(const std::string &base_frame_id, const tf2::Duration &transform_tolerance)
Supporting routine creating and configuring all polygons.
rclcpp::TimerBase::SharedPtr timer_
timer that runs actions
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
: Deactivates LifecyclePublishers, polygons and main processor, destroys bond connection
double frequency_
main loop frequency
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
: Initializes and obtains ROS-parameters, creates main subscribers and publishers,...
std::vector< std::shared_ptr< Polygon > > polygons_
Polygons array.