Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Collision Monitor] Add a watchdog mechanism #3880

Merged
merged 15 commits into from Oct 31, 2023
Expand Up @@ -69,8 +69,9 @@ class PointCloud : public Source
* @param curr_time Current node time for data interpolation
* @param data Array where the data from source to be added.
* Added data is transformed to base_frame_id_ coordinate system at curr_time.
* @return false if an invalid source should block the robot
*/
void getData(
bool getData(
const rclcpp::Time & curr_time,
std::vector<Point> & data) const;

Expand Down
Expand Up @@ -69,8 +69,9 @@ class Range : public Source
* @param curr_time Current node time for data interpolation
* @param data Array where the data from source to be added.
* Added data is transformed to base_frame_id_ coordinate system at curr_time.
* @return false if an invalid source should block the robot
*/
void getData(
bool getData(
const rclcpp::Time & curr_time,
std::vector<Point> & data) const;

Expand Down
Expand Up @@ -69,8 +69,9 @@ class Scan : public Source
* @param curr_time Current node time for data interpolation
* @param data Array where the data from source to be added.
* Added data is transformed to base_frame_id_ coordinate system at curr_time.
* @return false if an invalid source should block the robot
*/
void getData(
bool getData(
const rclcpp::Time & curr_time,
std::vector<Point> & data) const;

Expand Down
15 changes: 14 additions & 1 deletion nav2_collision_monitor/include/nav2_collision_monitor/source.hpp
Expand Up @@ -69,8 +69,9 @@ class Source
* @param curr_time Current node time for data interpolation
* @param data Array where the data from source to be added.
* Added data is transformed to base_frame_id_ coordinate system at curr_time.
* @return false if an invalid source should block the robot
*/
virtual void getData(
virtual bool getData(
const rclcpp::Time & curr_time,
std::vector<Point> & data) const = 0;

Expand All @@ -80,6 +81,18 @@ class Source
*/
bool getEnabled() const;

/**
* @brief Obtains the name of the data source
* @return Name of the data source
*/
std::string getSourceName() const;

/**
* @brief Obtains the source_timeout parameter of the data source
* @return source_timeout parameter value of the data source
*/
rclcpp::Duration getSourceTimeout() const;

protected:
/**
* @brief Source configuration routine.
Expand Down
17 changes: 13 additions & 4 deletions nav2_collision_monitor/src/collision_detector_node.cpp
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We need to think, how to report the robot needs to stop, when the sources were outdated for Collision Detector. In the initial message, there is a detected polygons string array, but there is not ability what to do. So, I am thinking about publishing CollisionDetectorState.msg with empty polygons[] array, that will give the developer an information that something (not polygon) is causing robot to report the "collision". Or add one more bool variable into this message, as an alternative for it.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

See last commit

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Now, the polygons[] is empty when robot detected to "collide" (stop) due to incorrect source. However, in normal operation, it will be also empty. Sorry, as I've missed this initially. Thus, we still seem to need to add invalid source feedback to CollisionDetectorState.msg (and CollisionMonitorState.msg).

Expand Up @@ -307,10 +307,22 @@ void CollisionDetector::process()
// Points array collected from different data sources in a robot base frame
std::vector<Point> collision_points;

std::unique_ptr<nav2_msgs::msg::CollisionDetectorState> state_msg =
std::make_unique<nav2_msgs::msg::CollisionDetectorState>();

// Fill collision_points array from different data sources
for (std::shared_ptr<Source> source : sources_) {
if (source->getEnabled()) {
source->getData(curr_time, collision_points);
if (!source->getData(curr_time, collision_points) &&
source->getSourceTimeout().seconds() != 0.0)
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
{
RCLCPP_WARN(
get_logger(),
"Invalid source %s detected."
" Either due to data not published yet, or to lack of new data received within the"
" sensor timeout, or if impossible to transform data to base frame",
source->getSourceName().c_str());
}
}
}

Expand Down Expand Up @@ -341,9 +353,6 @@ void CollisionDetector::process()
collision_points_marker_pub_->publish(std::move(marker_array));
}

std::unique_ptr<nav2_msgs::msg::CollisionDetectorState> state_msg =
std::make_unique<nav2_msgs::msg::CollisionDetectorState>();

for (std::shared_ptr<Polygon> polygon : polygons_) {
if (!polygon->getEnabled()) {
continue;
Expand Down
38 changes: 28 additions & 10 deletions nav2_collision_monitor/src/collision_monitor_node.cpp
Expand Up @@ -378,10 +378,25 @@ void CollisionMonitor::process(const Velocity & cmd_vel_in)
// Points array collected from different data sources in a robot base frame
std::vector<Point> 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;

// Fill collision_points array from different data sources
for (std::shared_ptr<Source> source : sources_) {
if (source->getEnabled()) {
source->getData(curr_time, collision_points);
if (!source->getData(curr_time, collision_points) &&
source->getSourceTimeout().seconds() != 0.0)
{
action_polygon = nullptr;
robot_action.polygon_name = "invalid source";
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Please change this to robot_action.polygon_name = "invalid source: " + source->getName(). If we have to stop due to different sources, robot_action.polygon_name should be different to re-trigger the reporting later in notifyActionState()

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same as above.
For now, without proper source tracing/feedback, that would not make sense as we are stopping at the detection of the first invalid source, so if we have multiple invalid, it will just be random which one we are reporting.
Alternative (complex) is here: https://github.com/doisyg/navigation2/tree/with_source_feedback
Better for another PR

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;
break;
}
}
}

Expand Down Expand Up @@ -412,11 +427,6 @@ void CollisionMonitor::process(const Velocity & cmd_vel_in)
collision_points_marker_pub_->publish(std::move(marker_array));
}

// 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 (!polygon->getEnabled()) {
continue;
Expand Down Expand Up @@ -545,10 +555,18 @@ void CollisionMonitor::notifyActionState(
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());
if (robot_action.polygon_name == "invalid source") {
RCLCPP_WARN(
get_logger(),
"Robot to stop due to invalid source."
" Either due to data not published yet, or to lack of new data received within the"
" sensor timeout, or if impossible to transform data to base frame");
} else {
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(),
Expand Down
11 changes: 6 additions & 5 deletions nav2_collision_monitor/src/pointcloud.cpp
Expand Up @@ -65,17 +65,17 @@ void PointCloud::configure()
std::bind(&PointCloud::dataCallback, this, std::placeholders::_1));
}

void PointCloud::getData(
bool PointCloud::getData(
const rclcpp::Time & curr_time,
std::vector<Point> & data) const
{
// Ignore data from the source if it is not being published yet or
// not published for a long time
if (data_ == nullptr) {
return;
return false;
}
if (!sourceValid(data_->header.stamp, curr_time)) {
return;
return false;
}

tf2::Transform tf_transform;
Expand All @@ -88,7 +88,7 @@ void PointCloud::getData(
base_frame_id_, curr_time, global_frame_id_,
transform_tolerance_, tf_buffer_, tf_transform))
{
return;
return false;
}
} else {
// Obtaining the transform to get data from source frame to base frame without time shift
Expand All @@ -99,7 +99,7 @@ void PointCloud::getData(
data_->header.frame_id, base_frame_id_,
transform_tolerance_, tf_buffer_, tf_transform))
{
return;
return false;
}
}

Expand All @@ -118,6 +118,7 @@ void PointCloud::getData(
data.push_back({p_v3_b.x(), p_v3_b.y()});
}
}
return true;
}

void PointCloud::getParameters(std::string & source_topic)
Expand Down
14 changes: 8 additions & 6 deletions nav2_collision_monitor/src/range.cpp
Expand Up @@ -65,17 +65,17 @@ void Range::configure()
std::bind(&Range::dataCallback, this, std::placeholders::_1));
}

void Range::getData(
bool Range::getData(
const rclcpp::Time & curr_time,
std::vector<Point> & data) const
{
// Ignore data from the source if it is not being published yet or
// not being published for a long time
if (data_ == nullptr) {
return;
return false;
}
if (!sourceValid(data_->header.stamp, curr_time)) {
return;
return false;
}

// Ignore data, if its range is out of scope of range sensor abilities
Expand All @@ -84,7 +84,7 @@ void Range::getData(
logger_,
"[%s]: Data range %fm is out of {%f..%f} sensor span. Ignoring...",
source_name_.c_str(), data_->range, data_->min_range, data_->max_range);
return;
return false;
}

tf2::Transform tf_transform;
Expand All @@ -97,7 +97,7 @@ void Range::getData(
base_frame_id_, curr_time, global_frame_id_,
transform_tolerance_, tf_buffer_, tf_transform))
{
return;
return false;
}
} else {
// Obtaining the transform to get data from source frame to base frame without time shift
Expand All @@ -108,7 +108,7 @@ void Range::getData(
data_->header.frame_id, base_frame_id_,
transform_tolerance_, tf_buffer_, tf_transform))
{
return;
return false;
}
}

Expand Down Expand Up @@ -142,6 +142,8 @@ void Range::getData(

// Refill data array
data.push_back({p_v3_b.x(), p_v3_b.y()});

return true;
}

void Range::getParameters(std::string & source_topic)
Expand Down
11 changes: 6 additions & 5 deletions nav2_collision_monitor/src/scan.cpp
Expand Up @@ -64,17 +64,17 @@ void Scan::configure()
std::bind(&Scan::dataCallback, this, std::placeholders::_1));
}

void Scan::getData(
bool Scan::getData(
const rclcpp::Time & curr_time,
std::vector<Point> & data) const
{
// Ignore data from the source if it is not being published yet or
// not being published for a long time
if (data_ == nullptr) {
return;
return false;
}
if (!sourceValid(data_->header.stamp, curr_time)) {
return;
return false;
}

tf2::Transform tf_transform;
Expand All @@ -87,7 +87,7 @@ void Scan::getData(
base_frame_id_, curr_time, global_frame_id_,
transform_tolerance_, tf_buffer_, tf_transform))
{
return;
return false;
}
} else {
// Obtaining the transform to get data from source frame to base frame without time shift
Expand All @@ -98,7 +98,7 @@ void Scan::getData(
data_->header.frame_id, base_frame_id_,
transform_tolerance_, tf_buffer_, tf_transform))
{
return;
return false;
}
}

Expand All @@ -118,6 +118,7 @@ void Scan::getData(
}
angle += data_->angle_increment;
}
return true;
}

void Scan::dataCallback(sensor_msgs::msg::LaserScan::ConstSharedPtr msg)
Expand Down
18 changes: 17 additions & 1 deletion nav2_collision_monitor/src/source.cpp
Expand Up @@ -69,6 +69,12 @@ void Source::getCommonParameters(std::string & source_topic)
nav2_util::declare_parameter_if_not_declared(
node, source_name_ + ".enabled", rclcpp::ParameterValue(true));
enabled_ = node->get_parameter(source_name_ + ".enabled").as_bool();

nav2_util::declare_parameter_if_not_declared(
node, source_name_ + ".source_timeout",
rclcpp::ParameterValue(source_timeout_.seconds())); // node source_timeout by default
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
source_timeout_ = rclcpp::Duration::from_seconds(
node->get_parameter(source_name_ + ".source_timeout").as_double());
}

bool Source::sourceValid(
Expand All @@ -78,7 +84,7 @@ bool Source::sourceValid(
// Source is considered as not valid, if latest received data timestamp is earlier
// than current time by source_timeout_ interval
const rclcpp::Duration dt = curr_time - source_time;
if (dt > source_timeout_) {
if (source_timeout_.seconds() != 0.0 && dt > source_timeout_) {
SteveMacenski marked this conversation as resolved.
Show resolved Hide resolved
RCLCPP_WARN(
logger_,
"[%s]: Latest source and current collision monitor node timestamps differ on %f seconds. "
Expand All @@ -95,6 +101,16 @@ bool Source::getEnabled() const
return enabled_;
}

std::string Source::getSourceName() const
{
return source_name_;
}

rclcpp::Duration Source::getSourceTimeout() const
{
return source_timeout_;
}

rcl_interfaces::msg::SetParametersResult
Source::dynamicParametersCallback(
std::vector<rclcpp::Parameter> parameters)
Expand Down