diff --git a/examples/worlds/ground_spacecraft_testbed.sdf b/examples/worlds/ground_spacecraft_testbed.sdf
new file mode 100644
index 0000000000..9d061f2fdd
--- /dev/null
+++ b/examples/worlds/ground_spacecraft_testbed.sdf
@@ -0,0 +1,77 @@
+
+
+
+
+ 0 0 -9.8066
+
+ 0.001
+ 1.0
+
+
+
+
+
+
+
+
+ ogre2
+
+
+ true
+ 0 0 10 0 0 0
+ 0.8 0.8 0.8 1
+ 0.2 0.2 0.2 1
+
+ 1000
+ 0.9
+ 0.01
+ 0.001
+
+ -0.5 0.1 -0.9
+
+
+ true
+
+
+
+
+ 0 0 1
+ 100 100
+
+
+
+
+
+
+ 0 0 1
+ 100 100
+
+
+
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+ 0.8 0.8 0.8 1
+
+
+
+
+
+ 0 0 0 0 0 0
+ https://fuel.gazebosim.org/1.0/proque/models/kth_freeflyer
+
+
+
diff --git a/examples/worlds/spacecraft.sdf b/examples/worlds/spacecraft.sdf
new file mode 100644
index 0000000000..b28090c283
--- /dev/null
+++ b/examples/worlds/spacecraft.sdf
@@ -0,0 +1,51 @@
+
+
+
+
+ 0 0 0
+
+ 0.001
+ 1.0
+
+
+
+
+
+
+
+
+ ogre2
+
+
+ true
+ 0 0 10 0 0 0
+ 0.8 0.8 0.8 1
+ 0.2 0.2 0.2 1
+
+ 1000
+ 0.9
+ 0.01
+ 0.001
+
+ -0.5 0.1 -0.9
+
+
+ 0 0 0 0 0 0
+ https://fuel.gazebosim.org/1.0/proque/models/dart/7
+
+
+
diff --git a/src/systems/CMakeLists.txt b/src/systems/CMakeLists.txt
index e09c0a6030..38b424583e 100644
--- a/src/systems/CMakeLists.txt
+++ b/src/systems/CMakeLists.txt
@@ -152,6 +152,7 @@ add_subdirectory(rf_comms)
add_subdirectory(scene_broadcaster)
add_subdirectory(sensors)
add_subdirectory(shader_param)
+add_subdirectory(spacecraft_thruster_model)
add_subdirectory(thermal)
add_subdirectory(thruster)
add_subdirectory(touch_plugin)
diff --git a/src/systems/spacecraft_thruster_model/CMakeLists.txt b/src/systems/spacecraft_thruster_model/CMakeLists.txt
new file mode 100644
index 0000000000..9554f52dd1
--- /dev/null
+++ b/src/systems/spacecraft_thruster_model/CMakeLists.txt
@@ -0,0 +1,6 @@
+gz_add_system(spacecraft-thruster-model
+ SOURCES
+ SpacecraftThrusterModel.cc
+ PUBLIC_LINK_LIBS
+ gz-common${GZ_COMMON_VER}::gz-common${GZ_COMMON_VER}
+)
diff --git a/src/systems/spacecraft_thruster_model/SpacecraftThrusterModel.cc b/src/systems/spacecraft_thruster_model/SpacecraftThrusterModel.cc
new file mode 100644
index 0000000000..7f65212ae1
--- /dev/null
+++ b/src/systems/spacecraft_thruster_model/SpacecraftThrusterModel.cc
@@ -0,0 +1,383 @@
+/*
+ * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland
+ * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland
+ * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland
+ * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland
+ * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
+ * Copyright 2016 Geoffrey Hunter
+ * Copyright (C) 2024 Open Source Robotics Foundation
+ * Copyright (C) 2024 Benjamin Perseghetti, Rudis Laboratories
+ * Copyright (C) 2024 Pedro Roque, DCS, KTH, Sweden
+ *
+ * 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 "SpacecraftThrusterModel.hh"
+
+#include
+#include
+#include
+#include
+
+#include
+
+#include
+
+#include
+#include
+
+#include
+#include
+#include
+#include
+
+#include
+
+#include "gz/sim/components/Actuators.hh"
+#include "gz/sim/components/ExternalWorldWrenchCmd.hh"
+#include "gz/sim/components/Pose.hh"
+#include "gz/sim/Link.hh"
+#include "gz/sim/Model.hh"
+#include "gz/sim/Util.hh"
+
+using namespace gz;
+using namespace sim;
+using namespace systems;
+
+class gz::sim::systems::SpacecraftThrusterModelPrivate
+{
+ /// \brief Callback for actuator commands.
+ public: void OnActuatorMsg(const msgs::Actuators &_msg);
+
+ /// \brief Apply link forces and moments based on propeller state.
+ public: void UpdateForcesAndMoments(EntityComponentManager &_ecm);
+
+ /// \brief Link Entity
+ public: Entity linkEntity;
+
+ /// \brief Link name
+ public: std::string linkName;
+
+ /// \brief Model interface
+ public: Model model{kNullEntity};
+
+ /// \brief sub topic for actuator commands.
+ public: std::string subTopic;
+
+ /// \brief Topic namespace.
+ public: std::string topic;
+
+ /// \brief Simulation time tracker
+ public: double simTime = 0.01;
+
+ /// \brief Index of motor in Actuators msg on multirotor_base.
+ public: int actuatorNumber = 0;
+
+ /// \brief Duty cycle frequency
+ public: double dutyCycleFrequency = 10.0;
+
+ /// \brief Cycle start time
+ public: double cycleStartTime = 0.0;
+
+ /// \brief Sampling time with the cycle period.
+ public: double samplingTime = 0.01;
+
+ /// \brief Actuator maximum thrust
+ public: double maxThrust = 0.0;
+
+ /// \brief Received Actuators message. This is nullopt if no message has been
+ /// received.
+ public: std::optional recvdActuatorsMsg;
+
+ /// \brief Mutex to protect recvdActuatorsMsg.
+ public: std::mutex recvdActuatorsMsgMutex;
+
+ /// \brief Gazebo communication node.
+ public: transport::Node node;
+};
+
+//////////////////////////////////////////////////
+SpacecraftThrusterModel::SpacecraftThrusterModel()
+ : dataPtr(std::make_unique())
+{
+}
+
+//////////////////////////////////////////////////
+void SpacecraftThrusterModel::Configure(const Entity &_entity,
+ const std::shared_ptr &_sdf,
+ EntityComponentManager &_ecm,
+ EventManager &/*_eventMgr*/)
+{
+ this->dataPtr->model = Model(_entity);
+
+ if (!this->dataPtr->model.Valid(_ecm))
+ {
+ gzerr << "SpacecraftThrusterModel plugin should be attached to a model "
+ << "entity. Failed to initialize." << std::endl;
+ return;
+ }
+
+ auto sdfClone = _sdf->Clone();
+
+ this->dataPtr->topic.clear();
+
+ if (sdfClone->HasElement("topic"))
+ {
+ this->dataPtr->topic =
+ sdfClone->Get("topic");
+ }
+ else
+ {
+ gzwarn << "No topic set using entity name.\n";
+ this->dataPtr->topic = this->dataPtr->model.Name(_ecm);
+ }
+
+ if (sdfClone->HasElement("link_name"))
+ {
+ this->dataPtr->linkName = sdfClone->Get("link_name");
+ }
+
+ if (this->dataPtr->linkName.empty())
+ {
+ gzerr << "SpacecraftThrusterModel found an empty link_name parameter. "
+ << "Failed to initialize.";
+ return;
+ }
+
+ if (sdfClone->HasElement("actuator_number"))
+ {
+ this->dataPtr->actuatorNumber =
+ sdfClone->GetElement("actuator_number")->Get();
+ }
+ else
+ {
+ gzerr << "Please specify a actuator_number.\n";
+ }
+
+ if (sdfClone->HasElement("max_thrust"))
+ {
+ this->dataPtr->maxThrust =
+ sdfClone->GetElement("max_thrust")->Get();
+ }
+ else
+ {
+ gzerr << "Please specify actuator "
+ << this->dataPtr->actuatorNumber <<" max_thrust.\n";
+ }
+
+ if (sdfClone->HasElement("duty_cycle_frequency"))
+ {
+ this->dataPtr->dutyCycleFrequency =
+ sdfClone->GetElement("duty_cycle_frequency")->Get();
+ }
+ else
+ {
+ gzerr << "Please specify actuator "
+ << this->dataPtr->actuatorNumber <<" duty_cycle_frequency.\n";
+ }
+
+ std::string topic;
+ if (sdfClone->HasElement("sub_topic"))
+ {
+ this->dataPtr->subTopic =
+ sdfClone->Get("sub_topic");
+ topic = transport::TopicUtils::AsValidTopic(
+ this->dataPtr->topic + "/" + this->dataPtr->subTopic);
+ }
+ else
+ {
+ topic = transport::TopicUtils::AsValidTopic(
+ this->dataPtr->topic);
+ }
+
+ // Subscribe to actuator command message
+ if (topic.empty())
+ {
+ gzerr << "Failed to create topic for [" << this->dataPtr->topic
+ << "]" << std::endl;
+ return;
+ }
+ else
+ {
+ gzdbg << "Listening to topic: " << topic << std::endl;
+ }
+ this->dataPtr->node.Subscribe(topic,
+ &SpacecraftThrusterModelPrivate::OnActuatorMsg, this->dataPtr.get());
+
+ // Look for components
+ // If the link hasn't been identified yet, look for it
+ if (this->dataPtr->linkEntity == kNullEntity)
+ {
+ this->dataPtr->linkEntity =
+ this->dataPtr->model.LinkByName(_ecm, this->dataPtr->linkName);
+ }
+
+ if ( this->dataPtr->linkEntity == kNullEntity)
+ {
+ gzerr << "Failed to find link entity. "
+ << "Failed to initialize." << std::endl;
+ return;
+ }
+
+ // skip UpdateForcesAndMoments if needed components are missing
+ bool providedAllComponents = true;
+ if (!_ecm.Component(this->dataPtr->linkEntity))
+ {
+ _ecm.CreateComponent(this->dataPtr->linkEntity, components::WorldPose());
+ }
+
+ if (!providedAllComponents) {
+ gzdbg << "Created necessary components." << std::endl;
+ }
+
+}
+
+//////////////////////////////////////////////////
+void SpacecraftThrusterModelPrivate::OnActuatorMsg(
+ const msgs::Actuators &_msg)
+{
+ std::lock_guard lock(this->recvdActuatorsMsgMutex);
+ this->recvdActuatorsMsg = _msg;
+ if (this->actuatorNumber == 0)
+ gzdbg << "Received actuator message!" << std::endl;
+}
+
+//////////////////////////////////////////////////
+void SpacecraftThrusterModel::PreUpdate(const UpdateInfo &_info,
+ EntityComponentManager &_ecm)
+{
+ GZ_PROFILE("SpacecraftThrusterModel::PreUpdate");
+ // \TODO(anyone) Support rewind
+ if (_info.dt < std::chrono::steady_clock::duration::zero())
+ {
+ gzwarn << "Detected jump back in time ["
+ << std::chrono::duration_cast(_info.dt).count()
+ << "s]. System may not work properly." << std::endl;
+ }
+
+ // Nothing left to do if paused.
+ if (_info.paused)
+ return;
+
+ this->dataPtr->simTime = std::chrono::duration(_info.simTime).count();
+ this->dataPtr->UpdateForcesAndMoments(_ecm);
+}
+
+//////////////////////////////////////////////////
+void SpacecraftThrusterModelPrivate::UpdateForcesAndMoments(
+ EntityComponentManager &_ecm)
+{
+ GZ_PROFILE("SpacecraftThrusterModelPrivate::UpdateForcesAndMoments");
+ std::optional msg;
+ auto actuatorMsgComp =
+ _ecm.Component(this->model.Entity());
+
+ // Actuators messages can come in from transport or via a component. If a
+ // component is available, it takes precedence.
+ if (actuatorMsgComp)
+ {
+ msg = actuatorMsgComp->Data();
+ }
+ else
+ {
+ std::lock_guard lock(this->recvdActuatorsMsgMutex);
+ if (this->recvdActuatorsMsg.has_value())
+ {
+ msg = *this->recvdActuatorsMsg;
+ }
+ }
+
+ if (msg.has_value())
+ {
+ if (this->actuatorNumber > msg->normalized_size() - 1)
+ {
+ gzerr << "You tried to access index " << this->actuatorNumber
+ << " of the Actuator array which is of size "
+ << msg->normalized_size() << std::endl;
+ return;
+ }
+ }
+ else
+ {
+ return;
+ }
+
+ // METHOD:
+ //
+ // targetDutyCycle starts as a normalized value between 0 and 1, so we
+ // need to convert it to the corresponding time in the duty cycle
+ // period
+ // |________| |________
+ // | ^ | | |
+ // __| | |____| |__
+ // a b c d
+ // a: cycle start time
+ // b: sampling time
+ // c: target duty cycle
+ // d: cycle period
+ double targetDutyCycle =
+ msg->normalized(this->actuatorNumber) * (1.0 / this->dutyCycleFrequency);
+ if (this->actuatorNumber == 0)
+ gzdbg << this->actuatorNumber
+ << ": target duty cycle: " << targetDutyCycle << std::endl;
+
+ // Calculate cycle start time
+ if (this->samplingTime >= 1.0/this->dutyCycleFrequency) {
+ if (this->actuatorNumber == 0)
+ gzdbg << this->actuatorNumber
+ << ": Cycle completed. Resetting cycle start time."
+ << std::endl;
+ this->cycleStartTime = this->simTime;
+ }
+
+ // Calculate sampling time instant within the cycle
+ this->samplingTime = this->simTime - this->cycleStartTime;
+ if (this->actuatorNumber == 0)
+ gzdbg << this->actuatorNumber
+ << ": PWM Period: " << 1.0/this->dutyCycleFrequency
+ << " Cycle Start time: " << this->cycleStartTime
+ << " Sampling time: " << this->samplingTime << std::endl;
+
+ // Apply force if the sampling time is less than the target ON duty cycle
+ double force = this->samplingTime <= targetDutyCycle ? this->maxThrust : 0.0;
+ if(targetDutyCycle < 1e-9) force = 0.0;
+
+ if (this->actuatorNumber == 0)
+ gzdbg << this->actuatorNumber
+ << ": Force: " << force
+ << " Sampling time: " << this->samplingTime
+ << " Tgt duty cycle: " << targetDutyCycle << std::endl;
+
+ // Apply force to the link
+ Link link(this->linkEntity);
+ const auto worldPose = link.WorldPose(_ecm);
+ link.AddWorldForce(_ecm,
+ worldPose->Rot().RotateVector(math::Vector3d(0, 0, force)));
+ if (this->actuatorNumber == 0)
+ gzdbg << this->actuatorNumber
+ << ": Input Value: " << msg->normalized(this->actuatorNumber)
+ << " Calc. Force: " << force << std::endl;
+}
+
+GZ_ADD_PLUGIN(SpacecraftThrusterModel,
+ System,
+ SpacecraftThrusterModel::ISystemConfigure,
+ SpacecraftThrusterModel::ISystemPreUpdate)
+
+GZ_ADD_PLUGIN_ALIAS(SpacecraftThrusterModel,
+ "gz::sim::systems::SpacecraftThrusterModel")
+
+// TODO(CH3): Deprecated, remove on version 8
+GZ_ADD_PLUGIN_ALIAS(SpacecraftThrusterModel,
+ "ignition::gazebo::systems::SpacecraftThrusterModel")
diff --git a/src/systems/spacecraft_thruster_model/SpacecraftThrusterModel.hh b/src/systems/spacecraft_thruster_model/SpacecraftThrusterModel.hh
new file mode 100644
index 0000000000..77b0dbc715
--- /dev/null
+++ b/src/systems/spacecraft_thruster_model/SpacecraftThrusterModel.hh
@@ -0,0 +1,88 @@
+/*
+ * Copyright (C) 2019 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 GZ_SIM_SYSTEMS_SPACECRAFTTHRUSTERMODEL_HH_
+#define GZ_SIM_SYSTEMS_SPACECRAFTTHRUSTERMODEL_HH_
+
+#include
+#include
+
+namespace gz
+{
+namespace sim
+{
+// Inline bracket to help doxygen filtering.
+inline namespace GZ_SIM_VERSION_NAMESPACE {
+namespace systems
+{
+ // Forward declaration
+ class SpacecraftThrusterModelPrivate;
+
+ /// \brief This system applies a thrust force to models with RCS-like
+ /// thrusters. See tutorials/spacecraft_thrusters.md for a tutorial usage.
+ /// Below follow the minimum necessary parameters needed by the plugin:
+ /// \param link_name Name of the link that the thruster is attached to.
+ /// \param actuator_number Index of the element to be used from the
+ /// actuators message for a joint.
+ /// \param duty_cycle_frequency Frequency of the duty cycle signal in Hz.
+ /// \param max_thrust Maximum thrust force in Newtons, applied on the
+ /// «on» phase of the duty cycle.
+ /// \param topic Name of the topic where the commanded normalized
+ /// thrust is published. Unit is <0, 1>, corresponding to the
+ /// percentage of the duty cycle that the thruster is on.
+ /// Default uses the models name.
+ /// \param sub_topic [optional] Name of the sub_topic to listen to actuator
+ /// message on.
+ ///
+ /// This plugin replicates the PWM thruster behavior in:
+ /// Nakka, Yashwanth Kumar, et al. "A six degree-of-freedom spacecraft
+ /// dynamics simulator for formation control research." 2018 AAS/AIAA
+ /// Astrodynamics Specialist Conference. 2018. -> 'Thruster Firing Time'
+ /// Phodapol, S. (2023). Predictive Controllers for Load Transportation in
+ /// Microgravity Environments (Dissertation). -> '5.3.4 PWM Controller Node'
+ /// Retrieved from https://urn.kb.se/resolve?urn=urn:nbn:se:kth:diva-344440
+
+ class SpacecraftThrusterModel
+ : public System,
+ public ISystemConfigure,
+ public ISystemPreUpdate
+ {
+ /// \brief Constructor
+ public: SpacecraftThrusterModel();
+
+ /// \brief Destructor
+ public: ~SpacecraftThrusterModel() override = default;
+
+ // Documentation inherited
+ public: void Configure(const Entity &_entity,
+ const std::shared_ptr &_sdf,
+ EntityComponentManager &_ecm,
+ EventManager &_eventMgr) override;
+
+ // Documentation inherited
+ public: void PreUpdate(
+ const gz::sim::UpdateInfo &_info,
+ gz::sim::EntityComponentManager &_ecm) override;
+
+ /// \brief Private data pointer
+ private: std::unique_ptr dataPtr;
+ };
+ }
+}
+}
+}
+
+#endif
diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt
index 8c616bcbe7..8afc9cfe24 100644
--- a/test/integration/CMakeLists.txt
+++ b/test/integration/CMakeLists.txt
@@ -71,6 +71,7 @@ set(tests
reset.cc
reset_detachable_joint.cc
save_world.cc
+ spacecraft.cc
scene_broadcaster_system.cc
sdf_frame_semantics.cc
sdf_include.cc
diff --git a/test/integration/spacecraft.cc b/test/integration/spacecraft.cc
new file mode 100644
index 0000000000..1af76f87a0
--- /dev/null
+++ b/test/integration/spacecraft.cc
@@ -0,0 +1,120 @@
+/*
+ * Copyright (C) 2024 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.
+ *
+ */
+
+
+#include
+
+#include
+
+#include
+#include
+
+#include
+#include
+#include
+#include
+#include
+
+#include "gz/sim/components/AngularVelocity.hh"
+#include "gz/sim/components/Joint.hh"
+#include "gz/sim/components/JointVelocity.hh"
+#include "gz/sim/components/LinearVelocity.hh"
+#include "gz/sim/components/Link.hh"
+#include "gz/sim/components/Name.hh"
+#include "gz/sim/components/Model.hh"
+#include "gz/sim/components/Pose.hh"
+
+#include "gz/sim/Model.hh"
+#include "gz/sim/Server.hh"
+#include "gz/sim/SystemLoader.hh"
+#include "test_config.hh"
+
+#include "../helpers/Relay.hh"
+#include "../helpers/EnvTestFixture.hh"
+
+using namespace gz;
+using namespace sim;
+using namespace std::chrono_literals;
+
+class SpacecraftTest : public InternalFixture<::testing::Test>
+{
+ protected: std::unique_ptr StartServer(const std::string &_filePath)
+ {
+ ServerConfig serverConfig;
+ const auto sdfFile = std::string(PROJECT_SOURCE_PATH) + _filePath;
+ serverConfig.SetSdfFile(sdfFile);
+
+ auto server = std::make_unique(serverConfig);
+ EXPECT_FALSE(server->Running());
+ EXPECT_FALSE(*server->Running(0));
+
+ using namespace std::chrono_literals;
+ server->SetUpdatePeriod(1ns);
+ return server;
+ }
+};
+
+/////////////////////////////////////////////////
+// Test that a thruster duty cycle command is applied
+TEST_F(SpacecraftTest, GZ_UTILS_TEST_DISABLED_ON_WIN32(InputTest))
+{
+ // Start server
+ auto server = this->StartServer("/examples/worlds/spacecraft.sdf");
+
+ test::Relay testSystem;
+ transport::Node node;
+ auto cmdDutyCyclePublisher =
+ node.Advertise("/dart/command/duty_cycle");
+
+ const std::size_t iterTestStart{100};
+ const std::size_t nIters{500};
+ std::vector poses;
+
+ testSystem.OnPostUpdate(
+ [&](const UpdateInfo &_info,
+ const EntityComponentManager &_ecm)
+ {
+ // Command a thruster duty cycle
+ const double cmdDutyCycle{0};
+ if (_info.iterations == iterTestStart)
+ {
+ msgs::Actuators msg;
+ msg.mutable_normalized()->Resize(12, cmdDutyCycle);
+ msg.mutable_normalized()->Set(0, 1.0);
+ cmdDutyCyclePublisher.Publish(msg);
+ }
+ else
+ {
+ auto id = _ecm.EntityByComponents(
+ components::Model(),
+ components::Name("dart"));
+ EXPECT_NE(kNullEntity, id);
+
+ auto poseComp = _ecm.Component(id);
+ ASSERT_NE(nullptr, poseComp);
+ // Collect poses
+ poses.push_back(poseComp->Data());
+ }
+ });
+
+ server->AddSystem(testSystem.systemPtr);
+ server->Run(true, iterTestStart + nIters, false);
+
+ // Check for movement in the right direction
+ math::Pose3d lastPose = poses.back();
+ EXPECT_GT(lastPose.Pos().Y(), 0.0);
+}
diff --git a/tutorials/files/spacecraft/dart.png b/tutorials/files/spacecraft/dart.png
new file mode 100644
index 0000000000..2f109cd5c0
Binary files /dev/null and b/tutorials/files/spacecraft/dart.png differ
diff --git a/tutorials/files/spacecraft/kth_spacecraft_simulator.png b/tutorials/files/spacecraft/kth_spacecraft_simulator.png
new file mode 100644
index 0000000000..11fa8807d1
Binary files /dev/null and b/tutorials/files/spacecraft/kth_spacecraft_simulator.png differ
diff --git a/tutorials/spacecraft_thrusters.md b/tutorials/spacecraft_thrusters.md
new file mode 100644
index 0000000000..5cbf8f6bd4
--- /dev/null
+++ b/tutorials/spacecraft_thrusters.md
@@ -0,0 +1,105 @@
+\page spacecraft_thrusters Spacecraft thrusters
+
+## Spacecraft Thrusters Model
+
+To enable a seamless transition of space robotics control and planning schemes from simulation to real, we introduce
+a spacecraft thrusters model in Gazebo. The model provides a very simple interface to a solenoid valve that controls
+the flow of gas to the thruster. The thruster model is as follows:
+
+- force output equals max_thrust when the command is 1
+- force output equals 0 when the command is 0
+- force output is modeled according to a duty cycle with a given frequency, and thrust output is maximum at the ON state of the duty cycle
+
+In short, if the duty cycle signal is high, the solenoid valve behaves as a fully-opened thruster, providing maximum thrust.
+If the duty cycle signal is low, the solenoid valve behaves as a fully-closed thruster, providing no thrust.
+
+## Setting up the SpacecraftThrusterModel plugin
+
+Here follows an example instance of the `SpacecraftThrusterModel` plugin in an SDF file:
+```xml
+
+ thruster_0
+ 0
+ 10
+ 1.4
+ command/duty_cycle
+
+```
+
+In this case, each thruster link should be placed in the proper location in the spacecraft model.
+An example of this goes below:
+```xml
+
+ -0.12 0.12 0.2 3.14159 1.57079 3.14159
+ base_link
+ thruster_0
+
+
+ 0
+ 0
+
+ 0 0 1
+
+ -1e+16
+ 1e+16
+
+
+
+
+
+ 0
+ 0.2
+
+
+
+
+
+ true
+ 0 0 0 0 -0 0
+
+ 0 0 0 0 0 0
+ 0.001
+
+ 1e-05
+ 0
+ 0
+ 1e-05
+ 0
+ 1e-05
+
+
+
+```
+
+## Testing an implementation of a Spacecraft model
+An example of a spacecraft with thrusters is implemented in the [DART spacecraft model](https://app.gazebosim.org/proque/fuel/models/dart). To run the example, run the following command:
+```bash
+gz sim spacecraft.sdf
+```
+
+This spacecraft has 12 thrusters. To send inputs to `thruster_0`, run the following command:
+```bash
+gz topic -p 'normalized:[1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]' -t /dart/command/duty_cycle --msgtype gz.msgs.Actuators
+```
+
+This command will send the maximum force of a thruster over one sampling time.
+
+Below, an image of the spacecraft:
+![Spacecraft](./files/spacecraft/dart.png)
+
+## 2D Spacecraft Simulator - Ground Space Robotics testbed
+
+An example of a ground testbed for spacecrafts is also available, where the spacecraft moves a 2D plane using thrusters. The testbed spacecraft model has 8 thrusters, and the thrusters are controlled by the `SpacecraftThrusterModel` plugin. This replicates the real [DISCOWER](https://www.discower.io/) testbed at KTH Space Robotics Laboratory in Stockholm Sweden.
+
+To run this example, run the following command:
+```bash
+gz sim ground_spacecraft_testbed.sdf
+```
+
+This spacecraft has 8 thrusters. To send inputs to `thruster_0`, run the following command:
+```bash
+gz topic -p 'normalized:[1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]' -t /kth_freeflyer/command/duty_cycle --msgtype gz.msgs.Actuators
+```
+
+Below is a picture of the simulator:
+![Spacecraft simulator](./files/spacecraft/kth_spacecraft_simulator.png)