Drake
Drake C++ Documentation
IiwaDriver Struct Reference

Detailed Description

This config struct specifies how to wire 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.

It creates an LCM publisher on the IIWA_STATUS channel and an LCM subscriber on the IIWA_COMMAND channel.

#include <drake/manipulation/kuka_iiwa/iiwa_driver.h>

Public Member Functions

template<typename Archive >
void Serialize (Archive *a)
 

Public Attributes

std::string hand_model_name
 The name of the model (name element of the add_model directive) in the simulation that the driver will analyze to compute end effector inertia for its copy of the arm in inverse dynamics. More...
 
double ext_joint_filter_tau {0.01}
 A time constant used to low-pass filter external torque inputs. More...
 
std::optional< Eigen::VectorXd > desired_kp_gains
 Optionally pass in gains corresponding to the Iiwa Dof (7) in the controller. More...
 
std::string control_mode {"position_and_torque"}
 The driver's control mode. More...
 
std::optional< std::string > arm_child_frame_name
 Optionally give an alternative frame on the arm model for its weld point to the world. More...
 
std::optional< std::string > gripper_parent_frame_name
 Optionally give an alternative frame on the arm model for its weld point to the gripper. More...
 
std::string lcm_bus {"default"}
 
double lcm_status_period {kIiwaLcmStatusPeriod}
 The period in seconds at which status reports are expected. More...
 

Member Function Documentation

◆ Serialize()

void Serialize ( Archive *  a)

Member Data Documentation

◆ arm_child_frame_name

std::optional<std::string> arm_child_frame_name

Optionally give an alternative frame on the arm model for its weld point to the world.

If not supplied, the child_frame_name in the arm's ModelInstanceInfo will be used.

◆ control_mode

std::string control_mode {"position_and_torque"}

The driver's control mode.

Valid options (per ParseIiwaControlMode) are:

  • "position_only"
  • "position_and_torque" (default)
  • "torque_only"

◆ desired_kp_gains

std::optional<Eigen::VectorXd> desired_kp_gains

Optionally pass in gains corresponding to the Iiwa Dof (7) in the controller.

If no value is passed, the gains derived from hardware will be used instead (hardcoded within the implementations of functions accepting this struct). These gains must be nullopt if control_mode does not include position control.

◆ ext_joint_filter_tau

double ext_joint_filter_tau {0.01}

A time constant used to low-pass filter external torque inputs.

◆ gripper_parent_frame_name

std::optional<std::string> gripper_parent_frame_name

Optionally give an alternative frame on the arm model for its weld point to the gripper.

If not supplied, the parent_frame_name in the gripper's ModelInstanceInfo will be used.

◆ hand_model_name

std::string hand_model_name

The name of the model (name element of the add_model directive) in the simulation that the driver will analyze to compute end effector inertia for its copy of the arm in inverse dynamics.

◆ lcm_bus

std::string lcm_bus {"default"}

◆ lcm_status_period

double lcm_status_period {kIiwaLcmStatusPeriod}

The period in seconds at which status reports are expected.


The documentation for this struct was generated from the following file: