Skip to content

Commit

Permalink
Your future hasn't been written yet, no one's has. Your future is wha…
Browse files Browse the repository at this point in the history
…tever you make it, so make it a good one.
  • Loading branch information
DLu committed Apr 14, 2022
1 parent ca16e96 commit 515627a
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -212,8 +212,7 @@ bool HybridPlanningManager::sendGlobalPlannerAction()

// Add goal response callback
global_goal_options.goal_response_callback =
[this](std::shared_future<rclcpp_action::ClientGoalHandle<moveit_msgs::action::GlobalPlanner>::SharedPtr> future) {
auto const& goal_handle = future.get();
[this](rclcpp_action::ClientGoalHandle<moveit_msgs::action::GlobalPlanner>::SharedPtr goal_handle) {
auto planning_progress = std::make_shared<moveit_msgs::action::HybridPlanner::Feedback>();
auto& feedback = planning_progress->feedback;
if (!goal_handle)
Expand Down Expand Up @@ -283,8 +282,7 @@ bool HybridPlanningManager::sendLocalPlannerAction()

// Add goal response callback
local_goal_options.goal_response_callback =
[this](std::shared_future<rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::SharedPtr> future) {
auto const& goal_handle = future.get();
[this](rclcpp_action::ClientGoalHandle<moveit_msgs::action::LocalPlanner>::SharedPtr goal_handle) {
auto planning_progress = std::make_shared<moveit_msgs::action::HybridPlanner::Feedback>();
auto& feedback = planning_progress->feedback;
if (!goal_handle)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -762,8 +762,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl
auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::MoveGroup>::SendGoalOptions();

send_goal_opts.goal_response_callback =
[&](std::shared_future<rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::SharedPtr> future) {
const auto& goal_handle = future.get();
[&](rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::SharedPtr goal_handle) {
if (!goal_handle)
{
done = true;
Expand Down Expand Up @@ -841,8 +840,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl
auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::MoveGroup>::SendGoalOptions();

send_goal_opts.goal_response_callback =
[&](std::shared_future<rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::SharedPtr> future) {
const auto& goal_handle = future.get();
[&](rclcpp_action::ClientGoalHandle<moveit_msgs::action::MoveGroup>::SharedPtr goal_handle) {
if (!goal_handle)
{
done = true;
Expand Down Expand Up @@ -906,9 +904,7 @@ class MoveGroupInterface::MoveGroupInterfaceImpl
auto send_goal_opts = rclcpp_action::Client<moveit_msgs::action::ExecuteTrajectory>::SendGoalOptions();

send_goal_opts.goal_response_callback =
[&](std::shared_future<rclcpp_action::ClientGoalHandle<moveit_msgs::action::ExecuteTrajectory>::SharedPtr>
future) {
const auto& goal_handle = future.get();
[&](rclcpp_action::ClientGoalHandle<moveit_msgs::action::ExecuteTrajectory>::SharedPtr goal_handle) {
if (!goal_handle)
{
done = true;
Expand Down

0 comments on commit 515627a

Please sign in to comment.