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 (systems::DiagramBuilder< double > *builder, lcm::DrakeLcmInterface *lcm, const multibody::MultibodyPlant< double > &plant, const multibody::ModelInstanceIndex iiwa_instance, const IiwaDriver &driver_config, const multibody::MultibodyPlant< double > &controller_plant)
 Given a plant (and associated iiwa_instance) and abuilder, installs in that builder the systems necessary to control and monitor an Iiwa described by controller_plant in that plant. More...
 
IiwaControlPorts BuildSimplifiedIiwaControl (systems::DiagramBuilder< double > *builder, const multibody::MultibodyPlant< double > &plant, const multibody::ModelInstanceIndex iiwa_instance, const IiwaDriver &driver_config, const multibody::MultibodyPlant< double > &controller_plant)
 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...
 
std::string FormatIiwaControlMode (IiwaControlMode mode)
 Formats control mode to a string using the mappping shown above. 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 ( systems::DiagramBuilder< double > *  builder,
lcm::DrakeLcmInterface lcm,
const multibody::MultibodyPlant< double > &  plant,
const multibody::ModelInstanceIndex  iiwa_instance,
const IiwaDriver driver_config,
const multibody::MultibodyPlant< double > &  controller_plant 
)

Given a plant (and associated iiwa_instance) and abuilder, 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.

The values in driver_config further specify Diagram behavior; see IiwaDriver for more details.

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.

The torque values in the published LCM status messages will follow the IIWA-specific LCM conventions outlined in manipulation/README.

◆ BuildSimplifiedIiwaControl()

IiwaControlPorts drake::manipulation::kuka_iiwa::BuildSimplifiedIiwaControl ( systems::DiagramBuilder< double > *  builder,
const multibody::MultibodyPlant< double > &  plant,
const multibody::ModelInstanceIndex  iiwa_instance,
const IiwaDriver driver_config,
const multibody::MultibodyPlant< double > &  controller_plant 
)

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

See also
BuildIiwaControl()

◆ FormatIiwaControlMode()

std::string drake::manipulation::kuka_iiwa::FormatIiwaControlMode ( IiwaControlMode  mode)

Formats control mode to a string using the mappping shown above.

◆ 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