Drake
Drake C++ Documentation
drake::manipulation::kuka_iiwa Namespace Reference

Classes

class  IiwaCommandReceiver
 Handles lcmt_iiwa_command message from a LcmSubscriberSystem. More...
 
class  IiwaCommandSender
 Creates and outputs lcmt_iiwa_command messages. More...
 
struct  IiwaControlPorts
 The return type of BuildSimplifiedIiwaControl(). More...
 
struct  IiwaDriver
 This config struct specifies how to wire up Drake systems between an LCM interface and the actuation input ports of a MultibodyPlant. More...
 
class  IiwaStatusReceiver
 Handles lcmt_iiwa_status messages from a LcmSubscriberSystem. More...
 
class  IiwaStatusSender
 Creates and outputs lcmt_iiwa_status messages. More...
 
class  SimIiwaDriver
 SimIiwaDriver simulates the IIWA control and status interface using a MultibodyPlant. More...
 

Enumerations

enum  IiwaControlMode { kPositionOnly, kTorqueOnly, kPositionAndTorque }
 Enumeration for control modes. More...
 

Functions

void BuildIiwaControl (const multibody::MultibodyPlant< double > &plant, const multibody::ModelInstanceIndex iiwa_instance, const multibody::MultibodyPlant< double > &controller_plant, lcm::DrakeLcmInterface *lcm, systems::DiagramBuilder< double > *builder, double ext_joint_filter_tau=0.01, const std::optional< Eigen::VectorXd > &desired_iiwa_kp_gains=std::nullopt, IiwaControlMode control_mode=IiwaControlMode::kPositionAndTorque)
 Given a plant (and associated iiwa_instance) and a builder, installs in that builder the systems necessary to control and monitor an Iiwa described by controller_plant in that plant. More...
 
IiwaControlPorts BuildSimplifiedIiwaControl (const multibody::MultibodyPlant< double > &plant, const multibody::ModelInstanceIndex iiwa_instance, const multibody::MultibodyPlant< double > &controller_plant, systems::DiagramBuilder< double > *builder, double ext_joint_filter_tau=0.01, const std::optional< Eigen::VectorXd > &desired_iiwa_kp_gains=std::nullopt, IiwaControlMode control_mode=IiwaControlMode::kPositionAndTorque)
 A simplified Iiwa controller builder to construct an InverseDynamicsController without adding LCM I/O systems. More...
 
VectorX< doubleget_iiwa_max_joint_velocities ()
 Returns the maximum joint velocities (rad/s) provided by Kuka. More...
 
constexpr bool position_enabled (IiwaControlMode control_mode)
 Reports if the given control mode includes positions. More...
 
constexpr bool torque_enabled (IiwaControlMode control_mode)
 Reports if the given control mode includes torques. More...
 
IiwaControlMode ParseIiwaControlMode (const std::string &control_mode)
 Parses control mode with the following mapping: More...
 
void ApplyDriverConfig (const IiwaDriver &driver_config, const std::string &model_instance_name, const multibody::MultibodyPlant< double > &sim_plant, const std::map< std::string, multibody::parsing::ModelInstanceInfo > &models_from_directives, const systems::lcm::LcmBuses &lcms, systems::DiagramBuilder< double > *builder)
 Wires up Drake systems between an LCM interface and the actuation input ports of a MultibodyPlant. More...
 

Variables

constexpr int kIiwaArmNumJoints = 7
 
const double kIiwaLcmStatusPeriod
 

Enumeration Type Documentation

◆ IiwaControlMode

enum IiwaControlMode
strong

Enumeration for control modes.

Enumerator
kPositionOnly 
kTorqueOnly 
kPositionAndTorque 

Function Documentation

◆ ApplyDriverConfig()

void drake::manipulation::kuka_iiwa::ApplyDriverConfig ( const IiwaDriver driver_config,
const std::string &  model_instance_name,
const multibody::MultibodyPlant< double > &  sim_plant,
const std::map< std::string, multibody::parsing::ModelInstanceInfo > &  models_from_directives,
const systems::lcm::LcmBuses lcms,
systems::DiagramBuilder< double > *  builder 
)

Wires up Drake systems between an LCM interface and the actuation input ports of a MultibodyPlant.

This simulates the role that driver software and control cabinets would take in real life.

Precondition
model_instance_name is in models_from_directives.
driver_config.hand_model_name is in models_from_directives.

◆ BuildIiwaControl()

void drake::manipulation::kuka_iiwa::BuildIiwaControl ( const multibody::MultibodyPlant< double > &  plant,
const multibody::ModelInstanceIndex  iiwa_instance,
const multibody::MultibodyPlant< double > &  controller_plant,
lcm::DrakeLcmInterface lcm,
systems::DiagramBuilder< double > *  builder,
double  ext_joint_filter_tau = 0.01,
const std::optional< Eigen::VectorXd > &  desired_iiwa_kp_gains = std::nullopt,
IiwaControlMode  control_mode = IiwaControlMode::kPositionAndTorque 
)

Given a plant (and associated iiwa_instance) and a builder, installs in that builder the systems necessary to control and monitor an Iiwa described by controller_plant in that plant.

The installed plant will communicate over the LCM interface lcm.

The installed plant will connect itself to the actuation input port and state output ports in plant corresponding to the Iiwa model.

desired_iiwa_kp_gains is an optional argument to pass in gains corresponding to the Iiwa Dof (7) in the controller. If no argument is passed, the gains derived from hardware will be used instead (hardcoded within the implementation of this function). These gains must be nullopt if control_mode does not include position control.

control_mode the control mode for the controller.

Note: The Diagram will maintain an internal reference to controller_plant, so you must ensure that controller_plant has a longer lifetime than the Diagram.

◆ BuildSimplifiedIiwaControl()

IiwaControlPorts drake::manipulation::kuka_iiwa::BuildSimplifiedIiwaControl ( const multibody::MultibodyPlant< double > &  plant,
const multibody::ModelInstanceIndex  iiwa_instance,
const multibody::MultibodyPlant< double > &  controller_plant,
systems::DiagramBuilder< double > *  builder,
double  ext_joint_filter_tau = 0.01,
const std::optional< Eigen::VectorXd > &  desired_iiwa_kp_gains = std::nullopt,
IiwaControlMode  control_mode = IiwaControlMode::kPositionAndTorque 
)

A simplified Iiwa controller builder to construct an InverseDynamicsController without adding LCM I/O systems.

See also
BuildIiwaControl()

◆ get_iiwa_max_joint_velocities()

VectorX<double> drake::manipulation::kuka_iiwa::get_iiwa_max_joint_velocities ( )

Returns the maximum joint velocities (rad/s) provided by Kuka.

◆ ParseIiwaControlMode()

IiwaControlMode drake::manipulation::kuka_iiwa::ParseIiwaControlMode ( const std::string &  control_mode)

Parses control mode with the following mapping:

  • "position_only": kPositionOnly
  • "torque_only": kTorqueOnly
  • "position_and_torque": kPositionAndTorque

◆ position_enabled()

constexpr bool drake::manipulation::kuka_iiwa::position_enabled ( IiwaControlMode  control_mode)

Reports if the given control mode includes positions.

◆ torque_enabled()

constexpr bool drake::manipulation::kuka_iiwa::torque_enabled ( IiwaControlMode  control_mode)

Reports if the given control mode includes torques.

Variable Documentation

◆ kIiwaArmNumJoints

constexpr int kIiwaArmNumJoints = 7

◆ kIiwaLcmStatusPeriod

const double kIiwaLcmStatusPeriod