Skip to content

Commit

Permalink
- Removed added empty line
Browse files Browse the repository at this point in the history
- Renamed initialGuessCallback to initialPoseReceivedSrv
- Added new line to SetInitialPose service definition
- Removed mutex from initialPoseReceived
- Cleanup service server

Signed-off-by: Alexander Mock <[email protected]>
  • Loading branch information
amock committed Mar 16, 2024
1 parent bfa9184 commit 1bfb42e
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 6 deletions.
5 changes: 2 additions & 3 deletions nav2_amcl/include/nav2_amcl/amcl_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,9 +214,9 @@ class AmclNode : public nav2_util::LifecycleNode
// service server for providing an initial pose guess
rclcpp::Service<nav2_msgs::srv::SetInitialPose>::SharedPtr initial_guess_srv_;
/*
* @brief Service callback for a global relocalization request
* @brief Service callback for an initial pose guess request
*/
void initialGuessCallback(
void initialPoseReceivedSrv(
const std::shared_ptr<rmw_request_id_t> request_header,
const std::shared_ptr<nav2_msgs::srv::SetInitialPose::Request> request,
std::shared_ptr<nav2_msgs::srv::SetInitialPose::Response> response);
Expand All @@ -234,7 +234,6 @@ class AmclNode : public nav2_util::LifecycleNode
// Nomotion update control. Used to temporarily let amcl update samples even when no motion occurs
std::atomic<bool> force_update_{false};


// Odometry
/*
* @brief Initialize odometry
Expand Down
4 changes: 2 additions & 2 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -325,6 +325,7 @@ AmclNode::on_cleanup(const rclcpp_lifecycle::State & /*state*/)
// Get rid of the inputs first (services and message filter input), so we
// don't continue to process incoming messages
global_loc_srv_.reset();
initial_guess_srv_.reset();
nomotion_update_srv_.reset();
initial_pose_sub_.reset();
laser_scan_connection_.disconnect();
Expand Down Expand Up @@ -495,12 +496,11 @@ AmclNode::globalLocalizationCallback(
}

void
AmclNode::initialGuessCallback(
AmclNode::initialPoseReceivedSrv(
const std::shared_ptr<rmw_request_id_t>/*request_header*/,
const std::shared_ptr<nav2_msgs::srv::SetInitialPose::Request> req,
std::shared_ptr<nav2_msgs::srv::SetInitialPose::Response>/*res*/)
{
std::lock_guard<std::recursive_mutex> cfl(mutex_);
initialPoseReceived(std::make_shared<geometry_msgs::msg::PoseWithCovarianceStamped>(req->pose));
}

Expand Down
2 changes: 1 addition & 1 deletion nav2_msgs/srv/SetInitialPose.srv
Original file line number Diff line number Diff line change
@@ -1,2 +1,2 @@
geometry_msgs/PoseWithCovarianceStamped pose
---
---

0 comments on commit 1bfb42e

Please sign in to comment.