Joint position controller which can be attached to a model with a reference to a single joint. More...
#include <JointPositionController.hh>
Public Member Functions | |
| JointPositionController () | |
| Constructor. More... | |
| ~JointPositionController () override=default | |
| Destructor. More... | |
| void | Configure (const Entity &_entity, const std::shared_ptr< const sdf::Element > &_sdf, EntityComponentManager &_ecm, EventManager &_eventMgr) override |
| Configure the system. More... | |
| void | PreUpdate (const gz::sim::UpdateInfo &_info, gz::sim::EntityComponentManager &_ecm) override |
Public Member Functions inherited from System | |
| System ()=default | |
| Constructor. More... | |
| virtual | ~System ()=default |
| Destructor. More... | |
Detailed Description
Joint position controller which can be attached to a model with a reference to a single joint.
A new Ignition Transport topic is created to send target joint positions. The topic name is "/model/<model_name>/joint/<joint_name>/<joint_index>/cmd_pos".
This topic accepts gz::msgs::Double values representing the target position. If you wish to change the topic on which this plugin listens you may use the <topic> parameter to specify which topic the plugin should listen on.
System Parameters
<joint_name> The name of the joint to control. Required parameter.
<joint_index> Axis of the joint to control. Optional parameter. The default value is 0.
<p_gain> The proportional gain of the PID. Optional parameter. The default value is 1.
<i_gain> The integral gain of the PID. Optional parameter. The default value is 0.1.
<d_gain> The derivative gain of the PID. Optional parameter. The default value is 0.01
<i_max> The integral upper limit of the PID. Optional parameter. The default value is 1.
<i_min> The integral lower limit of the PID. Optional parameter. The default value is -1.
<cmd_max> Output max value of the PID. Optional parameter. The default value is 1000.
<cmd_min> Output min value of the PID. Optional parameter. The default value is -1000.
<cmd_offset> Command offset (feed-forward) of the PID. Optional parameter. The default value is 0.
<use_velocity_commands> Bypasses the PID and creates a perfect position. The maximum speed on the joint can be set using the <cmd_max> tag.
<topic> If you wish to listen on a non-default topic you may specify it here, otherwise the controller defaults to listening on "/model/<model_name>/joint/<joint_name>/<joint_index>/cmd_pos".
<initial_position> Initial position of a joint. Optional parameter. The default value is 0.
Constructor & Destructor Documentation
◆ JointPositionController()
Constructor.
◆ ~JointPositionController()
|
overridedefault |
Destructor.
Member Function Documentation
◆ Configure()
|
overridevirtual |
Configure the system.
- Parameters
-
[in] _entity The entity this plugin is attached to. [in] _sdf The SDF Element associated with this system plugin. [in] _ecm The EntityComponentManager of the given simulation instance. [in] _eventMgr The EventManager of the given simulation instance.
Implements ISystemConfigure.
◆ PreUpdate()
|
overridevirtual |
Implements ISystemPreUpdate.
The documentation for this class was generated from the following file:
Public Member Functions inherited from