A class for manipulating physics::Joint. More...
#include <physics/physics.hh>
Public Member Functions | |
| JointController (ModelPtr _model) | |
| Constructor. More... | |
| virtual | ~JointController () |
| Destructor. More... | |
| void | AddJoint (JointPtr _joint) |
| Add a joint to control. More... | |
| std::map< std::string, double > | GetForces () const |
| Get all the applied forces. More... | |
| std::map< std::string, JointPtr > | GetJoints () const |
| Get all the joints. More... | |
| common::Time | GetLastUpdateTime () const |
| Get the last time the controller was updated. More... | |
| std::map< std::string, common::PID > | GetPositionPIDs () const |
| Get all the position PID controllers. More... | |
| std::map< std::string, double > | GetPositions () const |
| Get all the position PID set points. More... | |
| std::map< std::string, double > | GetVelocities () const |
| Get all the velocity PID set points. More... | |
| std::map< std::string, common::PID > | GetVelocityPIDs () const |
| Get all the velocity PID controllers. More... | |
| void | Reset () |
| Reset all commands. More... | |
| void | SetJointPosition (const std::string &_name, double _position, int _index=0) |
| Set the positions of a Joint by name. More... | |
| void | SetJointPosition (JointPtr _joint, double _position, int _index=0) |
| Set the positions of a Joint by name The position is specified in native units, which means, if you are using metric system, it's meters for SliderJoint and radians for HingeJoint, etc. More... | |
| void | SetJointPositions (const std::map< std::string, double > &_jointPositions) |
| Set the positions of a set of Joint's. More... | |
| bool | SetPositionTarget (const std::string &_jointName, double _target) |
| Set the target position for the position PID controller. More... | |
| bool | SetVelocityTarget (const std::string &_jointName, double _target) |
| Set the target velocity for the velocity PID controller. More... | |
| void | Update () |
| Update the joint control. More... | |
A class for manipulating physics::Joint.
|
explicit |
Constructor.
| [in] | _model | Model that uses this joint controller. |
|
virtual |
Destructor.
| void gazebo::physics::JointController::AddJoint | ( | JointPtr | _joint) |
Add a joint to control.
| [in] | _joint | Joint to control. |
| std::map<std::string, double> gazebo::physics::JointController::GetForces | ( | ) | const |
Get all the applied forces.
| std::map<std::string, JointPtr> gazebo::physics::JointController::GetJoints | ( | ) | const |
Get all the joints.
| common::Time gazebo::physics::JointController::GetLastUpdateTime | ( | ) | const |
Get the last time the controller was updated.
| std::map<std::string, common::PID> gazebo::physics::JointController::GetPositionPIDs | ( | ) | const |
Get all the position PID controllers.
| std::map<std::string, double> gazebo::physics::JointController::GetPositions | ( | ) | const |
Get all the position PID set points.
| std::map<std::string, double> gazebo::physics::JointController::GetVelocities | ( | ) | const |
Get all the velocity PID set points.
| std::map<std::string, common::PID> gazebo::physics::JointController::GetVelocityPIDs | ( | ) | const |
Get all the velocity PID controllers.
| void gazebo::physics::JointController::Reset | ( | ) |
Reset all commands.
| void gazebo::physics::JointController::SetJointPosition | ( | const std::string & | _name, |
| double | _position, | ||
| int | _index = 0 |
||
| ) |
Set the positions of a Joint by name.
Warning: This function is disabled since collisions are not updated correctly. See issue #1138
| void gazebo::physics::JointController::SetJointPosition | ( | JointPtr | _joint, |
| double | _position, | ||
| int | _index = 0 |
||
| ) |
Set the positions of a Joint by name The position is specified in native units, which means, if you are using metric system, it's meters for SliderJoint and radians for HingeJoint, etc.
Implementation: In order to change the position of a Joint inside a Model, this call must recursively crawl through all the connected children Link's in this Model, and update each Link Pose affected by this Joint angle update. Warning: There is no constraint satisfaction being done here, traversal through the kinematic graph has unexpected behavior if you try to set the joint position of a link inside a loop structure. Warning: This function is disabled since collisions are not updated correctly. See issue #1138
| [in] | _joint | Joint to set. |
| [in] | _position | Position of the joint. |
| void gazebo::physics::JointController::SetJointPositions | ( | const std::map< std::string, double > & | _jointPositions) |
Set the positions of a set of Joint's.
Warning: This function is disabled since collisions are not updated correctly. See issue #1138
| bool gazebo::physics::JointController::SetPositionTarget | ( | const std::string & | _jointName, |
| double | _target | ||
| ) |
Set the target position for the position PID controller.
| [in] | _jointName | Scoped name of the joint. |
| [in] | _target | Position target. |
| bool gazebo::physics::JointController::SetVelocityTarget | ( | const std::string & | _jointName, |
| double | _target | ||
| ) |
Set the target velocity for the velocity PID controller.
| [in] | _jointName | Scoped name of the joint. |
| [in] | _target | Velocity target. |
| void gazebo::physics::JointController::Update | ( | ) |
Update the joint control.