A mask on the degrees of freedom (dofs) of a MultibodyPlant instance, partitioning the plant's dofs into "selected" and "unselected" dofs.
A DofMask has two measures: its "size" and its "count". The size is the number of dofs it can mask in total (the selected and unselected dofs together). It must be equal to the number of dofs contained in a MultibodyPlant instance (its q
s). The interpretation of a DofMask's indices come from the plant's ordering of its own dofs and their indices. A DofMask instance's valid index values lie in the range [0, size())
. The count of the DofMask is the number of selected dofs.
Currently, DofMask is only compatible with MultibodyPlant instances where the generalized velocities are the same as the time derivatives of the generalized positions. Or, in other words, vᵢ = q̇ᵢ
. This property holds for all single-dof joints but is not generally true for all joints (e.g., floating joints or roll-pitch-yaw ball joints).
#include <drake/planning/dof_mask.h>
Public Member Functions | |
int | size () const |
@group Introspection More... | |
int | count () const |
Reports this DofMask instance's number of selected dofs. More... | |
std::vector< multibody::JointIndex > | GetJoints (const multibody::MultibodyPlant< double > &plant) const |
Creates a collection of all of the joints implied by the selected dofs in this . More... | |
bool | operator== (const DofMask &o) const |
Note: o.size() may be different from this->size() . More... | |
bool | operator[] (int index) const |
std::string | to_string () const |
The string representation of the mask – it encodes the full mask size clearly indicating which dofs are selected and which are unselected. More... | |
DofMask | Complement () const |
@group Combining masks More... | |
DofMask | Union (const DofMask &other) const |
Creates the union of this and other . More... | |
DofMask | Intersect (const DofMask &other) const |
Creates the intersection of this and other . More... | |
DofMask | Subtract (const DofMask &other) const |
Creates the set difference of this and other . More... | |
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable | |
DofMask (const DofMask &)=default | |
DofMask & | operator= (const DofMask &)=default |
DofMask (DofMask &&)=default | |
DofMask & | operator= (DofMask &&)=default |
DofMask () | |
@group Constructors More... | |
DofMask (int size, bool value) | |
Full/empty constructor. More... | |
DofMask (std::initializer_list< bool > values) | |
Constructs a DofMask from an initializer list of bool. More... | |
DofMask (std::vector< bool > values) | |
Constructs a DofMask from a vector of bool. More... | |
void | GetFromArray (const Eigen::Ref< const Eigen::VectorXd > &full_vec, drake::EigenPtr< Eigen::VectorXd > output) const |
@group Scattering and gathering More... | |
Eigen::VectorXd | GetFromArray (const Eigen::Ref< const Eigen::VectorXd > &full_vec) const |
Overload for GetFromArray() which returns the read values in a new vector instead of writing to an output argument. More... | |
void | GetColumnsFromMatrix (const Eigen::Ref< const Eigen::MatrixXd > &full_mat, drake::EigenPtr< Eigen::MatrixXd > output) const |
Gets a subset of the columns of full_mat and writes them to output . More... | |
Eigen::MatrixXd | GetColumnsFromMatrix (const Eigen::Ref< const Eigen::MatrixXd > &full_mat) const |
Overload for GetColumnsFromMatrix() which returns the read values in a new matrix instead of writing to an output argument. More... | |
void | SetInArray (const Eigen::Ref< const Eigen::VectorXd > &vec, drake::EigenPtr< Eigen::VectorXd > output) const |
Sets the values given in vec into output . More... | |
Static Public Member Functions | |
static DofMask | MakeFromModel (const multibody::MultibodyPlant< double > &plant, multibody::ModelInstanceIndex model_index) |
@group Factory methods More... | |
static DofMask | MakeFromModel (const multibody::MultibodyPlant< double > &plant, const std::string &model_name) |
Creates the DofMask associated with the model instance (named by model_name ) in plant . More... | |
DofMask | ( | ) |
@group Constructors
There are a number of constructors available. Using these constructors puts the burden on the caller to know what the appropriate size is and what the interpretation of the indices is. If used in conjunction with a MultibodyPlant instance, the caller must guarantee that the DofMask is constructed to a compatible size with the plant. Default constructor; creates a mask with no dofs (size() = count() = 0 ).
Full/empty constructor.
This allows for construction of a mask with the given size
where all dofs are either selected (value = true
) or unselected.
DofMask | ( | std::initializer_list< bool > | values | ) |
Constructs a DofMask from an initializer list of bool.
DofMask | ( | std::vector< bool > | values | ) |
Constructs a DofMask from a vector of bool.
DofMask Complement | ( | ) | const |
@group Combining masks
We can think of the masks as sets – the iᵗʰ dof is in the set if it's selected. Therefore, we can apply set operations to create new masks from existing masks. Each operation creates a new DofMask.
The parameter for these methods, when present, must have the same size() as this->size()
. Returns a new mask such that its selected dofs are this
mask's unselected dofs and vice versa.
int count | ( | ) | const |
Reports this DofMask instance's number of selected dofs.
void GetColumnsFromMatrix | ( | const Eigen::Ref< const Eigen::MatrixXd > & | full_mat, |
drake::EigenPtr< Eigen::MatrixXd > | output | ||
) | const |
Gets a subset of the columns of full_mat
and writes them to output
.
Similar to GetFromArray(), but instead of single scalar values, whole columns are read from full_mat
and written to output
.
Eigen::MatrixXd GetColumnsFromMatrix | ( | const Eigen::Ref< const Eigen::MatrixXd > & | full_mat | ) | const |
Overload for GetColumnsFromMatrix() which returns the read values in a new matrix instead of writing to an output argument.
full_mat.cols() == size()
. void GetFromArray | ( | const Eigen::Ref< const Eigen::VectorXd > & | full_vec, |
drake::EigenPtr< Eigen::VectorXd > | output | ||
) | const |
@group Scattering and gathering
These functions allow the mask to selectively write dof-specific values into a full state vector or read dof-specific values from a full state vector into a compact, selected-dofs-only vector. Only the selected dofs in a DofMask instance participate in the operation. Gets a subset of the values in full_vec
and writes them to output
. The values read from full_vec
associated with the selected dofs in this
are written into output
with the same relative ordering as they appear in full_vec
.
For example:
Eigen::VectorXd GetFromArray | ( | const Eigen::Ref< const Eigen::VectorXd > & | full_vec | ) | const |
Overload for GetFromArray() which returns the read values in a new vector instead of writing to an output argument.
full_vec.size() == size()
. std::vector<multibody::JointIndex> GetJoints | ( | const multibody::MultibodyPlant< double > & | plant | ) | const |
Creates a collection of all of the joints implied by the selected dofs in this
.
The returned joint indices are reported in increasing order.
plant
is compatible with DofMask. plant.num_positions() == size()
. Creates the intersection of this
and other
.
The result includes all selected dofs that are in both this
and other
.
size() == other.size()
.
|
static |
@group Factory methods
These factory methods construct DofMask instances from a MultibodyPlant. Which dofs are marked as "selected" depends on the particular factory method.Creates the DofMask associated with a model instance (indicated by model_index
) in plant
.
std::exception | if plant doesn't satisfy the compatibility requirements for DofMask. |
|
static |
Creates the DofMask associated with the model instance (named by model_name
) in plant
.
std::exception | if plant doesn't satisfy the compatibility requirements for DofMask. |
bool operator== | ( | const DofMask & | o | ) | const |
Note: o.size()
may be different from this->size()
.
They will, by definition report as not equal.
void SetInArray | ( | const Eigen::Ref< const Eigen::VectorXd > & | vec, |
drake::EigenPtr< Eigen::VectorXd > | output | ||
) | const |
Sets the values given in vec
into output
.
This is the inverse of GetFromArray(). vec
contains count() values and the iᵗʰ value in vec
is written to output
at the index corresponding to the iᵗʰ selected dof in this
. Entries in output
which correspond to the unselected dofs will remain unchanged.
For example:
int size | ( | ) | const |
@group Introspection
Reports this DofMask instance's total number of indexable dofs.
Creates the set difference of this
and other
.
The result includes only those selected dofs in this
that are not in other
.
size() == other.size()
. std::string to_string | ( | ) | const |
The string representation of the mask – it encodes the full mask size clearly indicating which dofs are selected and which are unselected.
The exact format is not guaranteed to remain fixed, but always clear.
Creates the union of this
and other
.
The result includes all selected dofs in either this
or other
.
size() == other.size()
.