Skip to content

Commit

Permalink
Wait on result
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon committed Jan 10, 2023
1 parent ff677c9 commit 85aa1bc
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 0 deletions.
1 change: 1 addition & 0 deletions fuse_models/src/graph_ignition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,6 +182,7 @@ void GraphIgnition::process(const fuse_msgs::msg::SerializedGraph& msg)
auto srv = std::make_shared<std_srvs::srv::Empty::Request>();
// No need to spin since node is optimizer node, which should be spinning
auto result_future = reset_client_->async_send_request(srv);
result_future.wait();
}

// Now that the optimizer has been reset, actually send the initial state constraints to the optimizer
Expand Down
1 change: 1 addition & 0 deletions fuse_models/src/unicycle_2d_ignition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -274,6 +274,7 @@ void Unicycle2DIgnition::process(const geometry_msgs::msg::PoseWithCovarianceSta
auto srv = std::make_shared<std_srvs::srv::Empty::Request>();
// No need to spin since node is optimizer node, which should be spinning
auto result_future = reset_client_->async_send_request(srv);
result_future.wait();
}

// Now that the pose has been validated and the optimizer has been reset, actually send the initial state constraints
Expand Down

0 comments on commit 85aa1bc

Please sign in to comment.