Gazebo Sim

API Reference

9.0.0~pre1
SpacecraftThrusterModel Class Reference

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: More...

#include <SpacecraftThrusterModel.hh>

Public Member Functions

 SpacecraftThrusterModel ()
 Constructor.
 
 ~SpacecraftThrusterModel () override=default
 Destructor.
 
void Configure (const Entity &_entity, const std::shared_ptr< const sdf::Element > &_sdf, EntityComponentManager &_ecm, EventManager &_eventMgr) override
 Configure the system.
 
void PreUpdate (const UpdateInfo &_info, EntityComponentManager &_ecm) override
 
- Public Member Functions inherited from System
 System ()=default
 Constructor.
 
virtual ~System ()=default
 Destructor.
 

Additional Inherited Members

- Public Types inherited from System
using PriorityType = int32_t
 Signed integer type used for specifying priority of the execution order of PreUpdate and Update phases.
 
- Static Public Attributes inherited from System
static constexpr PriorityType kDefaultPriority = {0}
 Default priority value for execution order of the PreUpdate and Update phases.
 
static constexpr std::string_view kPriorityElementName
 Name of the XML element from which the priority value will be parsed.
 

Detailed Description

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:

Parameters
link_nameName of the link that the thruster is attached to.
actuator_numberIndex of the element to be used from the actuators message for a joint.
duty_cycle_frequencyFrequency of the duty cycle signal in Hz.
max_thrustMaximum thrust force in Newtons, applied on the «on» phase of the duty cycle.
topicName 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.
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

Constructor & Destructor Documentation

◆ SpacecraftThrusterModel()

Constructor.

◆ ~SpacecraftThrusterModel()

~SpacecraftThrusterModel ( )
overridedefault

Destructor.

Member Function Documentation

◆ Configure()

void Configure ( const Entity _entity,
const std::shared_ptr< const sdf::Element > &  _sdf,
EntityComponentManager _ecm,
EventManager _eventMgr 
)
overridevirtual

Configure the system.

Parameters
[in]_entityThe entity this plugin is attached to.
[in]_sdfThe SDF Element associated with this system plugin.
[in]_ecmThe EntityComponentManager of the given simulation instance.
[in]_eventMgrThe EventManager of the given simulation instance.

Implements ISystemConfigure.

◆ PreUpdate()

void PreUpdate ( const UpdateInfo _info,
EntityComponentManager _ecm 
)
overridevirtual

Implements ISystemPreUpdate.


The documentation for this class was generated from the following file: