Skip to content

Commit

Permalink
Synch with ros-navigation#4181
Browse files Browse the repository at this point in the history
  • Loading branch information
nachovizzo committed Mar 14, 2024
1 parent f2a4007 commit 9a36c17
Show file tree
Hide file tree
Showing 24 changed files with 252 additions and 274 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -38,14 +38,14 @@ class Circle : public Polygon
* @param polygon_name Name of circle
* @param tf_buffer Shared pointer to a TF buffer
* @param base_frame_id Robot base frame ID
* @param transform_tolerance Transform tolerance
* @param transform_timeout How long to block before failing
*/
Circle(
const nav2_util::LifecycleNode::WeakPtr & node,
const std::string & polygon_name,
const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
const std::string & base_frame_id,
const tf2::Duration & transform_tolerance);
const tf2::Duration & transform_timeout);
/**
* @brief Circle class destructor
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -99,18 +99,18 @@ class CollisionDetector : public nav2_util::LifecycleNode
/**
* @brief Supporting routine creating and configuring all polygons
* @param base_frame_id Robot base frame ID
* @param transform_tolerance Transform tolerance
* @param transform_timeout How long to block before failing
* @return True if all polygons were configured successfully or false in failure case
*/
bool configurePolygons(
const std::string & base_frame_id,
const tf2::Duration & transform_tolerance);
const tf2::Duration & transform_timeout);
/**
* @brief Supporting routine creating and configuring all data sources
* @param base_frame_id Robot base frame ID
* @param odom_frame_id Odometry frame ID. Used as global frame to get
* source->base time interpolated transform.
* @param transform_tolerance Transform tolerance
* @param transform_timeout How long to block before failing
* @param source_timeout Maximum time interval in which data is considered valid
* @param base_shift_correction Whether to correct source data towards to base frame movement,
* considering the difference between current time and latest source time
Expand All @@ -119,7 +119,7 @@ class CollisionDetector : public nav2_util::LifecycleNode
bool configureSources(
const std::string & base_frame_id,
const std::string & odom_frame_id,
const tf2::Duration & transform_tolerance,
const tf2::Duration & transform_timeout,
const rclcpp::Duration & source_timeout,
const bool base_shift_correction);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -118,18 +118,18 @@ class CollisionMonitor : public nav2_util::LifecycleNode
/**
* @brief Supporting routine creating and configuring all polygons
* @param base_frame_id Robot base frame ID
* @param transform_tolerance Transform tolerance
* @param transform_timeout How long to block before failing
* @return True if all polygons were configured successfully or false in failure case
*/
bool configurePolygons(
const std::string & base_frame_id,
const tf2::Duration & transform_tolerance);
const tf2::Duration & transform_timeout);
/**
* @brief Supporting routine creating and configuring all data sources
* @param base_frame_id Robot base frame ID
* @param odom_frame_id Odometry frame ID. Used as global frame to get
* source->base time interpolated transform.
* @param transform_tolerance Transform tolerance
* @param transform_timeout How long to block before failing
* @param source_timeout Maximum time interval in which data is considered valid
* @param base_shift_correction Whether to correct source data towards to base frame movement,
* considering the difference between current time and latest source time
Expand All @@ -138,7 +138,7 @@ class CollisionMonitor : public nav2_util::LifecycleNode
bool configureSources(
const std::string & base_frame_id,
const std::string & odom_frame_id,
const tf2::Duration & transform_tolerance,
const tf2::Duration & transform_timeout,
const rclcpp::Duration & source_timeout,
const bool base_shift_correction);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ class PointCloud : public Source
* @param tf_buffer Shared pointer to a TF buffer
* @param base_frame_id Robot base frame ID. The output data will be transformed into this frame.
* @param global_frame_id Global frame ID for correct transform calculation
* @param transform_tolerance Transform tolerance
* @param transform_timeout How long to block before failing
* @param source_timeout Maximum time interval in which data is considered valid
* @param base_shift_correction Whether to correct source data towards to base frame movement,
* considering the difference between current time and latest source time
Expand All @@ -50,7 +50,7 @@ class PointCloud : public Source
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 tf2::Duration & transform_timeout,
const rclcpp::Duration & source_timeout,
const bool base_shift_correction);
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,14 +47,14 @@ class Polygon
* @param polygon_name Name of polygon
* @param tf_buffer Shared pointer to a TF buffer
* @param base_frame_id Robot base frame ID
* @param transform_tolerance Transform tolerance
* @param transform_timeout how long to block before failing
*/
Polygon(
const nav2_util::LifecycleNode::WeakPtr & node,
const std::string & polygon_name,
const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
const std::string & base_frame_id,
const tf2::Duration & transform_tolerance);
const tf2::Duration & transform_timeout);
/**
* @brief Polygon destructor
*/
Expand Down Expand Up @@ -248,8 +248,8 @@ class Polygon
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
/// @brief Base frame ID
std::string base_frame_id_;
/// @brief Transform tolerance
tf2::Duration transform_tolerance_;
/// @brief Transform timeout on how long to block before failing
tf2::Duration transform_timeout_;

// Visualization
/// @brief Whether to publish the polygon
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ class Range : public Source
* @param tf_buffer Shared pointer to a TF buffer
* @param base_frame_id Robot base frame ID. The output data will be transformed into this frame.
* @param global_frame_id Global frame ID for correct transform calculation
* @param transform_tolerance Transform tolerance
* @param transform_timeout How long to block before failing
* @param source_timeout Maximum time interval in which data is considered valid
* @param base_shift_correction Whether to correct source data towards to base frame movement,
* considering the difference between current time and latest source time
Expand All @@ -50,7 +50,7 @@ class Range : public Source
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 tf2::Duration & transform_timeout,
const rclcpp::Duration & source_timeout,
const bool base_shift_correction);
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ class Scan : public Source
* @param tf_buffer Shared pointer to a TF buffer
* @param base_frame_id Robot base frame ID. The output data will be transformed into this frame.
* @param global_frame_id Global frame ID for correct transform calculation
* @param transform_tolerance Transform tolerance
* @param transform_timeout How long to block before failing
* @param source_timeout Maximum time interval in which data is considered valid
* @param base_shift_correction Whether to correct source data towards to base frame movement,
* considering the difference between current time and latest source time
Expand All @@ -50,7 +50,7 @@ class Scan : public Source
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 tf2::Duration & transform_timeout,
const rclcpp::Duration & source_timeout,
const bool base_shift_correction);
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ class Source
* @param tf_buffer Shared pointer to a TF buffer
* @param base_frame_id Robot base frame ID. The output data will be transformed into this frame.
* @param global_frame_id Global frame ID for correct transform calculation
* @param transform_tolerance Transform tolerance
* @param transform_timeout How long to block before failing
* @param source_timeout Maximum time interval in which data is considered valid
* @param base_shift_correction Whether to correct source data towards to base frame movement,
* considering the difference between current time and latest source time
Expand All @@ -55,7 +55,7 @@ class Source
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 tf2::Duration & transform_timeout,
const rclcpp::Duration & source_timeout,
const bool base_shift_correction);
/**
Expand Down Expand Up @@ -143,8 +143,8 @@ class Source
std::string base_frame_id_;
/// @brief Global frame ID for correct transform calculation
std::string global_frame_id_;
/// @brief Transform tolerance
tf2::Duration transform_tolerance_;
/// @brief Transform timeout
tf2::Duration transform_timeout_;
/// @brief Maximum time interval in which data is considered valid
rclcpp::Duration source_timeout_;
/// @brief Whether to correct source data towards to base frame movement,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ collision_detector:
frequency: 10.0
base_frame_id: "base_footprint"
odom_frame_id: "odom"
transform_tolerance: 0.5
transform_timeout: 0.5
source_timeout: 5.0
base_shift_correction: True
polygons: ["PolygonFront"]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ collision_monitor:
cmd_vel_in_topic: "cmd_vel_smoothed"
cmd_vel_out_topic: "cmd_vel"
state_topic: "collision_monitor_state"
transform_tolerance: 0.5
transform_timeout: 0.5
source_timeout: 5.0
base_shift_correction: True
stop_pub_timeout: 2.0
Expand Down
4 changes: 2 additions & 2 deletions nav2_collision_monitor/src/circle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,8 @@ Circle::Circle(
const std::string & polygon_name,
const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
const std::string & base_frame_id,
const tf2::Duration & transform_tolerance)
: Polygon::Polygon(node, polygon_name, tf_buffer, base_frame_id, transform_tolerance)
const tf2::Duration & transform_timeout)
: Polygon::Polygon(node, polygon_name, tf_buffer, base_frame_id, transform_timeout)
{
RCLCPP_INFO(logger_, "[%s]: Creating Circle", polygon_name_.c_str());
}
Expand Down
26 changes: 13 additions & 13 deletions nav2_collision_monitor/src/collision_detector_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ CollisionDetector::on_shutdown(const rclcpp_lifecycle::State & /*state*/)
bool CollisionDetector::getParameters()
{
std::string base_frame_id, odom_frame_id;
tf2::Duration transform_tolerance;
tf2::Duration transform_timeout;
rclcpp::Duration source_timeout(2.0, 0.0);

auto node = shared_from_this();
Expand All @@ -156,9 +156,9 @@ bool CollisionDetector::getParameters()
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());
node, "transform_timeout", rclcpp::ParameterValue(0.1));
transform_timeout =
tf2::durationFromSec(get_parameter("transform_timeout").as_double());
nav2_util::declare_parameter_if_not_declared(
node, "source_timeout", rclcpp::ParameterValue(2.0));
source_timeout =
Expand All @@ -168,12 +168,12 @@ bool CollisionDetector::getParameters()
const bool base_shift_correction =
get_parameter("base_shift_correction").as_bool();

