Drake
Drake C++ Documentation
drake::examples::allegro_hand Namespace Reference

Classes

class  AllegroCommandReceiver
 Handles lcmt_allegro_command messages from a LcmSubscriberSystem. More...
 
class  AllegroHandMotionState
 Detecting the state of the fingers: whether the joints are moving, or reached the destination, or got stuck by external collisions in the midway. More...
 
class  AllegroStatusSender
 Creates and outputs lcmt_allegro_status messages. More...
 

Functions

void SetPositionControlledGains (double pid_frequency, double Ieff, Eigen::VectorXd *Kp, Eigen::VectorXd *Ki, Eigen::VectorXd *Kd)
 Set the feedback gains for the simulated position control. More...
 
void GetControlPortMapping (const multibody::MultibodyPlant< double > &plant, MatrixX< double > *Sx, MatrixX< double > *Sy)
 Creates selector matrices which extract state xₛ in a known order from the plant's full x (xₛ = Sx⋅x) and promote the controller's ordered yₛ into the full plant's input actuation (u = Su⋅uₛ). More...
 
std::vector< std::string > GetPreferredJointOrdering ()
 Defines the desired ordering of the finger joints by name. More...
 

Variables

constexpr int kAllegroNumJoints = 16
 
const double kHardwareStatusPeriod = 0.003
 

Function Documentation

◆ GetControlPortMapping()

void drake::examples::allegro_hand::GetControlPortMapping ( const multibody::MultibodyPlant< double > &  plant,
MatrixX< double > *  Sx,
MatrixX< double > *  Sy 
)

Creates selector matrices which extract state xₛ in a known order from the plant's full x (xₛ = Sx⋅x) and promote the controller's ordered yₛ into the full plant's input actuation (u = Su⋅uₛ).

The matrices are used to initialize the PID controller for the hand.

See also
MultibodyPlant::MakeStateSelectorMatrix(), MultibodyPlant::MakeActuatorSelectorMatrix() for detailed definitions for the selector matrices.
systems::controllers::PidController for documentation on how these selector matrices are used in the PID controller.
Parameters
Sxthe matrix to match the output state of the plant into the state of the finger joints in the desired order.
Sythe matrix to match the output torque for the hand joint actuators in the desired order into the input actuation of the plant.

◆ GetPreferredJointOrdering()

std::vector<std::string> drake::examples::allegro_hand::GetPreferredJointOrdering ( )

Defines the desired ordering of the finger joints by name.

The fingers are ordered as [thumb, index, middle, ring] and the joints of each finger are ordered from most proximal to most distal (relative to the palm).

◆ SetPositionControlledGains()

void drake::examples::allegro_hand::SetPositionControlledGains ( double  pid_frequency,
double  Ieff,
Eigen::VectorXd *  Kp,
Eigen::VectorXd *  Ki,
Eigen::VectorXd *  Kd 
)

Set the feedback gains for the simulated position control.

Variable Documentation

◆ kAllegroNumJoints

constexpr int kAllegroNumJoints = 16

◆ kHardwareStatusPeriod

const double kHardwareStatusPeriod = 0.003