Drake
Drake C++ Documentation
build_iiwa_control.h File Reference

Detailed Description

Iiwa controller and controller plant setup.

This class implements the software stack of the Iiwa arm and the LCM-to-FRI adapter installed in it as it is exposed in https://github.com/RobotLocomotion/drake-iiwa-driver. The driver in this repository exposes three options:

  • position-only control,
  • position-and-torque control, where feedforward torque command is optional, and
  • torque-only control, added with nominal gravity compensation. The arm receives position and/or torque commands (lcmt_iiwa_command) and emits status (lcmt_iiwa_status); the Iiwa controller built here takes care of translating the command into torques on the Iiwa joints and the Iiwa measured positions and torques into those status messages. Note that only the 7 DoF Iiwa arm is supported.

A simulated controller maintains an entire separate Iiwa plant (not the simulated plant!) to perform inverse dynamics computations. These computations correspond to the servoing and gravity compensation done on the real Iiwa; disagreement between the controller model and the simulated model represents errors in the servo, end-effector, and gravity-compensation configuration.

#include <optional>
#include <string>
#include <Eigen/Dense>
#include "drake/lcm/drake_lcm_interface.h"
#include "drake/manipulation/kuka_iiwa/iiwa_constants.h"
#include "drake/multibody/plant/multibody_plant.h"
Include dependency graph for build_iiwa_control.h:

Classes

struct  IiwaControlPorts
 The return type of BuildSimplifiedIiwaControl(). More...
 

Namespaces

 drake
 
 drake::manipulation
 
 drake::manipulation::kuka_iiwa
 

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...