.. _program_listing_file_include_rclcpp_action_client_goal_handle_impl.hpp: Program Listing for File client_goal_handle_impl.hpp ==================================================== |exhale_lsh| :ref:`Return to documentation for file ` (``include/rclcpp_action/client_goal_handle_impl.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2018 Open Source Robotics Foundation, Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #ifndef RCLCPP_ACTION__CLIENT_GOAL_HANDLE_IMPL_HPP_ #define RCLCPP_ACTION__CLIENT_GOAL_HANDLE_IMPL_HPP_ #include #include #include "rclcpp/logging.hpp" #include "rclcpp_action/client_goal_handle.hpp" #include "rclcpp_action/exceptions.hpp" namespace rclcpp_action { template ClientGoalHandle::ClientGoalHandle( const GoalInfo & info, FeedbackCallback feedback_callback, ResultCallback result_callback) : info_(info), result_future_(result_promise_.get_future()), feedback_callback_(feedback_callback), result_callback_(result_callback) { } template ClientGoalHandle::~ClientGoalHandle() { } template const GoalUUID & ClientGoalHandle::get_goal_id() const { return info_.goal_id.uuid; } template rclcpp::Time ClientGoalHandle::get_goal_stamp() const { return info_.stamp; } template std::shared_future::WrappedResult> ClientGoalHandle::async_get_result() { std::lock_guard guard(handle_mutex_); if (!is_result_aware_) { throw exceptions::UnawareGoalHandleError(); } return result_future_; } template void ClientGoalHandle::set_result(const WrappedResult & wrapped_result) { std::lock_guard guard(handle_mutex_); status_ = static_cast(wrapped_result.code); result_promise_.set_value(wrapped_result); if (result_callback_) { result_callback_(wrapped_result); } } template void ClientGoalHandle::set_feedback_callback(FeedbackCallback callback) { std::lock_guard guard(handle_mutex_); feedback_callback_ = callback; } template void ClientGoalHandle::set_result_callback(ResultCallback callback) { std::lock_guard guard(handle_mutex_); result_callback_ = callback; } template int8_t ClientGoalHandle::get_status() { std::lock_guard guard(handle_mutex_); return status_; } template void ClientGoalHandle::set_status(int8_t status) { std::lock_guard guard(handle_mutex_); status_ = status; } template bool ClientGoalHandle::is_feedback_aware() { std::lock_guard guard(handle_mutex_); return feedback_callback_ != nullptr; } template bool ClientGoalHandle::is_result_aware() { std::lock_guard guard(handle_mutex_); return is_result_aware_; } template bool ClientGoalHandle::set_result_awareness(bool awareness) { std::lock_guard guard(handle_mutex_); bool previous = is_result_aware_; is_result_aware_ = awareness; return previous; } template void ClientGoalHandle::invalidate(const exceptions::UnawareGoalHandleError & ex) { std::lock_guard guard(handle_mutex_); // Guard against multiple calls if (is_invalidated()) { return; } is_result_aware_ = false; invalidate_exception_ = std::make_exception_ptr(ex); status_ = GoalStatus::STATUS_UNKNOWN; result_promise_.set_exception(invalidate_exception_); } template bool ClientGoalHandle::is_invalidated() const { return invalidate_exception_ != nullptr; } template void ClientGoalHandle::call_feedback_callback( typename ClientGoalHandle::SharedPtr shared_this, typename std::shared_ptr feedback_message) { if (shared_this.get() != this) { RCLCPP_ERROR(rclcpp::get_logger("rclcpp_action"), "Sent feedback to wrong goal handle."); return; } std::lock_guard guard(handle_mutex_); if (nullptr == feedback_callback_) { // Normal, some feedback messages may arrive after the goal result. RCLCPP_DEBUG(rclcpp::get_logger("rclcpp_action"), "Received feedback but goal ignores it."); return; } feedback_callback_(shared_this, feedback_message); } } // namespace rclcpp_action #endif // RCLCPP_ACTION__CLIENT_GOAL_HANDLE_IMPL_HPP_