Skip to content

Commit

Permalink
move per sensor param source_timeout logic to source.cpp
Browse files Browse the repository at this point in the history
  • Loading branch information
Guillaume Doisy committed Oct 27, 2023
1 parent 94587d0 commit e54293f
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 18 deletions.
12 changes: 3 additions & 9 deletions nav2_collision_monitor/src/collision_detector_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -259,32 +259,26 @@ bool CollisionDetector::configureSources(
rclcpp::ParameterValue("scan")); // Laser scanner by default
const std::string source_type = get_parameter(source_name + ".type").as_string();

nav2_util::declare_parameter_if_not_declared(
node, source_name + ".source_timeout",
rclcpp::ParameterValue(source_timeout.seconds())); // node source_timeout by default
const rclcpp::Duration sensor_specific_source_timeout = rclcpp::Duration::from_seconds(
get_parameter(source_name + ".source_timeout").as_double());

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

r->configure();

Expand Down
12 changes: 3 additions & 9 deletions nav2_collision_monitor/src/collision_monitor_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -325,32 +325,26 @@ bool CollisionMonitor::configureSources(
rclcpp::ParameterValue("scan")); // Laser scanner by default
const std::string source_type = get_parameter(source_name + ".type").as_string();

nav2_util::declare_parameter_if_not_declared(
node, source_name + ".source_timeout",
rclcpp::ParameterValue(source_timeout.seconds())); // node source_timeout by default
const rclcpp::Duration sensor_specific_source_timeout = rclcpp::Duration::from_seconds(
get_parameter(source_name + ".source_timeout").as_double());

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

r->configure();

Expand Down
6 changes: 6 additions & 0 deletions nav2_collision_monitor/src/source.cpp
Original file line number Diff line number Diff line change
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
source_timeout_ = rclcpp::Duration::from_seconds(
node->get_parameter(source_name_ + ".source_timeout").as_double());
}

bool Source::sourceValid(
Expand Down

0 comments on commit e54293f

Please sign in to comment.