Skip to content
Snippets Groups Projects
Unverified Commit 369e62df authored by Sarthak Mittal's avatar Sarthak Mittal Committed by GitHub
Browse files

Fix nav2_waypoint_follower bugs due to upstream ROS2 changes (#2000)


* Fix nav2_waypoint_follower bugs

Signed-off-by: default avatarSarthak Mittal <sarthakmittal2608@gmail.com>

* Update function description

Signed-off-by: default avatarSarthak Mittal <sarthakmittal2608@gmail.com>
parent 182d3b3e
No related branches found
No related tags found
No related merge requests found
......@@ -106,10 +106,9 @@ protected:
/**
* @brief Action client goal response callback
* @param future Shared future to goalhandle
* @param goal Response of action server updated asynchronously
*/
void goalResponseCallback(
std::shared_future<rclcpp_action::ClientGoalHandle<ClientT>::SharedPtr> future);
void goalResponseCallback(const rclcpp_action::ClientGoalHandle<ClientT>::SharedPtr & goal);
// Our action server
std::unique_ptr<ActionServer> action_server_;
......
......@@ -246,10 +246,9 @@ WaypointFollower::resultCallback(
void
WaypointFollower::goalResponseCallback(
std::shared_future<rclcpp_action::ClientGoalHandle<ClientT>::SharedPtr> future)
const rclcpp_action::ClientGoalHandle<ClientT>::SharedPtr & goal)
{
auto goal_handle = future.get();
if (!goal_handle) {
if (!goal) {
RCLCPP_ERROR(
get_logger(),
"navigate_to_pose action client failed to send goal to server.");
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment