forked from ros-navigation/navigation2
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathcollision_monitor_node.cpp
473 lines (392 loc) · 14.9 KB
/
collision_monitor_node.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
// Copyright (c) 2022 Samsung Research Russia
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "nav2_collision_monitor/collision_monitor_node.hpp"
#include <exception>
#include <utility>
#include <functional>
#include "tf2_ros/create_timer_ros.h"
#include "nav2_util/node_utils.hpp"
#include "nav2_collision_monitor/kinematics.hpp"
namespace nav2_collision_monitor
{
CollisionMonitor::CollisionMonitor(const rclcpp::NodeOptions & options)
: nav2_util::LifecycleNode("collision_monitor", "", options),
process_active_(false), robot_action_prev_{DO_NOTHING, {-1.0, -1.0, -1.0}},
stop_stamp_{0, 0, get_clock()->get_clock_type()}, stop_pub_timeout_(1.0, 0.0)
{
}
CollisionMonitor::~CollisionMonitor()
{
polygons_.clear();
sources_.clear();
}
nav2_util::CallbackReturn
CollisionMonitor::on_configure(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Configuring");
// Transform buffer and listener initialization
tf_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
this->get_node_base_interface(),
this->get_node_timers_interface());
tf_buffer_->setCreateTimerInterface(timer_interface);
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
std::string cmd_vel_in_topic;
std::string cmd_vel_out_topic;
// Obtaining ROS parameters
if (!getParameters(cmd_vel_in_topic, cmd_vel_out_topic)) {
return nav2_util::CallbackReturn::FAILURE;
}
cmd_vel_in_sub_ = this->create_subscription<geometry_msgs::msg::Twist>(
cmd_vel_in_topic, 1,
std::bind(&CollisionMonitor::cmdVelInCallback, this, std::placeholders::_1));
cmd_vel_out_pub_ = this->create_publisher<geometry_msgs::msg::Twist>(
cmd_vel_out_topic, 1);
return nav2_util::CallbackReturn::SUCCESS;
}
nav2_util::CallbackReturn
CollisionMonitor::on_activate(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Activating");
// Activating lifecycle publisher
cmd_vel_out_pub_->on_activate();
// Activating polygons
for (std::shared_ptr<Polygon> polygon : polygons_) {
polygon->activate();
}
// Since polygons are being published when cmd_vel_in appears,
// we need to publish polygons first time to display them at startup
publishPolygons();
// Activating main worker
process_active_ = true;
// Creating bond connection
createBond();
return nav2_util::CallbackReturn::SUCCESS;
}
nav2_util::CallbackReturn
CollisionMonitor::on_deactivate(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Deactivating");
// Deactivating main worker
process_active_ = false;
// Reset action type to default after worker deactivating
robot_action_prev_ = {DO_NOTHING, {-1.0, -1.0, -1.0}};
// Deactivating polygons
for (std::shared_ptr<Polygon> polygon : polygons_) {
polygon->deactivate();
}
// Deactivating lifecycle publishers
cmd_vel_out_pub_->on_deactivate();
// Destroying bond connection
destroyBond();
return nav2_util::CallbackReturn::SUCCESS;
}
nav2_util::CallbackReturn
CollisionMonitor::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Cleaning up");
cmd_vel_in_sub_.reset();
cmd_vel_out_pub_.reset();
polygons_.clear();
sources_.clear();
tf_listener_.reset();
tf_buffer_.reset();
return nav2_util::CallbackReturn::SUCCESS;
}
nav2_util::CallbackReturn
CollisionMonitor::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
{
RCLCPP_INFO(get_logger(), "Shutting down");
return nav2_util::CallbackReturn::SUCCESS;
}
void CollisionMonitor::cmdVelInCallback(geometry_msgs::msg::Twist::ConstSharedPtr msg)
{
process({msg->linear.x, msg->linear.y, msg->angular.z});
}
void CollisionMonitor::publishVelocity(const Action & robot_action)
{
if (robot_action.req_vel.isZero()) {
if (!robot_action_prev_.req_vel.isZero()) {
// Robot just stopped: saving stop timestamp and continue
stop_stamp_ = this->now();
} else if (this->now() - stop_stamp_ > stop_pub_timeout_) {
// More than stop_pub_timeout_ passed after robot has been stopped.
// Cease publishing output cmd_vel.
return;
}
}
std::unique_ptr<geometry_msgs::msg::Twist> cmd_vel_out_msg =
std::make_unique<geometry_msgs::msg::Twist>();
cmd_vel_out_msg->linear.x = robot_action.req_vel.x;
cmd_vel_out_msg->linear.y = robot_action.req_vel.y;
cmd_vel_out_msg->angular.z = robot_action.req_vel.tw;
// linear.z, angular.x and angular.y will remain 0.0
cmd_vel_out_pub_->publish(std::move(cmd_vel_out_msg));
}
bool CollisionMonitor::getParameters(
std::string & cmd_vel_in_topic,
std::string & cmd_vel_out_topic)
{
std::string base_frame_id, odom_frame_id;
tf2::Duration transform_tolerance;
rclcpp::Duration source_timeout(2.0, 0.0);
auto node = shared_from_this();
nav2_util::declare_parameter_if_not_declared(
node, "cmd_vel_in_topic", rclcpp::ParameterValue("cmd_vel_raw"));
cmd_vel_in_topic = get_parameter("cmd_vel_in_topic").as_string();
nav2_util::declare_parameter_if_not_declared(
node, "cmd_vel_out_topic", rclcpp::ParameterValue("cmd_vel"));
cmd_vel_out_topic = get_parameter("cmd_vel_out_topic").as_string();
nav2_util::declare_parameter_if_not_declared(
node, "base_frame_id", rclcpp::ParameterValue("base_footprint"));
base_frame_id = get_parameter("base_frame_id").as_string();
nav2_util::declare_parameter_if_not_declared(
node, "odom_frame_id", rclcpp::ParameterValue("odom"));
odom_frame_id = get_parameter("odom_frame_id").as_string();
nav2_util::declare_parameter_if_not_declared(
node, "transform_tolerance", rclcpp::ParameterValue(0.1));
transform_tolerance =
tf2::durationFromSec(get_parameter("transform_tolerance").as_double());
nav2_util::declare_parameter_if_not_declared(
node, "source_timeout", rclcpp::ParameterValue(2.0));
source_timeout =
rclcpp::Duration::from_seconds(get_parameter("source_timeout").as_double());
nav2_util::declare_parameter_if_not_declared(
node, "stop_pub_timeout", rclcpp::ParameterValue(1.0));
stop_pub_timeout_ =
rclcpp::Duration::from_seconds(get_parameter("stop_pub_timeout").as_double());
if (!configurePolygons(base_frame_id, transform_tolerance)) {
return false;
}
if (!configureSources(base_frame_id, odom_frame_id, transform_tolerance, source_timeout)) {
return false;
}
return true;
}
bool CollisionMonitor::configurePolygons(
const std::string & base_frame_id,
const tf2::Duration & transform_tolerance)
{
try {
auto node = shared_from_this();
nav2_util::declare_parameter_if_not_declared(
node, "polygons", rclcpp::ParameterValue(std::vector<std::string>()));
std::vector<std::string> polygon_names = get_parameter("polygons").as_string_array();
for (std::string polygon_name : polygon_names) {
// Leave it not initialized: the will cause an error if it will not set
nav2_util::declare_parameter_if_not_declared(
node, polygon_name + ".type", rclcpp::PARAMETER_STRING);
const std::string polygon_type = get_parameter(polygon_name + ".type").as_string();
if (polygon_type == "polygon") {
polygons_.push_back(
std::make_shared<Polygon>(
node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
} else if (polygon_type == "circle") {
polygons_.push_back(
std::make_shared<Circle>(
node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
} else { // Error if something else
RCLCPP_ERROR(
get_logger(),
"[%s]: Unknown polygon type: %s",
polygon_name.c_str(), polygon_type.c_str());
return false;
}
// Configure last added polygon
if (!polygons_.back()->configure()) {
return false;
}
}
} catch (const std::exception & ex) {
RCLCPP_ERROR(get_logger(), "Error while getting parameters: %s", ex.what());
return false;
}
return true;
}
bool CollisionMonitor::configureSources(
const std::string & base_frame_id,
const std::string & odom_frame_id,
const tf2::Duration & transform_tolerance,
const rclcpp::Duration & source_timeout)
{
try {
auto node = shared_from_this();
// Leave it to be not initialized: to intentionally cause an error if it will not set
nav2_util::declare_parameter_if_not_declared(
node, "observation_sources", rclcpp::PARAMETER_STRING_ARRAY);
std::vector<std::string> source_names = get_parameter("observation_sources").as_string_array();
for (std::string source_name : source_names) {
nav2_util::declare_parameter_if_not_declared(
node, source_name + ".type",
rclcpp::ParameterValue("scan")); // Laser scanner by default
const std::string source_type = get_parameter(source_name + ".type").as_string();
if (source_type == "scan") {
std::shared_ptr<Scan> s = std::make_shared<Scan>(
node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
transform_tolerance, source_timeout);
s->configure();
sources_.push_back(s);
} else if (source_type == "pointcloud") {
std::shared_ptr<PointCloud> p = std::make_shared<PointCloud>(
node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
transform_tolerance, source_timeout);
p->configure();
sources_.push_back(p);
} else { // Error if something else
RCLCPP_ERROR(
get_logger(),
"[%s]: Unknown source type: %s",
source_name.c_str(), source_type.c_str());
return false;
}
}
} catch (const std::exception & ex) {
RCLCPP_ERROR(get_logger(), "Error while getting parameters: %s", ex.what());
return false;
}
return true;
}
void CollisionMonitor::process(const Velocity & cmd_vel_in)
{
// Current timestamp for all inner routines prolongation
rclcpp::Time curr_time = this->now();
// Do nothing if main worker in non-active state
if (!process_active_) {
return;
}
// Points array collected from different data sources in a robot base frame
std::vector<Point> collision_points;
// Fill collision_points array from different data sources
for (std::shared_ptr<Source> source : sources_) {
source->getData(curr_time, collision_points);
}
// By default - there is no action
Action robot_action{DO_NOTHING, cmd_vel_in};
// Polygon causing robot action (if any)
std::shared_ptr<Polygon> action_polygon;
for (std::shared_ptr<Polygon> polygon : polygons_) {
if (robot_action.action_type == STOP) {
// If robot already should stop, do nothing
break;
}
const ActionType at = polygon->getActionType();
if (at == STOP || at == SLOWDOWN) {
// Process STOP/SLOWDOWN for the selected polygon
if (processStopSlowdown(polygon, collision_points, cmd_vel_in, robot_action)) {
action_polygon = polygon;
}
} else if (at == APPROACH) {
// Process APPROACH for the selected polygon
if (processApproach(polygon, collision_points, cmd_vel_in, robot_action)) {
action_polygon = polygon;
}
}
}
if (robot_action.action_type != robot_action_prev_.action_type) {
// Report changed robot behavior
printAction(robot_action, action_polygon);
}
// Publish requred robot velocity
publishVelocity(robot_action);
// Publish polygons for better visualization
publishPolygons();
robot_action_prev_ = robot_action;
}
bool CollisionMonitor::processStopSlowdown(
const std::shared_ptr<Polygon> polygon,
const std::vector<Point> & collision_points,
const Velocity & velocity,
Action & robot_action) const
{
if (polygon->getPointsInside(collision_points) > polygon->getMaxPoints()) {
if (polygon->getActionType() == STOP) {
// Setting up zero velocity for STOP model
robot_action.action_type = STOP;
robot_action.req_vel.x = 0.0;
robot_action.req_vel.y = 0.0;
robot_action.req_vel.tw = 0.0;
return true;
} else { // SLOWDOWN
const Velocity safe_vel = velocity * polygon->getSlowdownRatio();
// Check that currently calculated velocity is safer than
// chosen for previous shapes one
if (safe_vel < robot_action.req_vel) {
robot_action.action_type = SLOWDOWN;
robot_action.req_vel = safe_vel;
return true;
}
}
}
return false;
}
bool CollisionMonitor::processApproach(
const std::shared_ptr<Polygon> polygon,
const std::vector<Point> & collision_points,
const Velocity & velocity,
Action & robot_action) const
{
polygon->updatePolygon();
// Obtain time before a collision
const double collision_time = polygon->getCollisionTime(collision_points, velocity);
if (collision_time >= 0.0) {
// If collision will occurr, reduce robot speed
const double change_ratio = collision_time / polygon->getTimeBeforeCollision();
const Velocity safe_vel = velocity * change_ratio;
// Check that currently calculated velocity is safer than
// chosen for previous shapes one
if (safe_vel < robot_action.req_vel) {
robot_action.action_type = APPROACH;
robot_action.req_vel = safe_vel;
return true;
}
}
return false;
}
void CollisionMonitor::printAction(
const Action & robot_action, const std::shared_ptr<Polygon> action_polygon) const
{
if (robot_action.action_type == STOP) {
RCLCPP_INFO(
get_logger(),
"Robot to stop due to %s polygon",
action_polygon->getName().c_str());
} else if (robot_action.action_type == SLOWDOWN) {
RCLCPP_INFO(
get_logger(),
"Robot to slowdown for %f percents due to %s polygon",
action_polygon->getSlowdownRatio() * 100,
action_polygon->getName().c_str());
} else if (robot_action.action_type == APPROACH) {
RCLCPP_INFO(
get_logger(),
"Robot to approach for %f seconds away from collision",
action_polygon->getTimeBeforeCollision());
} else { // robot_action.action_type == DO_NOTHING
RCLCPP_INFO(
get_logger(),
"Robot to continue normal operation");
}
}
void CollisionMonitor::publishPolygons() const
{
for (std::shared_ptr<Polygon> polygon : polygons_) {
polygon->publish();
}
}
} // namespace nav2_collision_monitor
#include "rclcpp_components/register_node_macro.hpp"
// Register the component with class_loader.
// This acts as a sort of entry point, allowing the component to be discoverable when its library
// is being loaded into a running process.
RCLCPP_COMPONENTS_REGISTER_NODE(nav2_collision_monitor::CollisionMonitor)