Skip to content

Commit fe78dab

Browse files
AlexeyMerzlyakovSteveMacenski
authored andcommitted
Dynamically changing polygons support (ros-navigation#3245)
* Add Collision Monitor polygon topics subscription * Add the support of polygons published in different frame * Internal review * Fix working with polygons visualization * Update nav2_collision_monitor/README.md Co-authored-by: Steve Macenski <[email protected]> * Move getTransform to nav2_util * Fix misprint * Meet remaining review items: * Update polygon params handling logic * Warn if polygon shape was not set * Publish with ownership movement * Correct polygons_test.cpp parameters handling logic * Adjust README for dynamic polygons logic update Co-authored-by: Steve Macenski <[email protected]>
1 parent 0d86469 commit fe78dab

File tree

14 files changed

+526
-142
lines changed

14 files changed

+526
-142
lines changed

nav2_collision_monitor/README.md

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -27,9 +27,9 @@ The following models of safety behaviors are employed by Collision Monitor:
2727

2828
The zones around the robot can take the following shapes:
2929

30-
* Arbitrary user-defined polygon relative to the robot base frame.
31-
* Circle: is made for the best performance and could be used in the cases where the zone or robot could be approximated by round shape.
32-
* Robot footprint polygon, which is used in the approach behavior model only. Will use the footprint topic to allow it to be dynamically adjusted over time.
30+
* Arbitrary user-defined polygon relative to the robot base frame, which can be static in a configuration file or dynamically changing via a topic interface.
31+
* Robot footprint polygon, which is used in the approach behavior model only. Will use the static user-defined polygon or the footprint topic to allow it to be dynamically adjusted over time.
32+
* Circle: is made for the best performance and could be used in the cases where the zone or robot footprint could be approximated by round shape.
3333

3434
The data may be obtained from different data sources:
3535

@@ -43,7 +43,7 @@ The Collision Monitor is designed to operate below Nav2 as an independent safety
4343
This acts as a filter on the `cmd_vel` topic coming out of the Controller Server. If no such zone is triggered, then the Controller's `cmd_vel` is used. Else, it is scaled or set to stop as appropriate.
4444

4545
The following diagram is showing the high-level design of Collision Monitor module. All shapes (Polygons and Circles) are derived from base `Polygon` class, so without loss of generality we can call them as polygons. Subscribed footprint is also having the same properties as other polygons, but it is being obtained a footprint topic for the Approach Model.
46-
![HDL.png](doc/HLD.png)
46+
![HLD.png](doc/HLD.png)
4747

4848
## Configuration
4949

nav2_collision_monitor/include/nav2_collision_monitor/circle.hpp

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -66,15 +66,24 @@ class Circle : public Polygon
6666
*/
6767
int getPointsInside(const std::vector<Point> & points) const override;
6868

69+
/**
70+
* @brief Specifies that the shape is always set for a circle object
71+
*/
72+
bool isShapeSet() override {return true;}
73+
6974
protected:
7075
/**
7176
* @brief Supporting routine obtaining polygon-specific ROS-parameters
77+
* @brief polygon_sub_topic Input name of polygon subscription topic
7278
* @param polygon_pub_topic Output name of polygon publishing topic
7379
* @param footprint_topic Output name of footprint topic. For Circle returns empty string,
7480
* there is no footprint subscription in this class.
7581
* @return True if all parameters were obtained or false in failure case
7682
*/
77-
bool getParameters(std::string & polygon_pub_topic, std::string & footprint_topic) override;
83+
bool getParameters(
84+
std::string & polygon_sub_topic,
85+
std::string & polygon_pub_topic,
86+
std::string & footprint_topic) override;
7887

7988
// ----- Variables -----
8089

nav2_collision_monitor/include/nav2_collision_monitor/polygon.hpp

Lines changed: 31 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,6 @@
2121

2222
#include "rclcpp/rclcpp.hpp"
2323
#include "geometry_msgs/msg/polygon_stamped.hpp"
24-
#include "geometry_msgs/msg/polygon.hpp"
2524

2625
#include "tf2/time.h"
2726
#include "tf2_ros/buffer.h"
@@ -110,6 +109,12 @@ class Polygon
110109
*/
111110
virtual void getPolygon(std::vector<Point> & poly) const;
112111

112+
/**
113+
* @brief Returns true if polygon points were set.
114+
* Othewise, prints a warning and returns false.
115+
*/
116+
virtual bool isShapeSet();
117+
113118
/**
114119
* @brief Updates polygon from footprint subscriber (if any)
115120
*/
@@ -138,7 +143,7 @@ class Polygon
138143
/**
139144
* @brief Publishes polygon message into a its own topic
140145
*/
141-
void publish() const;
146+
void publish();
142147

143148
protected:
144149
/**
@@ -150,11 +155,29 @@ class Polygon
150155

151156
/**
152157
* @brief Supporting routine obtaining polygon-specific ROS-parameters
158+
* @brief polygon_sub_topic Output name of polygon subscription topic.
159+
* Empty, if no polygon subscription.
153160
* @param polygon_pub_topic Output name of polygon publishing topic
154-
* @param footprint_topic Output name of footprint topic. Empty, if no footprint subscription
161+
* @param footprint_topic Output name of footprint topic.
162+
* Empty, if no footprint subscription.
155163
* @return True if all parameters were obtained or false in failure case
156164
*/
157-
virtual bool getParameters(std::string & polygon_pub_topic, std::string & footprint_topic);
165+
virtual bool getParameters(
166+
std::string & polygon_sub_topic,
167+
std::string & polygon_pub_topic,
168+
std::string & footprint_topic);
169+
170+
/**
171+
* @brief Updates polygon from geometry_msgs::msg::PolygonStamped message
172+
* @param msg Message to update polygon from
173+
*/
174+
void updatePolygon(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg);
175+
176+
/**
177+
* @brief Dynamic polygon callback
178+
* @param msg Shared pointer to the polygon message
179+
*/
180+
void polygonCallback(geometry_msgs::msg::PolygonStamped::ConstSharedPtr msg);
158181

159182
/**
160183
* @brief Checks if point is inside polygon
@@ -183,6 +206,8 @@ class Polygon
183206
double time_before_collision_;
184207
/// @brief Time step for robot movement simulation
185208
double simulation_time_step_;
209+
/// @brief Polygon subscription
210+
rclcpp::Subscription<geometry_msgs::msg::PolygonStamped>::SharedPtr polygon_sub_;
186211
/// @brief Footprint subscriber
187212
std::unique_ptr<nav2_costmap_2d::FootprintSubscriber> footprint_sub_;
188213

@@ -197,8 +222,8 @@ class Polygon
197222
// Visualization
198223
/// @brief Whether to publish the polygon
199224
bool visualize_;
200-
/// @brief Polygon points stored for later publishing
201-
geometry_msgs::msg::Polygon polygon_;
225+
/// @brief Polygon stored for later publishing
226+
geometry_msgs::msg::PolygonStamped polygon_;
202227
/// @brief Polygon publisher for visualization purposes
203228
rclcpp_lifecycle::LifecyclePublisher<geometry_msgs::msg::PolygonStamped>::SharedPtr polygon_pub_;
204229

nav2_collision_monitor/include/nav2_collision_monitor/source.hpp

Lines changed: 0 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -88,21 +88,6 @@ class Source
8888
const rclcpp::Time & source_time,
8989
const rclcpp::Time & curr_time) const;
9090

91-
/**
92-
* @brief Obtains a transform from source_frame_id at source_time ->
93-
* to base_frame_id_ at curr_time time
94-
* @param source_frame_id Source frame ID to convert data from
95-
* @param source_time Source timestamp to convert data from
96-
* @param curr_time Current node time to interpolate data to
97-
* @param tf_transform Output source->base transform
98-
* @return True if got correct transform, otherwise false
99-
*/
100-
bool getTransform(
101-
const std::string & source_frame_id,
102-
const rclcpp::Time & source_time,
103-
const rclcpp::Time & curr_time,
104-
tf2::Transform & tf_transform) const;
105-
10691
// ----- Variables -----
10792

10893
/// @brief Collision Monitor node

nav2_collision_monitor/src/circle.cpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,10 @@ int Circle::getPointsInside(const std::vector<Point> & points) const
7070
return num;
7171
}
7272

73-
bool Circle::getParameters(std::string & polygon_pub_topic, std::string & footprint_topic)
73+
bool Circle::getParameters(
74+
std::string & polygon_sub_topic,
75+
std::string & polygon_pub_topic,
76+
std::string & footprint_topic)
7477
{
7578
auto node = node_.lock();
7679
if (!node) {
@@ -81,7 +84,8 @@ bool Circle::getParameters(std::string & polygon_pub_topic, std::string & footpr
8184
return false;
8285
}
8386

84-
// There is no footprint subscription for the Circle. Thus, set string as empty.
87+
// There is no polygon or footprint subscription for the Circle. Thus, set strings as empty.
88+
polygon_sub_topic.clear();
8589
footprint_topic.clear();
8690

8791
try {

nav2_collision_monitor/src/collision_monitor_node.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -389,6 +389,10 @@ bool CollisionMonitor::processStopSlowdown(
389389
const Velocity & velocity,
390390
Action & robot_action) const
391391
{
392+
if (!polygon->isShapeSet()) {
393+
return false;
394+
}
395+
392396
if (polygon->getPointsInside(collision_points) > polygon->getMaxPoints()) {
393397
if (polygon->getActionType() == STOP) {
394398
// Setting up zero velocity for STOP model
@@ -420,6 +424,10 @@ bool CollisionMonitor::processApproach(
420424
{
421425
polygon->updatePolygon();
422426

427+
if (!polygon->isShapeSet()) {
428+
return false;
429+
}
430+
423431
// Obtain time before a collision
424432
const double collision_time = polygon->getCollisionTime(collision_points, velocity);
425433
if (collision_time >= 0.0) {

nav2_collision_monitor/src/pointcloud.cpp

Lines changed: 7 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include "sensor_msgs/point_cloud2_iterator.hpp"
2020

2121
#include "nav2_util/node_utils.hpp"
22+
#include "nav2_util/robot_utils.hpp"
2223

2324
namespace nav2_collision_monitor
2425
{
@@ -78,7 +79,12 @@ void PointCloud::getData(
7879
// Obtaining the transform to get data from source frame and time where it was received
7980
// to the base frame and current time
8081
tf2::Transform tf_transform;
81-
if (!getTransform(data_->header.frame_id, data_->header.stamp, curr_time, tf_transform)) {
82+
if (
83+
!nav2_util::getTransform(
84+
data_->header.frame_id, data_->header.stamp,
85+
base_frame_id_, curr_time, global_frame_id_,
86+
transform_tolerance_, tf_buffer_, tf_transform))
87+
{
8288
return;
8389
}
8490

0 commit comments

Comments
 (0)