if (!configurePolygons(base_frame_id, transform_tolerance)) {
if (!configurePolygons(base_frame_id, transform_timeout)) {
return false;
}

if (!configureSources(
base_frame_id, odom_frame_id, transform_tolerance, source_timeout,
base_frame_id, odom_frame_id, transform_timeout, source_timeout,
base_shift_correction))
{
return false;
Expand All @@ -184,7 +184,7 @@ bool CollisionDetector::getParameters()

bool CollisionDetector::configurePolygons(
const std::string & base_frame_id,
const tf2::Duration & transform_tolerance)
const tf2::Duration & transform_timeout)
{
try {
auto node = shared_from_this();
Expand All @@ -202,11 +202,11 @@ bool CollisionDetector::configurePolygons(
if (polygon_type == "polygon") {
polygons_.push_back(
std::make_shared<Polygon>(
node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
node, polygon_name, tf_buffer_, base_frame_id, transform_timeout));
} else if (polygon_type == "circle") {
polygons_.push_back(
std::make_shared<Circle>(
node, polygon_name, tf_buffer_, base_frame_id, transform_tolerance));
node, polygon_name, tf_buffer_, base_frame_id, transform_timeout));
} else { // Error if something else
RCLCPP_ERROR(
get_logger(),
Expand Down Expand Up @@ -242,7 +242,7 @@ bool CollisionDetector::configurePolygons(
bool CollisionDetector::configureSources(
const std::string & base_frame_id,
const std::string & odom_frame_id,
const tf2::Duration & transform_tolerance,
const tf2::Duration & transform_timeout,
const rclcpp::Duration & source_timeout,
const bool base_shift_correction)
{
Expand All @@ -262,23 +262,23 @@ bool CollisionDetector::configureSources(
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, base_shift_correction);
transform_timeout, source_timeout, base_shift_correction);

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, base_shift_correction);
transform_timeout, source_timeout, base_shift_correction);

p->configure();

sources_.push_back(p);
} else if (source_type == "range") {
std::shared_ptr<Range> r = std::make_shared<Range>(
node, source_name, tf_buffer_, base_frame_id, odom_frame_id,
transform_tolerance, source_timeout, base_shift_correction);
transform_timeout, source_timeout, base_shift_correction);

r->configure();

Expand Down
Loading

0 comments on commit 9a36c17

Please sign in to comment.