Skip to content

Commit

Permalink
backport pull-request ros-navigation#2712 to foxy (ros-navigation#2776)
Browse files Browse the repository at this point in the history
  • Loading branch information
Jannkar authored Jan 19, 2022
1 parent 8a8b4d2 commit d1ed5e4
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 0 deletions.
1 change: 1 addition & 0 deletions nav2_amcl/include/nav2_amcl/amcl_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,6 +160,7 @@ class AmclNode : public nav2_util::LifecycleNode
// Pose-generating function used to uniformly distribute particles over the map
static pf_vector_t uniformPoseGenerator(void * arg);
pf_t * pf_{nullptr};
std::mutex pf_mutex_;
bool pf_init_;
pf_vector_t pf_odom_pose_;
int resample_count_{0};
Expand Down
6 changes: 6 additions & 0 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -505,6 +505,8 @@ AmclNode::globalLocalizationCallback(
const std::shared_ptr<std_srvs::srv::Empty::Request>/*req*/,
std::shared_ptr<std_srvs::srv::Empty::Response>/*res*/)
{
std::lock_guard<std::mutex> lock(pf_mutex_);

RCLCPP_INFO(get_logger(), "Initializing with uniform distribution");

pf_init_model(
Expand All @@ -529,6 +531,8 @@ AmclNode::nomotionUpdateCallback(
void
AmclNode::initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg)
{
std::lock_guard<std::mutex> lock(pf_mutex_);

RCLCPP_INFO(get_logger(), "initialPoseReceived");

if (msg->header.frame_id == "") {
Expand Down Expand Up @@ -626,6 +630,8 @@ AmclNode::handleInitialPose(geometry_msgs::msg::PoseWithCovarianceStamped & msg)
void
AmclNode::laserReceived(sensor_msgs::msg::LaserScan::ConstSharedPtr laser_scan)
{
std::lock_guard<std::mutex> lock(pf_mutex_);

// Since the sensor data is continually being published by the simulator or robot,
// we don't want our callbacks to fire until we're in the active state
if (!active_) {return;}
Expand Down

0 comments on commit d1ed5e4

Please sign in to comment.