Drake
Drake C++ Documentation
drake::manipulation Namespace Reference

Namespaces

 kinova_jaco
 
 kuka_iiwa
 
 schunk_wsg
 
 util
 

Classes

struct  ZeroForceDriver
 A driver that applies zero actuation to every joint of a model. More...
 

Typedefs

using NamedPositions = drake::string_map< drake::string_map< Eigen::VectorXd > >
 A map-of-maps {model_instance_name: {joint_name: joint_positions}} that describes joint positions. More...
 

Functions

template<typename... Types>
void ApplyDriverConfigs (const std::map< std::string, std::variant< Types... >> &driver_configs, const multibody::MultibodyPlant< double > &sim_plant, const std::vector< multibody::parsing::ModelInstanceInfo > &models_from_directives, const systems::lcm::LcmBuses &lcm_buses, systems::DiagramBuilder< double > *builder)
 Apply many driver configurations to a model. More...
 
void ApplyNamedPositionsAsDefaults (const NamedPositions &input, drake::multibody::MultibodyPlant< double > *plant)
 Sets default joint positions in the given plant according to the given input (which specifies joints by their string name). More...
 
void ApplyDriverConfig (const ZeroForceDriver &driver_config, const std::string &model_instance_name, const multibody::MultibodyPlant< double > &sim_plant, const std::map< std::string, multibody::parsing::ModelInstanceInfo > &models_from_directives, const systems::lcm::LcmBuses &lcms, systems::DiagramBuilder< double > *builder)
 Applies zero actuation to every joint of a model mainly for debugging and testing purposes. More...
 

Typedef Documentation

◆ NamedPositions

A map-of-maps {model_instance_name: {joint_name: joint_positions}} that describes joint positions.

Note that a given joint's positions are always spelled as a vector, even though for the most common joint types (prismatic, revolute, screw, etc.) the vector will only contain a single element.

Function Documentation

◆ ApplyDriverConfig()

void drake::manipulation::ApplyDriverConfig ( const ZeroForceDriver driver_config,
const std::string &  model_instance_name,
const multibody::MultibodyPlant< double > &  sim_plant,
const std::map< std::string, multibody::parsing::ModelInstanceInfo > &  models_from_directives,
const systems::lcm::LcmBuses lcms,
systems::DiagramBuilder< double > *  builder 
)

Applies zero actuation to every joint of a model mainly for debugging and testing purposes.

Precondition
The sim_plant.is_finalized() is true.

◆ ApplyDriverConfigs()

void drake::manipulation::ApplyDriverConfigs ( const std::map< std::string, std::variant< Types... >> &  driver_configs,
const multibody::MultibodyPlant< double > &  sim_plant,
const std::vector< multibody::parsing::ModelInstanceInfo > &  models_from_directives,
const systems::lcm::LcmBuses lcm_buses,
systems::DiagramBuilder< double > *  builder 
)

Apply many driver configurations to a model.

A "driver configuration" helps stack Drake systems between an LCM interface subscriber system and the actuation input ports of a MultibodyPlant (to enact the driver command), as well as the output ports of a MultibodyPlant back to an LCM interface publisher system (to provide the driver status).

These conceptually simulate "drivers" – they take the role that driver software and control cabinets would take in real life – but may also model some physical properties of the robot that are not easily reflected in MultibodyPlant (e.g., the WSG belt drive).

The caller of this function is responsible for including the variant members' apply function, such as schunk_wsg_driver_functions.h.

driver_configs The configurations to apply. sim_plant The plant containing the model. models_from_directives All of the ModelInstanceInfos from previously- loaded directives. lcm_buses The available LCM buses to drive and/or sense from this driver. builder The DiagramBuilder into which to install this driver.

◆ ApplyNamedPositionsAsDefaults()

void drake::manipulation::ApplyNamedPositionsAsDefaults ( const NamedPositions input,
drake::multibody::MultibodyPlant< double > *  plant 
)

Sets default joint positions in the given plant according to the given input (which specifies joints by their string name).

The default positions for joints not mentioned will remain unchanged.

Exceptions
std::exceptionif the number of position values in the input and the actual number of positions for the intended joint do not match.