Constants defined in this file are for the Schunk WSG gripper modeled in models/schunk_wsg_50.sdf.
#include <memory>#include "drake/common/eigen_types.h"#include "drake/systems/framework/vector_system.h"#include "drake/systems/primitives/matrix_gain.h"Classes | |
| class | MultibodyForceToWsgForceSystem< T > |
| Extract the gripper measured force from the generalized forces on the two fingers. More... | |
Namespaces | |
| drake | |
| drake::manipulation | |
| drake::manipulation::schunk_wsg | |
Functions | |
| template<typename T > | |
| VectorX< T > | GetSchunkWsgOpenPosition () |
| Returns the position vector corresponding to the open position of the gripper. More... | |
| template<typename T > | |
| std::unique_ptr< systems::MatrixGain< T > > | MakeMultibodyStateToWsgStateSystem () |
| Extract the distance between the fingers (and its time derivative) out of the plant model which pretends the two fingers are independent. More... | |
| template<typename T > | |
| std::unique_ptr< systems::VectorSystem< T > > | MakeMultibodyForceToWsgForceSystem () |
| Helper method to create a MultibodyForceToWsgForceSystem. More... | |
Variables | |
| constexpr int | kSchunkWsgNumActuators = 2 |
| constexpr int | kSchunkWsgNumPositions = 2 |
| constexpr int | kSchunkWsgNumVelocities = 2 |
| constexpr int | kSchunkWsgPositionIndex = 0 |
| constexpr int | kSchunkWsgVelocityIndex |
| constexpr double | kSchunkWsgLcmStatusPeriod = 0.05 |