| 
 | 1 | +// Copyright 2025 Open Source Robotics Foundation, Inc.  | 
 | 2 | +//  | 
 | 3 | +// Licensed under the Apache License, Version 2.0 (the "License");  | 
 | 4 | +// you may not use this file except in compliance with the License.  | 
 | 5 | +// You may obtain a copy of the License at  | 
 | 6 | +//  | 
 | 7 | +//     http://www.apache.org/licenses/LICENSE-2.0  | 
 | 8 | +//  | 
 | 9 | +// Unless required by applicable law or agreed to in writing, software  | 
 | 10 | +// distributed under the License is distributed on an "AS IS" BASIS,  | 
 | 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  | 
 | 12 | +// See the License for the specific language governing permissions and  | 
 | 13 | +// limitations under the License.  | 
 | 14 | + | 
 | 15 | +#include "simulate_steps.hpp"  | 
 | 16 | + | 
 | 17 | +#include <gz/msgs/boolean.pb.h>  | 
 | 18 | +#include <gz/msgs/world_control.pb.h>  | 
 | 19 | + | 
 | 20 | +#include <chrono>  | 
 | 21 | +#include <cstdint>  | 
 | 22 | +#include <future>  | 
 | 23 | +#include <limits>  | 
 | 24 | +#include <memory>  | 
 | 25 | +#include <string>  | 
 | 26 | + | 
 | 27 | +#include "../gazebo_proxy.hpp"  | 
 | 28 | +#include "simulation_interfaces/action/simulate_steps.hpp"  | 
 | 29 | + | 
 | 30 | +namespace ros_gz_sim  | 
 | 31 | +{  | 
 | 32 | +namespace gz_simulation_interfaces  | 
 | 33 | +{  | 
 | 34 | +namespace actions  | 
 | 35 | +{  | 
 | 36 | +using SimulateStepsAction = simulation_interfaces::action::SimulateSteps;  | 
 | 37 | +using GoalHandleSimulateSteps = rclcpp_action::ServerGoalHandle<SimulateStepsAction>;  | 
 | 38 | + | 
 | 39 | +SimulateSteps::SimulateSteps(  | 
 | 40 | +  std::shared_ptr<rclcpp::Node> ros_node, std::shared_ptr<GazeboProxy> gz_proxy)  | 
 | 41 | +: HandlerBase(ros_node, gz_proxy)  | 
 | 42 | +{  | 
 | 43 | +  const auto control_service = this->gz_proxy_->PrefixTopic("control");  | 
 | 44 | +  if (!this->gz_proxy_->WaitForGzService(control_service)) {  | 
 | 45 | +    RCLCPP_ERROR_STREAM(  | 
 | 46 | +      this->ros_node_->get_logger(),  | 
 | 47 | +      "Gazebo service [" << control_service << "] is not available. "  | 
 | 48 | +                         << "The [SimulateSteps] interface will not function properly.");  | 
 | 49 | +  }  | 
 | 50 | +  auto goal_callback =  | 
 | 51 | +    [](const rclcpp_action::GoalUUID &, std::shared_ptr<const SimulateStepsAction::Goal>) {  | 
 | 52 | +      // TODO(azeey) Add console message that we've received the goal  | 
 | 53 | +      return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;  | 
 | 54 | +    };  | 
 | 55 | + | 
 | 56 | +  auto cancel_cb =  | 
 | 57 | +    [](const std::shared_ptr<GoalHandleSimulateSteps>) {  | 
 | 58 | +      // TODO(azeey) Add console message that we've received the cancellation  | 
 | 59 | +      return rclcpp_action::CancelResponse::ACCEPT;  | 
 | 60 | +    };  | 
 | 61 | + | 
 | 62 | +  auto accept_cb =  | 
 | 63 | +    [this, control_service](const std::shared_ptr<GoalHandleSimulateSteps> goal_handle) {  | 
 | 64 | +      // Note that this is not the same as SimulateStepsAction::Result, which is the typename  | 
 | 65 | +      // associated with the Result of the action, which in turn contains a  | 
 | 66 | +      // simulation_interfaces::msg::Result  | 
 | 67 | +      using Result = simulation_interfaces::msg::Result;  | 
 | 68 | + | 
 | 69 | +      // Adapted from https://github.com/ros-navigation/navigation2/blob/main/nav2_ros_common/include/nav2_ros_common/simple_action_server.hpp#L154  | 
 | 70 | +      if (this->worker_future_.valid() && (  | 
 | 71 | +          this->worker_future_.wait_for(std::chrono::milliseconds(0)) ==  | 
 | 72 | +          std::future_status::timeout))  | 
 | 73 | +      {  | 
 | 74 | +        auto action_result = std::make_shared<SimulateStepsAction::Result>();  | 
 | 75 | +        action_result->result.result = Result::RESULT_OPERATION_FAILED;  | 
 | 76 | +        action_result->result.error_message = "Another goal is already running";  | 
 | 77 | +        goal_handle->abort(action_result);  | 
 | 78 | +        return;  | 
 | 79 | +      }  | 
 | 80 | + | 
 | 81 | +      // Execute the task in a separate thread and return immediately.  | 
 | 82 | +      this->worker_future_ = std::async(std::launch::async, [this, goal_handle, control_service]  | 
 | 83 | +          {  | 
 | 84 | +            const auto goal = goal_handle->get_goal();  | 
 | 85 | +            auto action_result = std::make_shared<SimulateStepsAction::Result>();  | 
 | 86 | + | 
 | 87 | +            if (goal->steps > std::numeric_limits<uint32_t>::max()) {  | 
 | 88 | +              action_result->result.result = Result::RESULT_OPERATION_FAILED;  | 
 | 89 | +              action_result->result.error_message =  | 
 | 90 | +              "The requested number of steps exceeds the maximum supported value (max uint32)";  | 
 | 91 | +              goal_handle->abort(action_result);  | 
 | 92 | +              return;  | 
 | 93 | +            }  | 
 | 94 | + | 
 | 95 | +            if (!this->gz_proxy_->Paused()) {  | 
 | 96 | +              action_result->result.result = Result::RESULT_OPERATION_FAILED;  | 
 | 97 | +              action_result->result.error_message = "Simulation has to be paused before stepping";  | 
 | 98 | +              goal_handle->abort(action_result);  | 
 | 99 | +              return;  | 
 | 100 | +            }  | 
 | 101 | + | 
 | 102 | +            uint64_t num_iters_start = this->gz_proxy_->Iterations();  | 
 | 103 | + | 
 | 104 | +            // TODO(azeey) Refactor this code since it's also used in the StepSimulation service.  | 
 | 105 | +            gz::msgs::WorldControl gz_request;  | 
 | 106 | +            gz_request.set_pause(true);  | 
 | 107 | +            gz_request.set_step(true);  | 
 | 108 | +            gz_request.set_multi_step(goal->steps);  | 
 | 109 | +            bool gz_result;  | 
 | 110 | +            gz::msgs::Boolean reply;  | 
 | 111 | +            bool executed = this->gz_proxy_->GzNode()->Request(  | 
 | 112 | +              control_service, gz_request, GazeboProxy::kGzServiceTimeoutMs, reply, gz_result);  | 
 | 113 | +            if (!executed) {  | 
 | 114 | +              action_result->result.result = Result::RESULT_OPERATION_FAILED;  | 
 | 115 | +              action_result->result.error_message = "Timed out while trying to reset simulation";  | 
 | 116 | +              goal_handle->abort(action_result);  | 
 | 117 | +            } else if (action_result && reply.data()) {  | 
 | 118 | +              // The request has succeeded, so now we listen to the stats and provide feedback.  | 
 | 119 | +              action_result->result.result = Result::RESULT_OK;  | 
 | 120 | +              auto feedback = std::make_shared<SimulateStepsAction::Feedback>();  | 
 | 121 | + | 
 | 122 | +              while (rclcpp::ok()) {  | 
 | 123 | +                if (!this->gz_proxy_->AssertUpdatedWorldStats(action_result->result)) {  | 
 | 124 | +                  goal_handle->abort(action_result);  | 
 | 125 | +                }  | 
 | 126 | + | 
 | 127 | +                auto iterations = this->gz_proxy_->Iterations();  | 
 | 128 | +                feedback->completed_steps = iterations - num_iters_start;  | 
 | 129 | +                feedback->remaining_steps = goal->steps - feedback->completed_steps;  | 
 | 130 | +                goal_handle->publish_feedback(feedback);  | 
 | 131 | +                // TODO(azeey) There is a bug in Gazebo where the stepping field is set to true only  | 
 | 132 | +                // once immediately after the request to step instead of being true for the whole  | 
 | 133 | +                // duration of steps. So we can't use this right now to determine if we need to  | 
 | 134 | +                // break out early  | 
 | 135 | + | 
 | 136 | +                // if (!this->world_stats_.stepping()) {  | 
 | 137 | +                //   break;  | 
 | 138 | +                // }  | 
 | 139 | +                if (feedback->remaining_steps == 0) {  | 
 | 140 | +                  break;  | 
 | 141 | +                }  | 
 | 142 | + | 
 | 143 | +                if (goal_handle->is_canceling()) {  | 
 | 144 | +                  goal_handle->canceled(action_result);  | 
 | 145 | +                  return;  | 
 | 146 | +                }  | 
 | 147 | +              }  | 
 | 148 | + | 
 | 149 | +              if (rclcpp::ok() && goal_handle->is_active()) {  | 
 | 150 | +                if (feedback->remaining_steps == 0) {  | 
 | 151 | +                  goal_handle->succeed(action_result);  | 
 | 152 | +                } else {  | 
 | 153 | +                  action_result->result.result = Result::RESULT_OPERATION_FAILED;  | 
 | 154 | +                  action_result->result.error_message = "SimulateSteps was interrupted";  | 
 | 155 | +                  goal_handle->abort(action_result);  | 
 | 156 | +                }  | 
 | 157 | +              }  | 
 | 158 | +            } else {  | 
 | 159 | +              action_result->result.result = Result::RESULT_OPERATION_FAILED;  | 
 | 160 | +              action_result->result.error_message =  | 
 | 161 | +              "Unknown error while trying to reset simulation";  | 
 | 162 | +              goal_handle->abort(action_result);  | 
 | 163 | +            }  | 
 | 164 | +          });  | 
 | 165 | +    };  | 
 | 166 | + | 
 | 167 | +  // For some reason, create_server doesn't respect the sub_namespace of the node.  | 
 | 168 | +  const auto action_name = ros_node->get_effective_namespace() + "/simulate_steps";  | 
 | 169 | +  this->action_handle_ = rclcpp_action::create_server<SimulateStepsAction>(  | 
 | 170 | +    ros_node, action_name, goal_callback, cancel_cb, accept_cb);  | 
 | 171 | + | 
 | 172 | +  RCLCPP_INFO_STREAM(ros_node->get_logger(), "Created action " << action_name);  | 
 | 173 | +}  | 
 | 174 | + | 
 | 175 | +SimulateSteps::~SimulateSteps()  | 
 | 176 | +{  | 
 | 177 | +  if (this->worker_future_.valid()) {  | 
 | 178 | +    this->worker_future_.wait();  | 
 | 179 | +  }  | 
 | 180 | +}  | 
 | 181 | +}  // namespace actions  | 
 | 182 | +}  // namespace gz_simulation_interfaces  | 
 | 183 | +}  // namespace ros_gz_sim  | 
0 commit comments