Skip to content

Commit

Permalink
AMCL: Set an initial guess by service call (ros-navigation#4182)
Browse files Browse the repository at this point in the history
* Added initial guess service. Signed-off-by: Alexander Mock

Signed-off-by: Alexander Mock <amock@uos.de>

* - Removed added empty line
- Renamed initialGuessCallback to initialPoseReceivedSrv
- Added new line to SetInitialPose service definition
- Removed mutex from initialPoseReceived
- Cleanup service server

Signed-off-by: Alexander Mock <amock@uos.de>

* added whitespace

Signed-off-by: Alexander Mock <amock@uos.de>

* renamed initial pose service in callback bind

Signed-off-by: Alexander Mock <amock@uos.de>

---------

Signed-off-by: Alexander Mock <amock@uos.de>
  • Loading branch information
aock authored and ajtudela committed Apr 19, 2024
1 parent 13faf32 commit 9601ee2
Show file tree
Hide file tree
Showing 4 changed files with 29 additions and 0 deletions.
11 changes: 11 additions & 0 deletions nav2_amcl/include/nav2_amcl/amcl_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@
#include "nav2_amcl/sensors/laser/laser.hpp"
#include "nav2_msgs/msg/particle.hpp"
#include "nav2_msgs/msg/particle_cloud.hpp"
#include "nav2_msgs/srv/set_initial_pose.hpp"
#include "nav_msgs/srv/set_map.hpp"
#include "sensor_msgs/msg/laser_scan.hpp"
#include "std_srvs/srv/empty.hpp"
Expand Down Expand Up @@ -210,6 +211,16 @@ class AmclNode : public nav2_util::LifecycleNode
const std::shared_ptr<std_srvs::srv::Empty::Request> request,
std::shared_ptr<std_srvs::srv::Empty::Response> response);

// service server for providing an initial pose guess
rclcpp::Service<nav2_msgs::srv::SetInitialPose>::SharedPtr initial_guess_srv_;
/*
* @brief Service callback for an initial pose guess request
*/
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);

// Let amcl update samples without requiring motion
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr nomotion_update_srv_;
/*
Expand Down
14 changes: 14 additions & 0 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();
executor_thread_.reset(); // to make sure initial_pose_sub_ completely exit
initial_pose_sub_.reset();
Expand Down Expand Up @@ -495,6 +496,15 @@ AmclNode::globalLocalizationCallback(
pf_init_ = false;
}

void
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*/)
{
initialPoseReceived(std::make_shared<geometry_msgs::msg::PoseWithCovarianceStamped>(req->pose));
}

// force nomotion updates (amcl updating without requiring motion)
void
AmclNode::nomotionUpdateCallback(
Expand Down Expand Up @@ -1544,6 +1554,10 @@ AmclNode::initServices()
"reinitialize_global_localization",
std::bind(&AmclNode::globalLocalizationCallback, this, _1, _2, _3));

initial_guess_srv_ = create_service<nav2_msgs::srv::SetInitialPose>(
"set_initial_pose",
std::bind(&AmclNode::initialPoseReceivedSrv, this, _1, _2, _3));

nomotion_update_srv_ = create_service<std_srvs::srv::Empty>(
"request_nomotion_update",
std::bind(&AmclNode::nomotionUpdateCallback, this, _1, _2, _3));
Expand Down
1 change: 1 addition & 0 deletions nav2_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ rosidl_generate_interfaces(${PROJECT_NAME}
"srv/ManageLifecycleNodes.srv"
"srv/LoadMap.srv"
"srv/SaveMap.srv"
"srv/SetInitialPose.srv"
"action/AssistedTeleop.action"
"action/BackUp.action"
"action/ComputePathToPose.action"
Expand Down
3 changes: 3 additions & 0 deletions nav2_msgs/srv/SetInitialPose.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
geometry_msgs/PoseWithCovarianceStamped pose
---

0 comments on commit 9601ee2

Please sign in to comment.