Gazebo Sim

API Reference

9.0.0
JointController Class Reference

Joint controller which can be attached to a model with a reference to a single joint. Currently only the first axis of a joint is actuated. More...

#include <JointController.hh>

Public Member Functions

 JointController ()
 Constructor.
 
 ~JointController () 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

Joint controller which can be attached to a model with a reference to a single joint. Currently only the first axis of a joint is actuated.

System Parameters

  • <joint_name> The name of the joint to control. Required parameter. Can also include multiple <joint_name> for identical joints.
  • <use_force_commands> True to enable the controller implementation using force commands. If this parameter is not set or is false, the controller will use velocity commands internally.
  • <use_actuator_msg> True to enable the use of actuator message for velocity command. The actuator msg is an array of floats for position, velocity and normalized commands. Relies on <actuator_number> for the index of the velocity actuator and defaults to topic "/actuators" when topic or `subtopic not set.
  • <actuator_number> used with <use_actuator_msg> to set the index of the velocity actuator.
  • <topic> Topic to receive commands in. Defaults to /model/<model_name>/joint/<joint_name>/cmd_vel.
  • <sub_topic> Sub topic to receive commands in. Defaults to "/model/<model_name>/<sub_topic>".
  • <initial_velocity> Velocity to start with.

Velocity mode

No additional parameters are required.

Force mode

The controller accepts the next optional parameters:

  • <p_gain> The proportional gain of the PID. The default value is 1.
  • <i_gain> The integral gain of the PID. The default value is 0.
  • <d_gain> The derivative gain of the PID. The default value is 0.
  • <i_max> The integral upper limit of the PID. The default value is 1.
  • <i_min> The integral lower limit of the PID. The default value is -1.
  • <cmd_max> Output max value of the PID. The default value is 1000.
  • <cmd_min> Output min value of the PID. The default value is -1000.
  • <cmd_offset> Command offset (feed-forward) of the PID. The default value is 0.

Constructor & Destructor Documentation

◆ JointController()

Constructor.

◆ ~JointController()

~JointController ( )
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: