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

Option allowing to use simple lookupTransform API #3412

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -127,13 +127,16 @@ class CollisionMonitor : public nav2_util::LifecycleNode
* source->base time inerpolated transform.
* @param transform_tolerance Transform tolerance
* @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
* @return True if all sources were configured successfully or false in failure case
*/
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 rclcpp::Duration & source_timeout,
const bool base_shift_correction);

/**
* @brief Main processing routine
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,8 @@ class PointCloud : public Source
* @param global_frame_id Global frame ID for correct transform calculation
* @param transform_tolerance Transform tolerance
* @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
*/
PointCloud(
const nav2_util::LifecycleNode::WeakPtr & node,
Expand All @@ -49,7 +51,8 @@ class PointCloud : public Source
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
const rclcpp::Duration & source_timeout);
const rclcpp::Duration & source_timeout,
const bool base_shift_correction);
/**
* @brief PointCloud destructor
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,8 @@ class Range : public Source
* @param global_frame_id Global frame ID for correct transform calculation
* @param transform_tolerance Transform tolerance
* @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
*/
Range(
const nav2_util::LifecycleNode::WeakPtr & node,
Expand All @@ -49,7 +51,8 @@ class Range : public Source
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
const rclcpp::Duration & source_timeout);
const rclcpp::Duration & source_timeout,
const bool base_shift_correction);
/**
* @brief Range destructor
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,8 @@ class Scan : public Source
* @param global_frame_id Global frame ID for correct transform calculation
* @param transform_tolerance Transform tolerance
* @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
*/
Scan(
const nav2_util::LifecycleNode::WeakPtr & node,
Expand All @@ -49,7 +51,8 @@ class Scan : public Source
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
const rclcpp::Duration & source_timeout);
const rclcpp::Duration & source_timeout,
const bool base_shift_correction);
/**
* @brief Scan destructor
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,8 @@ class Source
* @param global_frame_id Global frame ID for correct transform calculation
* @param transform_tolerance Transform tolerance
* @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
*/
Source(
const nav2_util::LifecycleNode::WeakPtr & node,
Expand All @@ -54,7 +56,8 @@ class Source
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
const rclcpp::Duration & source_timeout);
const rclcpp::Duration & source_timeout,
const bool base_shift_correction);
/**
* @brief Source destructor
*/
Expand Down Expand Up @@ -110,6 +113,9 @@ class Source
tf2::Duration transform_tolerance_;
/// @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,
/// considering the difference between current time and latest source time
bool base_shift_correction_;
}; // class Source

} // namespace nav2_collision_monitor
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ collision_monitor:
cmd_vel_out_topic: "cmd_vel"
transform_tolerance: 0.5
source_timeout: 5.0
base_shift_correction: True
stop_pub_timeout: 2.0
# Polygons represent zone around the robot for "stop" and "slowdown" action types,
# and robot footprint for "approach" action type.
Expand Down
18 changes: 13 additions & 5 deletions nav2_collision_monitor/src/collision_monitor_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,6 +205,10 @@ bool CollisionMonitor::getParameters(
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, "base_shift_correction", rclcpp::ParameterValue(true));
const bool base_shift_correction =
get_parameter("base_shift_correction").as_bool();

nav2_util::declare_parameter_if_not_declared(
node, "stop_pub_timeout", rclcpp::ParameterValue(1.0));
Expand All @@ -215,7 +219,10 @@ bool CollisionMonitor::getParameters(
return false;
}

if (!configureSources(base_frame_id, odom_frame_id, transform_tolerance, source_timeout)) {
if (
!configureSources(
base_frame_id, odom_frame_id, transform_tolerance, source_timeout, base_shift_correction))
{
return false;
}

Expand Down Expand Up @@ -271,7 +278,8 @@ 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)
const rclcpp::Duration & source_timeout,
const bool base_shift_correction)
{
try {
auto node = shared_from_this();
Expand All @@ -289,23 +297,23 @@ bool CollisionMonitor::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);
transform_tolerance, 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);
transform_tolerance, 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);
transform_tolerance, source_timeout, base_shift_correction);

r->configure();

Expand Down
36 changes: 25 additions & 11 deletions nav2_collision_monitor/src/pointcloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,10 +31,11 @@ PointCloud::PointCloud(
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
const rclcpp::Duration & source_timeout)
const rclcpp::Duration & source_timeout,
const bool base_shift_correction)
: Source(
node, source_name, tf_buffer, base_frame_id, global_frame_id,
transform_tolerance, source_timeout),
transform_tolerance, source_timeout, base_shift_correction),
data_(nullptr)
{
RCLCPP_INFO(logger_, "[%s]: Creating PointCloud", source_name_.c_str());
Expand Down Expand Up @@ -76,16 +77,29 @@ void PointCloud::getData(
return;
}

// Obtaining the transform to get data from source frame and time where it was received
// to the base frame and current time
tf2::Transform tf_transform;
if (
!nav2_util::getTransform(
data_->header.frame_id, data_->header.stamp,
base_frame_id_, curr_time, global_frame_id_,
transform_tolerance_, tf_buffer_, tf_transform))
{
return;
if (base_shift_correction_) {
// Obtaining the transform to get data from source frame and time where it was received
// to the base frame and current time
if (
!nav2_util::getTransform(
data_->header.frame_id, data_->header.stamp,
base_frame_id_, curr_time, global_frame_id_,
transform_tolerance_, tf_buffer_, tf_transform))
{
return;
}
} else {
// Obtaining the transform to get data from source frame to base frame without time shift
// considered. Less accurate but much more faster option not dependent on state estimation
// frames.
if (
!nav2_util::getTransform(
data_->header.frame_id, base_frame_id_,
transform_tolerance_, tf_buffer_, tf_transform))
{
return;
}
}

sensor_msgs::PointCloud2ConstIterator<float> iter_x(*data_, "x");
Expand Down
36 changes: 25 additions & 11 deletions nav2_collision_monitor/src/range.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,10 +31,11 @@ Range::Range(
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
const rclcpp::Duration & source_timeout)
const rclcpp::Duration & source_timeout,
const bool base_shift_correction)
: Source(
node, source_name, tf_buffer, base_frame_id, global_frame_id,
transform_tolerance, source_timeout),
transform_tolerance, source_timeout, base_shift_correction),
data_(nullptr)
{
RCLCPP_INFO(logger_, "[%s]: Creating Range", source_name_.c_str());
Expand Down Expand Up @@ -85,16 +86,29 @@ void Range::getData(
return;
}

// Obtaining the transform to get data from source frame and time where it was received
// to the base frame and current time
tf2::Transform tf_transform;
if (
!nav2_util::getTransform(
data_->header.frame_id, data_->header.stamp,
base_frame_id_, curr_time, global_frame_id_,
transform_tolerance_, tf_buffer_, tf_transform))
{
return;
if (base_shift_correction_) {
// Obtaining the transform to get data from source frame and time where it was received
// to the base frame and current time
if (
!nav2_util::getTransform(
data_->header.frame_id, data_->header.stamp,
base_frame_id_, curr_time, global_frame_id_,
transform_tolerance_, tf_buffer_, tf_transform))
{
return;
}
} else {
// Obtaining the transform to get data from source frame to base frame without time shift
// considered. Less accurate but much more faster option not dependent on state estimation
// frames.
if (
!nav2_util::getTransform(
data_->header.frame_id, base_frame_id_,
transform_tolerance_, tf_buffer_, tf_transform))
{
return;
}
}

// Calculate poses and refill data array
Expand Down
36 changes: 25 additions & 11 deletions nav2_collision_monitor/src/scan.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,10 +29,11 @@ Scan::Scan(
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
const rclcpp::Duration & source_timeout)
const rclcpp::Duration & source_timeout,
const bool base_shift_correction)
: Source(
node, source_name, tf_buffer, base_frame_id, global_frame_id,
transform_tolerance, source_timeout),
transform_tolerance, source_timeout, base_shift_correction),
data_(nullptr)
{
RCLCPP_INFO(logger_, "[%s]: Creating Scan", source_name_.c_str());
Expand Down Expand Up @@ -75,16 +76,29 @@ void Scan::getData(
return;
}

// Obtaining the transform to get data from source frame and time where it was received
// to the base frame and current time
tf2::Transform tf_transform;
if (
!nav2_util::getTransform(
data_->header.frame_id, data_->header.stamp,
base_frame_id_, curr_time, global_frame_id_,
transform_tolerance_, tf_buffer_, tf_transform))
{
return;
if (base_shift_correction_) {
// Obtaining the transform to get data from source frame and time where it was received
// to the base frame and current time
if (
!nav2_util::getTransform(
data_->header.frame_id, data_->header.stamp,
base_frame_id_, curr_time, global_frame_id_,
transform_tolerance_, tf_buffer_, tf_transform))
{
return;
}
} else {
// Obtaining the transform to get data from source frame to base frame without time shift
// considered. Less accurate but much more faster option not dependent on state estimation
// frames.
if (
!nav2_util::getTransform(
data_->header.frame_id, base_frame_id_,
transform_tolerance_, tf_buffer_, tf_transform))
{
return;
}
}

// Calculate poses and refill data array
Expand Down
6 changes: 4 additions & 2 deletions nav2_collision_monitor/src/source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,10 +30,12 @@ Source::Source(
const std::string & base_frame_id,
const std::string & global_frame_id,
const tf2::Duration & transform_tolerance,
const rclcpp::Duration & source_timeout)
const rclcpp::Duration & source_timeout,
const bool base_shift_correction)
: node_(node), source_name_(source_name), tf_buffer_(tf_buffer),
base_frame_id_(base_frame_id), global_frame_id_(global_frame_id),
transform_tolerance_(transform_tolerance), source_timeout_(source_timeout)
transform_tolerance_(transform_tolerance), source_timeout_(source_timeout),
base_shift_correction_(base_shift_correction)
{
}

Expand Down
Loading