Public Member Functions | Public Attributes
pr2_mechanism_model::JointState Class Reference

#include <joint.h>

List of all members.

Public Member Functions

void enforceLimits ()
 Modify the commanded_effort_ of the joint state so that the joint limits are satisfied.
void getLimits (double &effort_low, double &effort_high)
 Returns the safety effort limits given the current position and velocity.
 JointState ()
 Constructor.

Public Attributes

bool calibrated_
 Bool to indicate if the joint has been calibrated or not.
double commanded_effort_
 The effort the joint should apply in Nm or N (write-to variable)
boost::shared_ptr< const
urdf::Joint > 
joint_
 A pointer to the corresponding urdf::Joint from the urdf::Model.
JointStatistics joint_statistics_
double measured_effort_
 The measured joint effort in Nm or N (read-only variable)
double position_
 The joint position in radians or meters (read-only variable)
double reference_position_
 The position of the optical flag that was used to calibrate this joint.
double velocity_
 The joint velocity in randians/sec or meters/sec (read-only variable)

Detailed Description

Definition at line 71 of file joint.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 105 of file joint.h.


Member Function Documentation

Modify the commanded_effort_ of the joint state so that the joint limits are satisfied.

Definition at line 76 of file joint.cpp.

void JointState::getLimits ( double &  effort_low,
double &  effort_high 
)

Returns the safety effort limits given the current position and velocity.

Definition at line 87 of file joint.cpp.


Member Data Documentation

Bool to indicate if the joint has been calibrated or not.

Definition at line 99 of file joint.h.

The effort the joint should apply in Nm or N (write-to variable)

Definition at line 96 of file joint.h.

boost::shared_ptr<const urdf::Joint> pr2_mechanism_model::JointState::joint_

A pointer to the corresponding urdf::Joint from the urdf::Model.

Definition at line 81 of file joint.h.

Definition at line 93 of file joint.h.

The measured joint effort in Nm or N (read-only variable)

Definition at line 90 of file joint.h.

The joint position in radians or meters (read-only variable)

Definition at line 84 of file joint.h.

The position of the optical flag that was used to calibrate this joint.

Definition at line 102 of file joint.h.

The joint velocity in randians/sec or meters/sec (read-only variable)

Definition at line 87 of file joint.h.


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


pr2_mechanism_model
Author(s): Eric Berger berger@willowgarage.com, Stuart Glaser, Wim Meeussen
autogenerated on Wed Aug 26 2015 15:37:19