Skip to content

Commit

Permalink
Initialize inflate_cone_ variable. (#1988)
Browse files Browse the repository at this point in the history
* Initialize inflate_cone_ variable.

* initialize inflate_cone_ based on parameter.

* Increase the sleep time in the tests makes the costmap test always succeed on my machine.
  • Loading branch information
wilcobonestroo authored and SteveMacenski committed Nov 4, 2020
1 parent 1ce77b8 commit e51b5b5
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
2 changes: 1 addition & 1 deletion nav2_costmap_2d/plugins/range_sensor_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ void RangeSensorLayer::onInitialize()
declareParameter("phi", rclcpp::ParameterValue(1.2));
node_->get_parameter(name_ + "." + "phi", phi_v_);
declareParameter("inflate_cone", rclcpp::ParameterValue(1.0));
node_->get_parameter(name_ + "." + "phi", phi_v_);
node->get_parameter(name_ + "." + "inflate_cone", inflate_cone_);
declareParameter("no_readings_timeout", rclcpp::ParameterValue(0.0));
node_->get_parameter(name_ + "." + "no_readings_timeout", no_readings_timeout_);
declareParameter("clear_threshold", rclcpp::ParameterValue(0.2));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -183,7 +183,7 @@ class TestCollisionChecker : public nav2_util::LifecycleNode
setPose(x, y, theta);
publishFootprint();
publishCostmap();
rclcpp::sleep_for(std::chrono::milliseconds(50));
rclcpp::sleep_for(std::chrono::milliseconds(1000));
return collision_checker_->isCollisionFree(pose);
}

Expand Down

0 comments on commit e51b5b5

Please sign in to comment.