Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
82 commits
Select commit Hold shift + click to select a range
50048eb
Add rough version of DeleteEntity
azeey Jul 22, 2025
7c6b474
Cleanup
azeey Jul 25, 2025
d5829f4
Add initial implementation for GetEntityState
azeey Jul 25, 2025
965859a
Add initial implementation for GetEntitiesStates
azeey Jul 25, 2025
fbc34a0
Add initial implementation for GetSimulationState
azeey Jul 25, 2025
7898841
Refactor
azeey Jul 25, 2025
05eaac0
Add GetSimulatorFeatures
azeey Jul 25, 2025
c418a2c
Add ResetSimulation
azeey Jul 25, 2025
054b56c
Add SetSimulationState
azeey Jul 25, 2025
0c0fe85
Add SpawnEntity
azeey Jul 25, 2025
f02fe82
Add StepSimulation
azeey Jul 25, 2025
7e29730
Add SimulateSteps action
azeey Jul 25, 2025
310e426
Large refactor
azeey Jul 29, 2025
f147f1f
Update CI to use nightlies from Jetty
azeey Jul 29, 2025
9852cf8
Fix typo
azeey Jul 29, 2025
06ffa9b
Include stable repos
azeey Jul 29, 2025
50ca3c5
Rename GazeboState to GazeboProxy
azeey Jul 31, 2025
5328944
Add GetEntityInfo
azeey Aug 1, 2025
a7ec767
Refactor get_entity_state
azeey Aug 1, 2025
305faf0
Simplify WithLocked
azeey Aug 1, 2025
5079fb3
Support EntityFilter
azeey Aug 1, 2025
7e44347
Add SetEntityState, but only for pose
azeey Aug 6, 2025
b6257f5
Support velocities for SetEntityState
azeey Aug 7, 2025
6c4724f
Add gazebo_proxy.cpp
azeey Aug 7, 2025
f743316
Run clang-format
azeey Aug 7, 2025
df10293
Support EntityFilters in GetEntitiesStates
azeey Aug 8, 2025
4f482db
Support getting velocities in GetEntityState
azeey Aug 13, 2025
b584150
Set velocities only on non-static models
azeey Aug 13, 2025
7d1918a
Update to simulation_interfaces 2.0
azeey Aug 14, 2025
9ae3723
Set header on state messages
azeey Aug 15, 2025
6583fb8
Add preliminary test
azeey Aug 15, 2025
64f719f
First meaningful test
azeey Aug 15, 2025
783b26a
Revert to using unique lock, fix race condition
azeey Aug 17, 2025
060f6f9
Add wait for updated state
azeey Aug 17, 2025
3387567
Handle newly created entities
azeey Aug 17, 2025
01ca3c2
Fix linter issues
azeey Aug 17, 2025
5df66ab
Handle newly created entities
azeey Aug 18, 2025
a5d7024
Use Gazebo's signal handlers
azeey Aug 18, 2025
8f9d5c5
Wait for services and topics
azeey Aug 19, 2025
bb79567
Fix linter issues
azeey Aug 19, 2025
9ee5bdf
Use sub-namespace for simulation_interfaces
azeey Aug 19, 2025
d258f7e
Depend on gz-sim to fix build order
azeey Aug 19, 2025
a29eeb6
Merge remote-tracking branch 'origin/ros2' into standard_interfaces
azeey Aug 19, 2025
dd990d5
Add API docs
azeey Aug 19, 2025
18064d0
Split out gz_entity_filter implementation into a cpp file
azeey Aug 19, 2025
74d7491
Add more API docs
azeey Aug 19, 2025
d18410f
Fix uncrustify
azeey Aug 19, 2025
0ff3086
Remove `simulation_interfaces` prefix per feedback
azeey Aug 22, 2025
e4db83e
Added tests covering all interfaces
sauk2 Aug 24, 2025
ccb16ee
Updated the test cases with comments
sauk2 Aug 24, 2025
d6bdc85
Style changes
sauk2 Aug 24, 2025
1de6c0d
Merge branch 'ros2' into standard_interfaces
ahcorde Aug 25, 2025
4434df4
Merge pull request #1 from sauk2/standard_interfaces
azeey Aug 25, 2025
19b2e34
Remove packages.osrfoundation.org as we only need to depend on vendor…
azeey Sep 8, 2025
72ba4a4
Build Jetty vendor packages from source
azeey Sep 8, 2025
acced3b
Add git
azeey Sep 8, 2025
3398a4b
Restore all commented out gz_vendor statements
azeey Sep 8, 2025
09d5c23
Add missing headers
azeey Sep 9, 2025
a649e5d
Address reviewr feedback
azeey Sep 9, 2025
821993e
fix uncrustify errors
azeey Sep 9, 2025
391fe45
Fix linter
azeey Sep 9, 2025
b3e37d4
Address reviewer feedback
azeey Sep 9, 2025
53a6ae8
Return an error code in GetEntitiesStates
azeey Sep 9, 2025
566f7c9
Don't build dartsim and ogre-next
azeey Sep 9, 2025
9c57205
Add missing headers, fix indentation, alphabetize
azeey Sep 9, 2025
237436c
Revert changes in build-and-test.sh now that Jetty vendor packages ha…
azeey Sep 10, 2025
6bcbc8a
Fix cpplint issues
azeey Sep 10, 2025
e855839
More uncrustify fixes
azeey Sep 10, 2025
a494331
Fix typos
azeey Sep 11, 2025
c49de80
Try to make the test less flaky
azeey Sep 11, 2025
6e05a1a
Fix flake8
azeey Sep 11, 2025
15e81b7
Reinitialize canonical links after reset
azeey Sep 26, 2025
2d3b276
Test set_entity_state
azeey Sep 26, 2025
1c6c699
Fix action namespace, print actual service/action name
azeey Sep 26, 2025
d8bbb15
Fix duplicate node warning, set GZ_IP once, check result in more places
azeey Sep 26, 2025
d8721f1
Fix crash at shutdown
azeey Sep 26, 2025
dfa43a0
Fix style
azeey Sep 26, 2025
3f37e64
Make reset and setting simulation state more reliable
azeey Sep 26, 2025
e0d970a
Handle existing goal, fix crash related to invalid goal during destru…
azeey Sep 26, 2025
b7f421b
Use CreateSubscriber to ensure that topics are unsubscribed during de…
azeey Sep 27, 2025
a2458fa
Fix style
azeey Sep 27, 2025
7dc79c6
Fix issue with running the SimulateSteps action repeatedly, add/fix test
azeey Sep 30, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
33 changes: 31 additions & 2 deletions ros_gz_sim/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,11 @@ find_package(gz-sim REQUIRED)
find_package(gz_transport_vendor REQUIRED)
find_package(gz-transport REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(rcpputils REQUIRED)
find_package(ros_gz_interfaces REQUIRED)
find_package(simulation_interfaces REQUIRED)
find_package(std_msgs REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_ros REQUIRED)
Expand Down Expand Up @@ -70,16 +72,42 @@ target_link_libraries(delete_entity ${PROJECT_NAME}_delete_entity
${builtin_interfaces_TARGETS}
${geometry_msgs_TARGETS}
${ros_gz_interfaces_TARGETS}
${simulation_intefaces_TARGETS}
rclcpp::rclcpp)
target_include_directories(delete_entity PUBLIC ${CLI11_INCLUDE_DIRS})

set(gz_simulation_interfaces_sources
src/gz_simulation_interfaces/gazebo_proxy.cpp
src/gz_simulation_interfaces/gz_entity_filters.cpp
src/gz_simulation_interfaces/gz_simulation_interfaces.cpp
src/gz_simulation_interfaces/utils.cpp

# Actions
src/gz_simulation_interfaces/actions/simulate_steps.cpp

# Services
src/gz_simulation_interfaces/services/delete_entity.cpp
src/gz_simulation_interfaces/services/get_entities.cpp
src/gz_simulation_interfaces/services/get_entities_states.cpp
src/gz_simulation_interfaces/services/get_entity_info.cpp
src/gz_simulation_interfaces/services/get_entity_state.cpp
src/gz_simulation_interfaces/services/get_simulation_state.cpp
src/gz_simulation_interfaces/services/get_simulator_features.cpp
src/gz_simulation_interfaces/services/reset_simulation.cpp
src/gz_simulation_interfaces/services/set_entity_state.cpp
src/gz_simulation_interfaces/services/set_simulation_state.cpp
src/gz_simulation_interfaces/services/spawn_entity.cpp
src/gz_simulation_interfaces/services/step_simulation.cpp
)

# gzserver_component
add_library(gzserver_component SHARED src/gzserver.cpp)
rclcpp_components_register_nodes(gzserver_component "ros_gz_sim::GzServer")
add_library(gzserver_component SHARED src/gzserver.cpp ${gz_simulation_interfaces_sources})
target_link_libraries(gzserver_component PUBLIC
${std_msgs_TARGETS}
${simulation_interfaces_TARGETS}
gz-sim::core
rclcpp::rclcpp
rclcpp_action::rclcpp_action
rclcpp_components::component
rclcpp_components::component_manager
)
Expand Down Expand Up @@ -294,6 +322,7 @@ if(BUILD_TESTING)

add_launch_test(test/test_create_node.launch.py TIMEOUT 200)
add_launch_test(test/test_remove_node.launch.py TIMEOUT 200)
add_launch_test(test/test_gz_simulation_interfaces.launch.py TIMEOUT 300)
endif()

ament_package()
40 changes: 40 additions & 0 deletions ros_gz_sim/include/ros_gz_sim/gz_simulation_interfaces.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
// Copyright 2025 Open Source Robotics Foundation
//
// 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 ROS_GZ_SIM__GZ_SIMULATION_INTERFACES_HPP_
#define ROS_GZ_SIM__GZ_SIMULATION_INTERFACES_HPP_

#include <memory>

#include <gz/utils/ImplPtr.hh>
#include <rclcpp/node.hpp>

namespace ros_gz_sim
{
namespace gz_simulation_interfaces
{
class GzSimulationInterfaces
{
public:
// Class constructor.
explicit GzSimulationInterfaces(std::shared_ptr<rclcpp::Node> node);

private:
/// \internal
/// \brief Private data pointer.
GZ_UTILS_UNIQUE_IMPL_PTR(dataPtr)
};
} // namespace gz_simulation_interfaces
} // namespace ros_gz_sim
#endif // ROS_GZ_SIM__GZ_SIMULATION_INTERFACES_HPP_
3 changes: 3 additions & 0 deletions ros_gz_sim/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -35,9 +35,11 @@
<depend>launch_ros</depend>
<depend>libgflags-dev</depend>
<depend>rclcpp</depend>
<depend>rclcpp_action</depend>
<depend>rclcpp_components</depend>
<depend>rcpputils</depend>
<depend>ros_gz_interfaces</depend>
<depend>simulation_interfaces</depend>
<depend>std_msgs</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
Expand All @@ -48,6 +50,7 @@
<test_depend>launch_ros</test_depend>
<test_depend>launch_testing</test_depend>
<test_depend>launch_testing_ament_cmake</test_depend>
<test_depend>ros_gz_bridge</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
183 changes: 183 additions & 0 deletions ros_gz_sim/src/gz_simulation_interfaces/actions/simulate_steps.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,183 @@
// Copyright 2025 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.

#include "simulate_steps.hpp"

#include <gz/msgs/boolean.pb.h>
#include <gz/msgs/world_control.pb.h>

#include <chrono>
#include <cstdint>
#include <future>
#include <limits>
#include <memory>
#include <string>

#include "../gazebo_proxy.hpp"
#include "simulation_interfaces/action/simulate_steps.hpp"

namespace ros_gz_sim
{
namespace gz_simulation_interfaces
{
namespace actions
{
using SimulateStepsAction = simulation_interfaces::action::SimulateSteps;
using GoalHandleSimulateSteps = rclcpp_action::ServerGoalHandle<SimulateStepsAction>;

SimulateSteps::SimulateSteps(
std::shared_ptr<rclcpp::Node> ros_node, std::shared_ptr<GazeboProxy> gz_proxy)
: HandlerBase(ros_node, gz_proxy)
{
const auto control_service = this->gz_proxy_->PrefixTopic("control");
if (!this->gz_proxy_->WaitForGzService(control_service)) {
RCLCPP_ERROR_STREAM(
this->ros_node_->get_logger(),
"Gazebo service [" << control_service << "] is not available. "
<< "The [SimulateSteps] interface will not function properly.");
}
auto goal_callback =
[](const rclcpp_action::GoalUUID &, std::shared_ptr<const SimulateStepsAction::Goal>) {
// TODO(azeey) Add console message that we've received the goal
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
};

auto cancel_cb =
[](const std::shared_ptr<GoalHandleSimulateSteps>) {
// TODO(azeey) Add console message that we've received the cancellation
return rclcpp_action::CancelResponse::ACCEPT;
};

auto accept_cb =
[this, control_service](const std::shared_ptr<GoalHandleSimulateSteps> goal_handle) {
// Note that this is not the same as SimulateStepsAction::Result, which is the typename
// associated with the Result of the action, which in turn contains a
// simulation_interfaces::msg::Result
using Result = simulation_interfaces::msg::Result;

// Adapted from https://github.com/ros-navigation/navigation2/blob/main/nav2_ros_common/include/nav2_ros_common/simple_action_server.hpp#L154
if (this->worker_future_.valid() && (
this->worker_future_.wait_for(std::chrono::milliseconds(0)) ==
std::future_status::timeout))
{
auto action_result = std::make_shared<SimulateStepsAction::Result>();
action_result->result.result = Result::RESULT_OPERATION_FAILED;
action_result->result.error_message = "Another goal is already running";
goal_handle->abort(action_result);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

When testing the simulate step action, the first action call works fine but subsequent action seems to fail and end up here saying another goal is running.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Fixed in 7dc79c6

return;
}

// Execute the task in a separate thread and return immediately.
this->worker_future_ = std::async(std::launch::async, [this, goal_handle, control_service]
{
const auto goal = goal_handle->get_goal();
auto action_result = std::make_shared<SimulateStepsAction::Result>();

if (goal->steps > std::numeric_limits<uint32_t>::max()) {
action_result->result.result = Result::RESULT_OPERATION_FAILED;
action_result->result.error_message =
"The requested number of steps exceeds the maximum supported value (max uint32)";
goal_handle->abort(action_result);
return;
}

if (!this->gz_proxy_->Paused()) {
action_result->result.result = Result::RESULT_OPERATION_FAILED;
action_result->result.error_message = "Simulation has to be paused before stepping";
goal_handle->abort(action_result);
return;
}

uint64_t num_iters_start = this->gz_proxy_->Iterations();

// TODO(azeey) Refactor this code since it's also used in the StepSimulation service.
gz::msgs::WorldControl gz_request;
gz_request.set_pause(true);
gz_request.set_step(true);
gz_request.set_multi_step(goal->steps);
bool gz_result;
gz::msgs::Boolean reply;
bool executed = this->gz_proxy_->GzNode()->Request(
control_service, gz_request, GazeboProxy::kGzServiceTimeoutMs, reply, gz_result);
if (!executed) {
action_result->result.result = Result::RESULT_OPERATION_FAILED;
action_result->result.error_message = "Timed out while trying to reset simulation";
goal_handle->abort(action_result);
} else if (action_result && reply.data()) {
// The request has succeeded, so now we listen to the stats and provide feedback.
action_result->result.result = Result::RESULT_OK;
auto feedback = std::make_shared<SimulateStepsAction::Feedback>();

while (rclcpp::ok()) {
if (!this->gz_proxy_->AssertUpdatedWorldStats(action_result->result)) {
goal_handle->abort(action_result);
}

auto iterations = this->gz_proxy_->Iterations();
feedback->completed_steps = iterations - num_iters_start;
feedback->remaining_steps = goal->steps - feedback->completed_steps;
goal_handle->publish_feedback(feedback);
// TODO(azeey) There is a bug in Gazebo where the stepping field is set to true only
// once immediately after the request to step instead of being true for the whole
// duration of steps. So we can't use this right now to determine if we need to
// break out early

// if (!this->world_stats_.stepping()) {
// break;
// }
if (feedback->remaining_steps == 0) {
break;
}

if (goal_handle->is_canceling()) {
goal_handle->canceled(action_result);
return;
}
}

if (rclcpp::ok() && goal_handle->is_active()) {
if (feedback->remaining_steps == 0) {
goal_handle->succeed(action_result);
} else {
action_result->result.result = Result::RESULT_OPERATION_FAILED;
action_result->result.error_message = "SimulateSteps was interrupted";
goal_handle->abort(action_result);
}
}
} else {
action_result->result.result = Result::RESULT_OPERATION_FAILED;
action_result->result.error_message =
"Unknown error while trying to reset simulation";
goal_handle->abort(action_result);
}
});
};

// For some reason, create_server doesn't respect the sub_namespace of the node.
const auto action_name = ros_node->get_effective_namespace() + "/simulate_steps";
this->action_handle_ = rclcpp_action::create_server<SimulateStepsAction>(
ros_node, action_name, goal_callback, cancel_cb, accept_cb);

RCLCPP_INFO_STREAM(ros_node->get_logger(), "Created action " << action_name);
}

SimulateSteps::~SimulateSteps()
{
if (this->worker_future_.valid()) {
this->worker_future_.wait();
}
}
} // namespace actions
} // namespace gz_simulation_interfaces
} // namespace ros_gz_sim
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
// Copyright 2025 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 GZ_SIMULATION_INTERFACES__ACTIONS__SIMULATE_STEPS_HPP_
#define GZ_SIMULATION_INTERFACES__ACTIONS__SIMULATE_STEPS_HPP_

#include <future>
#include <memory>

#include <rclcpp/node.hpp>
#include <rclcpp_action/rclcpp_action.hpp>

#include "../handler_base.hpp"

namespace ros_gz_sim
{

namespace gz_simulation_interfaces
{
class GazeboProxy;
namespace actions
{

/// \class SimulateSteps
/// \brief Implements the `simulation_interfaces/SimulateSteps` interface.
class SimulateSteps : public HandlerBase
{
public:
// Documentation inherited
SimulateSteps(std::shared_ptr<rclcpp::Node> node, std::shared_ptr<GazeboProxy> gz_proxy);
~SimulateSteps();

private:
// TODO(azeey) Refactor into base class
std::shared_ptr<rclcpp_action::ServerBase> action_handle_;
std::future<void> worker_future_;
};
} // namespace actions
} // namespace gz_simulation_interfaces
} // namespace ros_gz_sim
#endif // GZ_SIMULATION_INTERFACES__ACTIONS__SIMULATE_STEPS_HPP_
Loading
Loading