Skip to content

Commit ae92d97

Browse files
azeeysauk2ahcorde
authored
Implement ROS standard simulation interfaces (#790)
--------- Signed-off-by: Addisu Z. Taddese <[email protected]> Signed-off-by: Saurabh Kamat <[email protected]> Co-authored-by: Saurabh Kamat <[email protected]> Co-authored-by: Alejandro Hernández Cordero <[email protected]>
1 parent 64a87d5 commit ae92d97

40 files changed

+4042
-9
lines changed

ros_gz_sim/CMakeLists.txt

Lines changed: 31 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,9 +25,11 @@ find_package(gz-sim REQUIRED)
2525
find_package(gz_transport_vendor REQUIRED)
2626
find_package(gz-transport REQUIRED)
2727
find_package(rclcpp REQUIRED)
28+
find_package(rclcpp_action REQUIRED)
2829
find_package(rclcpp_components REQUIRED)
2930
find_package(rcpputils REQUIRED)
3031
find_package(ros_gz_interfaces REQUIRED)
32+
find_package(simulation_interfaces REQUIRED)
3133
find_package(std_msgs REQUIRED)
3234
find_package(tf2 REQUIRED)
3335
find_package(tf2_ros REQUIRED)
@@ -70,16 +72,42 @@ target_link_libraries(delete_entity ${PROJECT_NAME}_delete_entity
7072
${builtin_interfaces_TARGETS}
7173
${geometry_msgs_TARGETS}
7274
${ros_gz_interfaces_TARGETS}
75+
${simulation_intefaces_TARGETS}
7376
rclcpp::rclcpp)
7477
target_include_directories(delete_entity PUBLIC ${CLI11_INCLUDE_DIRS})
7578

79+
set(gz_simulation_interfaces_sources
80+
src/gz_simulation_interfaces/gazebo_proxy.cpp
81+
src/gz_simulation_interfaces/gz_entity_filters.cpp
82+
src/gz_simulation_interfaces/gz_simulation_interfaces.cpp
83+
src/gz_simulation_interfaces/utils.cpp
84+
85+
# Actions
86+
src/gz_simulation_interfaces/actions/simulate_steps.cpp
87+
88+
# Services
89+
src/gz_simulation_interfaces/services/delete_entity.cpp
90+
src/gz_simulation_interfaces/services/get_entities.cpp
91+
src/gz_simulation_interfaces/services/get_entities_states.cpp
92+
src/gz_simulation_interfaces/services/get_entity_info.cpp
93+
src/gz_simulation_interfaces/services/get_entity_state.cpp
94+
src/gz_simulation_interfaces/services/get_simulation_state.cpp
95+
src/gz_simulation_interfaces/services/get_simulator_features.cpp
96+
src/gz_simulation_interfaces/services/reset_simulation.cpp
97+
src/gz_simulation_interfaces/services/set_entity_state.cpp
98+
src/gz_simulation_interfaces/services/set_simulation_state.cpp
99+
src/gz_simulation_interfaces/services/spawn_entity.cpp
100+
src/gz_simulation_interfaces/services/step_simulation.cpp
101+
)
102+
76103
# gzserver_component
77-
add_library(gzserver_component SHARED src/gzserver.cpp)
78-
rclcpp_components_register_nodes(gzserver_component "ros_gz_sim::GzServer")
104+
add_library(gzserver_component SHARED src/gzserver.cpp ${gz_simulation_interfaces_sources})
79105
target_link_libraries(gzserver_component PUBLIC
80106
${std_msgs_TARGETS}
107+
${simulation_interfaces_TARGETS}
81108
gz-sim::core
82109
rclcpp::rclcpp
110+
rclcpp_action::rclcpp_action
83111
rclcpp_components::component
84112
rclcpp_components::component_manager
85113
)
@@ -294,6 +322,7 @@ if(BUILD_TESTING)
294322

295323
add_launch_test(test/test_create_node.launch.py TIMEOUT 200)
296324
add_launch_test(test/test_remove_node.launch.py TIMEOUT 200)
325+
add_launch_test(test/test_gz_simulation_interfaces.launch.py TIMEOUT 300)
297326
endif()
298327

299328
ament_package()
Lines changed: 40 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
// Copyright 2025 Open Source Robotics Foundation
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+
#ifndef ROS_GZ_SIM__GZ_SIMULATION_INTERFACES_HPP_
16+
#define ROS_GZ_SIM__GZ_SIMULATION_INTERFACES_HPP_
17+
18+
#include <memory>
19+
20+
#include <gz/utils/ImplPtr.hh>
21+
#include <rclcpp/node.hpp>
22+
23+
namespace ros_gz_sim
24+
{
25+
namespace gz_simulation_interfaces
26+
{
27+
class GzSimulationInterfaces
28+
{
29+
public:
30+
// Class constructor.
31+
explicit GzSimulationInterfaces(std::shared_ptr<rclcpp::Node> node);
32+
33+
private:
34+
/// \internal
35+
/// \brief Private data pointer.
36+
GZ_UTILS_UNIQUE_IMPL_PTR(dataPtr)
37+
};
38+
} // namespace gz_simulation_interfaces
39+
} // namespace ros_gz_sim
40+
#endif // ROS_GZ_SIM__GZ_SIMULATION_INTERFACES_HPP_

ros_gz_sim/package.xml

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,9 +35,11 @@
3535
<depend>launch_ros</depend>
3636
<depend>libgflags-dev</depend>
3737
<depend>rclcpp</depend>
38+
<depend>rclcpp_action</depend>
3839
<depend>rclcpp_components</depend>
3940
<depend>rcpputils</depend>
4041
<depend>ros_gz_interfaces</depend>
42+
<depend>simulation_interfaces</depend>
4143
<depend>std_msgs</depend>
4244
<depend>tf2</depend>
4345
<depend>tf2_ros</depend>
@@ -48,6 +50,7 @@
4850
<test_depend>launch_ros</test_depend>
4951
<test_depend>launch_testing</test_depend>
5052
<test_depend>launch_testing_ament_cmake</test_depend>
53+
<test_depend>ros_gz_bridge</test_depend>
5154

5255
<export>
5356
<build_type>ament_cmake</build_type>
Lines changed: 183 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,183 @@
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
Lines changed: 52 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,52 @@
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+
#ifndef GZ_SIMULATION_INTERFACES__ACTIONS__SIMULATE_STEPS_HPP_
16+
#define GZ_SIMULATION_INTERFACES__ACTIONS__SIMULATE_STEPS_HPP_
17+
18+
#include <future>
19+
#include <memory>
20+
21+
#include <rclcpp/node.hpp>
22+
#include <rclcpp_action/rclcpp_action.hpp>
23+
24+
#include "../handler_base.hpp"
25+
26+
namespace ros_gz_sim
27+
{
28+
29+
namespace gz_simulation_interfaces
30+
{
31+
class GazeboProxy;
32+
namespace actions
33+
{
34+
35+
/// \class SimulateSteps
36+
/// \brief Implements the `simulation_interfaces/SimulateSteps` interface.
37+
class SimulateSteps : public HandlerBase
38+
{
39+
public:
40+
// Documentation inherited
41+
SimulateSteps(std::shared_ptr<rclcpp::Node> node, std::shared_ptr<GazeboProxy> gz_proxy);
42+
~SimulateSteps();
43+
44+
private:
45+
// TODO(azeey) Refactor into base class
46+
std::shared_ptr<rclcpp_action::ServerBase> action_handle_;
47+
std::future<void> worker_future_;
48+
};
49+
} // namespace actions
50+
} // namespace gz_simulation_interfaces
51+
} // namespace ros_gz_sim
52+
#endif // GZ_SIMULATION_INTERFACES__ACTIONS__SIMULATE_STEPS_HPP_

0 commit comments

Comments
 (0)