#include <string>#include <vector>#include "drake/common/drake_assert.h"#include "drake/common/eigen_types.h"Namespaces | |
| namespace | drake |
| namespace | drake::manipulation |
| namespace | drake::manipulation::kuka_iiwa |
Enumerations | |
| enum class | IiwaControlMode { kPositionOnly , kTorqueOnly , kPositionAndTorque } |
| Enumeration for control modes. More... | |
Functions | |
| VectorX< double > | get_iiwa_max_joint_velocities () |
| Returns the maximum joint velocities (rad/s) provided by Kuka. | |
| constexpr bool | position_enabled (IiwaControlMode control_mode) |
| Reports if the given control mode includes positions. | |
| constexpr bool | torque_enabled (IiwaControlMode control_mode) |
| Reports if the given control mode includes torques. | |
| IiwaControlMode | ParseIiwaControlMode (const std::string &control_mode) |
| Parses control mode with the following mapping: | |
| std::string | FormatIiwaControlMode (IiwaControlMode mode) |
| Formats control mode to a string using the mappping shown above. | |
Variables | |
| constexpr int | kIiwaArmNumJoints = 7 |
| const double | kIiwaLcmStatusPeriod |