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} |
Per BuildIiwaControl. More... | |
std::string | control_mode {"position_and_torque"} |
The driver's control mode. More... | |
std::string | lcm_bus {"default"} |
void Serialize | ( | Archive * | a | ) |
std::string control_mode {"position_and_torque"} |
The driver's control mode.
Valid options (per ParseIiwaControlMode) are:
double ext_joint_filter_tau {0.01} |
Per BuildIiwaControl.
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.
std::string lcm_bus {"default"} |