A class for manipulating physics::Joint.  
 More...
#include <physics/physics.hh>
A class for manipulating physics::Joint. 
  
  | 
        
          | gazebo::physics::JointController::JointController | ( | ModelPtr | _model | ) |  |  | explicit | 
 
Constructor. 
- Parameters
- 
  
    | [in] | _model | Model that uses this joint controller. |  
 
 
 
      
        
          | void gazebo::physics::JointController::AddJoint | ( | JointPtr | _joint | ) |  | 
      
 
Add a joint to control. 
- Parameters
- 
  
    | [in] | _joint | Joint to control. |  
 
 
 
      
        
          | void gazebo::physics::JointController::Reset | ( |  | ) |  | 
      
 
 
      
        
          | void gazebo::physics::JointController::SetJointPosition | ( | const std::string & | _name, | 
        
          |  |  | double | _position, | 
        
          |  |  | int | _index = 0 | 
        
          |  | ) |  |  | 
      
 
Set the positions of a Joint by name. 
- See Also
- JointController::SetJointPosition(JointPtr, double) 
 
 
      
        
          | 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. 
- Parameters
- 
  
    | [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. 
- See Also
- JointController::SetJointPosition(JointPtr, double) 
 
 
      
        
          | void gazebo::physics::JointController::Update | ( |  | ) |  | 
      
 
Update the joint control. 
 
 
The documentation for this class was generated from the following file: