Drake
drake::multibody::internal Namespace Reference

Namespaces

 multibody_model
 

Classes

class  AccelerationKinematicsCache
 This class is one of the cache entries in the Context. More...
 
class  ArticulatedBodyInertiaCache
 This class is one of the cache entries in the Context. More...
 
class  BodyNode
 For internal use only of the MultibodyTree implementation. More...
 
class  BodyNodeImpl
 For internal use only of the MultibodyTree implementation. More...
 
struct  BodyNodeTopology
 Data structure to store the topological information associated with a tree node. More...
 
class  BodyNodeWelded
 This class represents a BodyNode for nodes with zero degrees of freedom. More...
 
struct  BodyTopology
 Data structure to store the topological information associated with a Body. More...
 
struct  ContactJacobians
 Stores the computed contact Jacobians when a point contact model is used. More...
 
struct  DirectionChangeLimiter
 This struct implements an internal (thus within internal::) detail of the implicit Stribeck solver. More...
 
struct  ForceElementTopology
 Data structure to store the topological information associated with a ForceElement. More...
 
struct  FrameTopology
 Data structure to store the topological information associated with a Frame. More...
 
struct  GeometryPairContactWrenchEvaluatorBinding
 This struct records the contact wrench evaluator, together with the indices of lambda used in this evaluator, among all lambda (the variable bound with the StaticEquilibriumConstraint). More...
 
class  HydroelasticTractionCalculator
 A class for computing the spatial forces on rigid bodies in a MultibodyPlant using the hydroelastic contact model, as described in: More...
 
struct  ImplicitStribeckSolverResults
 This struct stores the results from a computation performed with ImplicitStribeckSolver. More...
 
struct  JointActuatorTopology
 Data structure to store the topological information associated with a JointActuator. More...
 
class  Mobilizer
 Mobilizer is a fundamental object within Drake's multibody engine used to specify the allowed motions between two Frame objects within a MultibodyTree. More...
 
class  MobilizerImpl
 Base class for specific Mobilizer implementations with the number of generalized positions and velocities resolved at compile time as template parameters. More...
 
class  MobilizerTester
 
struct  MobilizerTopology
 Data structure to store the topological information associated with a Mobilizer object. More...
 
class  ModelInstance
 
class  MultibodyGraph
 Defines a multibody graph consisting of bodies interconnected by joints. More...
 
class  MultibodyTree
 MultibodyTree provides a representation for a physical system consisting of a collection of interconnected rigid and deformable bodies. More...
 
class  MultibodyTreeSystem
 This is a bare Drake System providing just enough functionality to allow standalone exercise of a MultibodyTree. More...
 
class  MultibodyTreeTopology
 Data structure to store the topological information associated with an entire MultibodyTree. More...
 
class  PositionKinematicsCache
 This class is one of the cache entries in the Context. More...
 
class  PrismaticMobilizer
 This Mobilizer allows two frames to translate relative to one another along an axis whose direction is constant when measured in either this mobilizer's inboard frame or its outboard frame. More...
 
class  QuaternionFloatingMobilizer
 This Mobilizer allows two frames to move freely relatively to one another. More...
 
class  RevoluteMobilizer
 This Mobilizer allows two frames to rotate relatively to one another around an axis that is constant when measured in either this mobilizer's inboard or outboard frames, while the distance between the two frames does not vary. More...
 
class  SpaceXYZMobilizer
 This mobilizer models a gimbal joint between an inboard frame F and an outboard frame M that allows frame M to rotate freely with respect to F ( though a gimbal joint provides arbitrary orientation like a ball joint but with some restrictions, discussed below). More...
 
class  StaticFrictionConeComplementarityNonlinearConstraint
 The nonlinear constraints to be imposed for static friction force. More...
 
class  VelocityKinematicsCache
 This class is one of the cache entries in the Context. More...
 
class  WeldMobilizer
 This mobilizer fixes the relative pose X_FM of an outboard frame M in an inboard frame F as if "welding" them together at this fixed relative pose. More...
 

Typedefs

typedef std::map< std::string, Eigen::Vector4d > MaterialMap
 A map from the name of a material to its color. More...
 
using JointTypeIndex = TypeSafeIndex< class JointTypeTag >
 Type used to identify joint types. More...
 
using MobilizerIndex = TypeSafeIndex< class MobilizerTag >
 Type used to identify mobilizers by index in a multibody tree system. More...
 
using BodyNodeIndex = TypeSafeIndex< class BodyNodeTag >
 Type used to identify tree nodes by index within a multibody tree system. More...
 

Functions

void CalcDistanceDerivatives (const MultibodyPlant< double > &plant, const systems::Context< double > &context, const Frame< double > &frameA, const Frame< double > &frameB, const Eigen::Vector3d &p_ACa, double distance, const Eigen::Vector3d &nhat_BA_W, const Eigen::Ref< const AutoDiffVecXd > &q, AutoDiffXd *distance_autodiff)
 
void CalcDistanceDerivatives (const MultibodyPlant< AutoDiffXd > &plant, const systems::Context< AutoDiffXd > &context, const Frame< AutoDiffXd > &frameA, const Frame< AutoDiffXd > &frameB, const Vector3< AutoDiffXd > &p_ACa, const AutoDiffXd &distance_autodiff, const Vector3< AutoDiffXd > &nhat_BA_W, const Eigen::Ref< const Eigen::VectorXd > &q, double *distance)
 This is the overloaded version of CalcDistanceDerivatives for plant being MultibodyPlant<AutoDiffXd> instead of MultibodyPlant<double>. More...
 
void CalcDistanceDerivatives (const MultibodyPlant< double > &, const systems::Context< double > &, const Frame< double > &, const Frame< double > &, const Eigen::Vector3d &, double distance_in, const Eigen::Vector3d &, const Eigen::Ref< const VectorX< double >> &, double *distance_out)
 
template<typename T >
void CalcDistanceDerivatives (const MultibodyPlant< T > &, const systems::Context< T > &, const Frame< T > &, const Frame< T > &, const Vector3< T > &, T distance_in, const Vector3< T > &, const Eigen::Ref< const VectorX< T >> &, T *distance_out)
 This is the overloaded version of CalcDistanceDerivatives for the input q of double scalar type, it just copies distance_in to distance_out. More...
 
template<typename T >
void CheckPlantIsConnectedToSceneGraph (const MultibodyPlant< T > &plant, const systems::Context< T > &plant_context)
 Check if the plant has registered its geometry with the SceneGraph. More...
 
bool AreAutoDiffVecXdEqual (const Eigen::Ref< const VectorX< AutoDiffXd >> &a, const Eigen::Ref< const VectorX< AutoDiffXd >> &b)
 
void UpdateContextConfiguration (drake::systems::Context< double > *context, const MultibodyPlant< double > &plant, const Eigen::Ref< const VectorX< double >> &q)
 Check if the generalized positions in context are the same as q. More...
 
void UpdateContextConfiguration (drake::systems::Context< double > *context, const MultibodyPlant< double > &plant, const Eigen::Ref< const AutoDiffVecXd > &q)
 
void UpdateContextConfiguration (systems::Context< AutoDiffXd > *context, const MultibodyPlant< AutoDiffXd > &plant, const Eigen::Ref< const AutoDiffVecXd > &q)
 
bool AreAutoDiffVecXdEqual (const Eigen::Ref< const AutoDiffVecXd > &a, const Eigen::Ref< const AutoDiffVecXd > &b)
 Determines if a and b are equal. More...
 
void UpdateContextConfiguration (drake::systems::Context< double > *context, const MultibodyPlant< double > &plant, const Eigen::Ref< const VectorX< AutoDiffXd >> &q)
 
template<typename DerivedA >
std::enable_if< is_eigen_vector_of< DerivedA, double >::value, Eigen::Matrix< double, DerivedA::RowsAtCompileTime, 1 > >::type NormalizeVector (const Eigen::MatrixBase< DerivedA > &a)
 Normalize an Eigen vector of doubles. More...
 
template<typename T >
const MultibodyPlant< T > & RefFromPtrOrThrow (const MultibodyPlant< T > *const plant)
 If plant is not nullptr, return a reference to the MultibodyPlant to which it points. More...
 
CoulombFriction< doubledefault_friction ()
 Default value of the Coulomb's law coefficients of friction for when they are not specified in the URDF/SDF file. More...
 
Vector3d ToVector3 (const ignition::math::Vector3d &vector)
 Helper function to express an ignition::math::Vector3d instance as a Vector3d instance. More...
 
RigidTransformd ToRigidTransform (const ignition::math::Pose3d &pose)
 Helper function to express an ignition::math::Pose3d instance as a RigidTransform instance. More...
 
string GetFullPath (const std::string &file_name)
 Obtains the full path of @file_name. More...
 
string ResolveUri (const std::string &uri, const PackageMap &package_map, const std::string &root_dir)
 Resolves the full path of a URI. More...
 
std::unique_ptr< geometry::ShapeMakeShapeFromSdfGeometry (const sdf::Geometry &sdf_geometry)
 Given an sdf::Geometry object representing a <geometry> element from an SDF file, this method makes a new drake::geometry::Shape object from this specification. More...
 
std::unique_ptr< GeometryInstanceMakeGeometryInstanceFromSdfVisual (const sdf::Visual &sdf_visual)
 Given an sdf::Visual object representing a <visual> element from an SDF file, this method makes a new drake::geometry::GeometryInstance object from this specification. More...
 
IllustrationProperties MakeVisualPropertiesFromSdfVisual (const sdf::Visual &sdf_visual)
 
RigidTransformd MakeGeometryPoseFromSdfCollision (const sdf::Collision &sdf_collision)
 
CoulombFriction< doubleMakeCoulombFrictionFromSdfCollisionOde (const sdf::Collision &sdf_collision)
 Extracts the material properties from the given sdf::Visual object. More...
 
sdf::Visual ResolveVisualUri (const sdf::Visual &original, const multibody::PackageMap &package_map, const std::string &root_dir)
 Given an sdf::Visual object representing a <visual> element from an SDF file, this method makes a new Visual object which resolves the uri for the mesh element, if present. More...
 
ModelInstanceIndex AddModelFromSdfFile (const std::string &file_name, const std::string &model_name, const PackageMap &package_map, MultibodyPlant< double > *plant, geometry::SceneGraph< double > *scene_graph=nullptr)
 Parses a <model> element from the SDF file specified by file_name and adds it to plant. More...
 
std::vector< ModelInstanceIndexAddModelsFromSdfFile (const std::string &file_name, const PackageMap &package_map, MultibodyPlant< double > *plant, geometry::SceneGraph< double > *scene_graph=nullptr)
 Parses all <model> elements from the SDF file specified by file_name and adds them to plant. More...
 
bool ParseStringAttribute (const tinyxml2::XMLElement *node, const char *attribute_name, std::string *val)
 Parses a string attribute of node named attribute_name into val. More...
 
bool ParseScalarAttribute (const tinyxml2::XMLElement *node, const char *attribute_name, double *val)
 Parses a scalar attribute of node named attribute_name into val. More...
 
bool ParseVectorAttribute (const tinyxml2::XMLElement *node, const char *attribute_name, Eigen::Vector3d *val)
 Parses an attribute of node named attribute_name consisting of 3 scalar values into val. More...
 
bool ParseVectorAttribute (const tinyxml2::XMLElement *node, const char *attribute_name, Eigen::Vector4d *val)
 Parses an attribute of node named attribute_name consisting of 4 scalar values into val. More...
 
math::RigidTransformd OriginAttributesToTransform (const tinyxml2::XMLElement *node)
 Parses "xyz" and "rpy" attributes from node and returns a RigidTransformd created from them. More...
 
bool ParseThreeVectorAttribute (const tinyxml2::XMLElement *node, const char *attribute_name, Eigen::Vector3d *val)
 Parses a three vector value from parameter node, which is an XML node. More...
 
void ParseMaterial (const XMLElement *node, MaterialMap *materials)
 
geometry::GeometryInstance ParseVisual (const std::string &parent_element_name, const PackageMap &package_map, const std::string &root_dir, const XMLElement *node, MaterialMap *materials)
 
geometry::GeometryInstance ParseCollision (const std::string &parent_element_name, const PackageMap &package_map, const std::string &root_dir, const XMLElement *node, CoulombFriction< double > *friction)
 
void ParseMaterial (const tinyxml2::XMLElement *node, MaterialMap *materials)
 Parses a "material" element in node and adds the result to materials. More...
 
geometry::GeometryInstance ParseVisual (const std::string &parent_element_name, const PackageMap &package_map, const std::string &root_dir, const tinyxml2::XMLElement *node, MaterialMap *materials)
 Parses a "visual" element in node. More...
 
geometry::GeometryInstance ParseCollision (const std::string &parent_element_name, const PackageMap &package_map, const std::string &root_dir, const tinyxml2::XMLElement *node, CoulombFriction< double > *friction)
 Parses a "collision" element in node. More...
 
ModelInstanceIndex AddModelFromUrdfFile (const std::string &file_name, const std::string &model_name, const PackageMap &package_map, MultibodyPlant< double > *plant, geometry::SceneGraph< double > *scene_graph=nullptr)
 Parses a <robot> element from the URDF file specified by file_name and adds it to plant. More...
 
std::unique_ptr< SurfaceMesh< double > > CreateSurfaceMesh ()
 
GeometryId FindGeometry (const MultibodyPlant< double > &plant, const std::string body_name)
 
 TEST_P (MultibodyPlantHydroelasticTractionTests, VanillaTraction)
 
 TEST_P (MultibodyPlantHydroelasticTractionTests, TractionWithFriction)
 
 TEST_P (MultibodyPlantHydroelasticTractionTests, TractionWithDissipation)
 
 TEST_P (MultibodyPlantHydroelasticTractionTests, VanillaTractionOverPatch)
 
 TEST_P (MultibodyPlantHydroelasticTractionTests, FrictionalTractionOverPatch)
 
 TEST_P (MultibodyPlantHydroelasticTractionTests, TractionOverPatchWithDissipation)
 
 TEST_P (HydroelasticReportingTests, LinearTraction)
 
 TEST_P (HydroelasticReportingTests, LinearSlipVelocity)
 
 INSTANTIATE_TEST_CASE_P (PoseInstantiations, MultibodyPlantHydroelasticTractionTests, ::testing::ValuesIn(poses))
 
 GTEST_TEST (MultibodyGraph, SerialChain)
 
 GTEST_TEST (MultibodyGraph, Weldedsubgraphs)
 
 DRAKE_DEFINE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN_T (AccelerationKinematicsCache)
 
 DRAKE_DEFINE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN_T (ArticulatedBodyInertiaCache)
 
 EXPLICITLY_INSTANTIATE_IMPLS (double)
 
 EXPLICITLY_INSTANTIATE_IMPLS (AutoDiffXd)
 
 EXPLICITLY_INSTANTIATE_IMPLS (symbolic::Expression)
 
template<typename T >
const MultibodyTree< T > & GetInternalTree (const MultibodyTreeSystem< T > &system)
 Access internal tree outside of MultibodyTreeSystem. More...
 

Variables

const RigidTransform< doubleposes []
 
const char kRevoluteType [] = "revolute"
 
const char kPrismaticType [] = "prismatic"
 
const char kWorldBodyName [] = "DefaultWorldBodyName"
 

Typedef Documentation

◆ BodyNodeIndex

using BodyNodeIndex = TypeSafeIndex<class BodyNodeTag>

Type used to identify tree nodes by index within a multibody tree system.

◆ JointTypeIndex

using JointTypeIndex = TypeSafeIndex<class JointTypeTag>

Type used to identify joint types.

◆ MaterialMap

typedef std::map<std::string, Eigen::Vector4d> MaterialMap

A map from the name of a material to its color.

The color is specified in RGBA (Red, Green, Blue, Alpha) format.

◆ MobilizerIndex

using MobilizerIndex = TypeSafeIndex<class MobilizerTag>

Type used to identify mobilizers by index in a multibody tree system.

Function Documentation

◆ AddModelFromSdfFile()

ModelInstanceIndex AddModelFromSdfFile ( const std::string &  file_name,
const std::string &  model_name,
const PackageMap package_map,
MultibodyPlant< double > *  plant,
geometry::SceneGraph< double > *  scene_graph = nullptr 
)

Parses a <model> element from the SDF file specified by file_name and adds it to plant.

The SDF file can only contain a single <model> element. <world> elements (used for instance to specify gravity) are ignored by this method. A new model instance will be added to plant.

Exceptions
std::runtime_errorif the file is not in accordance with the SDF specification containing a message with a list of errors encountered while parsing the file.
std::runtime_errorif there is more than one <model> element or zero of them.
std::exceptionif plant is nullptr or if MultibodyPlant::Finalize() was already called on plant.
Parameters
file_nameThe name of the SDF file to be parsed.
model_nameThe name given to the newly created instance of this model. If empty, the "name" attribute from the model tag will be used.
package_mapAn object that maps ROS packages to their full pathnames.
plantA pointer to a mutable MultibodyPlant object to which the model will be added.
scene_graphA pointer to a mutable SceneGraph object used for geometry registration (either to model visual or contact geometry). May be nullptr.
Returns
The model instance index for the newly added model.

◆ AddModelFromUrdfFile()

ModelInstanceIndex AddModelFromUrdfFile ( const std::string &  file_name,
const std::string &  model_name,
const PackageMap package_map,
MultibodyPlant< double > *  plant,
geometry::SceneGraph< double > *  scene_graph = nullptr 
)

Parses a <robot> element from the URDF file specified by file_name and adds it to plant.

A new model instance will be added to plant.

Exceptions
std::runtime_errorif the file is not in accordance with the URDF specification. The exception contains a message with a list of errors encountered while parsing the file.
Parameters
file_nameThe name of the URDF file to be parsed.
model_nameThe name given to the newly created instance of this model. If empty, the "name" attribute from the model tag will be used.
plantA pointer to a mutable MultibodyPlant object to which the model will be added.
scene_graphA pointer to a mutable SceneGraph object used for geometry registration (either to model visual or contact geometry). May be nullptr.
Returns
The model instance index for the newly added model.

◆ AddModelsFromSdfFile()

std::vector< ModelInstanceIndex > AddModelsFromSdfFile ( const std::string &  file_name,
const PackageMap package_map,
MultibodyPlant< double > *  plant,
geometry::SceneGraph< double > *  scene_graph = nullptr 
)

Parses all <model> elements from the SDF file specified by file_name and adds them to plant.

The SDF file can contain multiple <model> elements. New model instances will be added to plant for each <model> tag in the SDF file.

Exceptions
std::runtime_errorif the file is not in accordance with the SDF specification containing a message with a list of errors encountered while parsing the file.
std::runtime_errorif the file contains no models.
std::exceptionif plant is nullptr or if MultibodyPlant::Finalize() was already called on plant.
Parameters
file_nameThe name of the SDF file to be parsed.
plantA pointer to a mutable MultibodyPlant object to which the model will be added.
package_mapAn object that maps ROS packages to their full pathnames.
scene_graphA pointer to a mutable SceneGraph object used for geometry registration (either to model visual or contact geometry). May be nullptr.
Returns
The set of model instance indices for the newly added models.

◆ AreAutoDiffVecXdEqual() [1/2]

bool drake::multibody::internal::AreAutoDiffVecXdEqual ( const Eigen::Ref< const VectorX< AutoDiffXd >> &  a,
const Eigen::Ref< const VectorX< AutoDiffXd >> &  b 
)

◆ AreAutoDiffVecXdEqual() [2/2]

bool drake::multibody::internal::AreAutoDiffVecXdEqual ( const Eigen::Ref< const AutoDiffVecXd > &  a,
const Eigen::Ref< const AutoDiffVecXd > &  b 
)

Determines if a and b are equal.

a equals to b if they have the same value and gradients. TODO(hongkai.dai) implement and use std::equal_to<> for comparing Eigen vector of AutoDiffXd.

◆ CalcDistanceDerivatives() [1/4]

void CalcDistanceDerivatives ( const MultibodyPlant< double > &  plant,
const systems::Context< double > &  context,
const Frame< double > &  frameA,
const Frame< double > &  frameB,
const Eigen::Vector3d &  p_ACa,
double  distance,
const Eigen::Vector3d &  nhat_BA_W,
const Eigen::Ref< const AutoDiffVecXd > &  q,
AutoDiffXd distance_autodiff 
)
Parameters
plantThe plant for which the distance is computed.
contextThe context containing the generalized position for computing the distance.
frameAThe frame to which geometry A is attached.
frameBThe frame to which geometry B is attached.
p_ACaThe position of the witness point Ca measured and expressed in frame A.
distanceThe signed distance between geometry A and B.
nhat_BA_WThe unit length vector representing the gradient of the signed distance field to geometry B, expressed in the world frame.
qThe generalized position of the plant, it also stores the gradient dq / dz, where z is some other variables.
[out]distance_autodiffContaining the gradient of distance w.r.t z (the same variable as shown up in the gradient of q).

◆ CalcDistanceDerivatives() [2/4]

void CalcDistanceDerivatives ( const MultibodyPlant< AutoDiffXd > &  ,
const systems::Context< AutoDiffXd > &  ,
const Frame< AutoDiffXd > &  ,
const Frame< AutoDiffXd > &  ,
const Vector3< AutoDiffXd > &  ,
const AutoDiffXd distance_autodiff,
const Vector3< AutoDiffXd > &  ,
const Eigen::Ref< const Eigen::VectorXd > &  ,
double distance 
)

This is the overloaded version of CalcDistanceDerivatives for plant being MultibodyPlant<AutoDiffXd> instead of MultibodyPlant<double>.

◆ CalcDistanceDerivatives() [3/4]

void drake::multibody::internal::CalcDistanceDerivatives ( const MultibodyPlant< T > &  ,
const systems::Context< T > &  ,
const Frame< T > &  ,
const Frame< T > &  ,
const Vector3< T > &  ,
distance_in,
const Vector3< T > &  ,
const Eigen::Ref< const VectorX< T >> &  ,
T *  distance_out 
)

This is the overloaded version of CalcDistanceDerivatives for the input q of double scalar type, it just copies distance_in to distance_out.

◆ CalcDistanceDerivatives() [4/4]

void drake::multibody::internal::CalcDistanceDerivatives ( const MultibodyPlant< double > &  ,
const systems::Context< double > &  ,
const Frame< double > &  ,
const Frame< double > &  ,
const Eigen::Vector3d &  ,
double  distance_in,
const Eigen::Vector3d &  ,
const Eigen::Ref< const VectorX< double >> &  ,
double distance_out 
)

◆ CheckPlantIsConnectedToSceneGraph()

void drake::multibody::internal::CheckPlantIsConnectedToSceneGraph ( const MultibodyPlant< T > &  plant,
const systems::Context< T > &  plant_context 
)

Check if the plant has registered its geometry with the SceneGraph.

◆ CreateSurfaceMesh()

std::unique_ptr<SurfaceMesh<double> > drake::multibody::internal::CreateSurfaceMesh ( )

◆ default_friction()

CoulombFriction<double> drake::multibody::internal::default_friction ( )

Default value of the Coulomb's law coefficients of friction for when they are not specified in the URDF/SDF file.

◆ DRAKE_DEFINE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN_T() [1/2]

drake::multibody::internal::DRAKE_DEFINE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN_T ( ArticulatedBodyInertiaCache  )

◆ DRAKE_DEFINE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN_T() [2/2]

drake::multibody::internal::DRAKE_DEFINE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN_T ( AccelerationKinematicsCache  )

◆ EXPLICITLY_INSTANTIATE_IMPLS() [1/3]

drake::multibody::internal::EXPLICITLY_INSTANTIATE_IMPLS ( double  )

◆ EXPLICITLY_INSTANTIATE_IMPLS() [2/3]

drake::multibody::internal::EXPLICITLY_INSTANTIATE_IMPLS ( AutoDiffXd  )

◆ EXPLICITLY_INSTANTIATE_IMPLS() [3/3]

drake::multibody::internal::EXPLICITLY_INSTANTIATE_IMPLS ( symbolic::Expression  )

◆ FindGeometry()

GeometryId drake::multibody::internal::FindGeometry ( const MultibodyPlant< double > &  plant,
const std::string  body_name 
)

◆ GetFullPath()

std::string GetFullPath ( const std::string &  file_name)

Obtains the full path of @file_name.

If file_name is already a full path (i.e., it starts with a "/"), the path is not modified. If file_name is a relative path, this method converts it into an absolute path based on the current working directory.

Exceptions
std::runtime_errorif the file does not exist or if file_name is empty.

◆ GetInternalTree()

const MultibodyTree<T>& drake::multibody::internal::GetInternalTree ( const MultibodyTreeSystem< T > &  system)

Access internal tree outside of MultibodyTreeSystem.

◆ GTEST_TEST() [1/2]

drake::multibody::internal::GTEST_TEST ( MultibodyGraph  ,
SerialChain   
)

◆ GTEST_TEST() [2/2]

drake::multibody::internal::GTEST_TEST ( MultibodyGraph  ,
Weldedsubgraphs   
)

◆ INSTANTIATE_TEST_CASE_P()

drake::multibody::internal::INSTANTIATE_TEST_CASE_P ( PoseInstantiations  ,
MultibodyPlantHydroelasticTractionTests  ,
::testing::ValuesIn(poses  
)

◆ MakeCoulombFrictionFromSdfCollisionOde()

CoulombFriction< double > MakeCoulombFrictionFromSdfCollisionOde ( const sdf::Collision &  sdf_collision)

Extracts the material properties from the given sdf::Visual object.

The sdf::Visual object represents a corresponding <visual> tag from an SDF file. The material properties are placed into a geometry::IllustrationProperties as follows:

Group Name Type Description
phong diffuse Vector4<double> The normalized rgba values for the diffuse color
phong ambient Vector4<double> The normalized rgba values for the ambient color
phong specular Vector4<double> The normalized rgba values for the specular color
phong emissive Vector4<double> The normalized rgba values for the emissive color

These are properties to be used in the Phong lighting model and are taken from the similarly named property tags (see below). If any of ambient, diffuse, specular, or emissive tags are missing, that property will be omitted from the property set and the impact of those missing properties will depend on the downstream consumers documented handling of missing parameters.

The material properties come from the child <material> tag. E.g.,

<visual>
<geometry>
...
</geometry>
<material>
<ambient>r_a g_a b_a a_a</ambient>
<diffuse>r_d g_d b_d a_d</diffuse>
<specular>r_s g_s b_s a_s</specular>
<emissive>r_e g_e b_e a_e</emissive>
</material>
</visual>

An instance of geometry::IllustrationProperties will always be returned. If there is no material tag, no material property tags, or no successfully parsed material property tags, the property set will be empty. */ geometry::IllustrationProperties MakeVisualPropertiesFromSdfVisual( const sdf::Visual& sdf_visual);

/** Given sdf_collision stemming from the parsing of a <collision> element in an SDF file, this method makes the pose X_LG of frame G for the geometry of that collision element in the frame L of the link it belongs to. */ math::RigidTransformd MakeGeometryPoseFromSdfCollision( const sdf::Collision& sdf_collision);

/** Parses friction coefficients from sdf_collision. This method looks for the definitions specific to ODE, as given by the SDF specification in <collision><surface><friction><ode>. Drake understands <mu> as the static coefficient of friction and <mu2> as the dynamic coefficient of friction. Consider the example below:

<collision>
<surface>
<friction>
<ode>
<mu>0.8</mu>
<mu2>0.3</mu2>
</ode>
</friction>
</surface>
</collision>

If a <surface> is not found, it returns the coefficients for a frictionless surface. If <surface> is found, all other nested elements are required and an exception is thrown if not present.

◆ MakeGeometryInstanceFromSdfVisual()

std::unique_ptr< geometry::GeometryInstance > MakeGeometryInstanceFromSdfVisual ( const sdf::Visual &  sdf_visual)

Given an sdf::Visual object representing a <visual> element from an SDF file, this method makes a new drake::geometry::GeometryInstance object from this specification.

This method returns nullptr when the given SDF specification corresponds to a geometry of type sdf::GeometryType::EMPTY (<empty> SDF tag.)

◆ MakeGeometryPoseFromSdfCollision()

RigidTransformd drake::multibody::internal::MakeGeometryPoseFromSdfCollision ( const sdf::Collision &  sdf_collision)

◆ MakeShapeFromSdfGeometry()

std::unique_ptr< geometry::Shape > MakeShapeFromSdfGeometry ( const sdf::Geometry &  sdf_geometry)

Given an sdf::Geometry object representing a <geometry> element from an SDF file, this method makes a new drake::geometry::Shape object from this specification.

For sdf_geometry.Type() == sdf::GeometryType::EMPTY, corresponding to the <empty> SDF tag, it returns nullptr.

◆ MakeVisualPropertiesFromSdfVisual()

IllustrationProperties drake::multibody::internal::MakeVisualPropertiesFromSdfVisual ( const sdf::Visual &  sdf_visual)

◆ NormalizeVector()

std::enable_if< is_eigen_vector_of<DerivedA, double>::value, Eigen::Matrix<double, DerivedA::RowsAtCompileTime, 1> >::type drake::multibody::internal::NormalizeVector ( const Eigen::MatrixBase< DerivedA > &  a)

Normalize an Eigen vector of doubles.

This function is used in the constructor of some kinematic constraints.

Exceptions
std::invalid_argumentif the vector is close to zero.

◆ OriginAttributesToTransform()

math::RigidTransformd OriginAttributesToTransform ( const tinyxml2::XMLElement *  node)

Parses "xyz" and "rpy" attributes from node and returns a RigidTransformd created from them.

If either the "xyz" or "rpy" attributes are omitted they will be initialized with zero values.

Exceptions
std::invalid_argumentif the "xyz" or "rpy" attributes are malformed.

◆ ParseCollision() [1/2]

geometry::GeometryInstance drake::multibody::internal::ParseCollision ( const std::string &  parent_element_name,
const PackageMap package_map,
const std::string &  root_dir,
const tinyxml2::XMLElement *  node,
CoulombFriction< double > *  friction 
)

Parses a "collision" element in node.

Parameters
[in]parent_element_nameThe name of the parent link element, used to construct default geometry names and for error reporting.
[out]frictionCoulomb friction for the associated geometry.

◆ ParseCollision() [2/2]

geometry::GeometryInstance drake::multibody::internal::ParseCollision ( const std::string &  parent_element_name,
const PackageMap package_map,
const std::string &  root_dir,
const XMLElement *  node,
CoulombFriction< double > *  friction 
)

◆ ParseMaterial() [1/2]

void drake::multibody::internal::ParseMaterial ( const tinyxml2::XMLElement *  node,
MaterialMap materials 
)

Parses a "material" element in node and adds the result to materials.

Exceptions
std::runtime_errorif the material is missing required attributes or if it was already defined with different properties.

◆ ParseMaterial() [2/2]

void drake::multibody::internal::ParseMaterial ( const XMLElement *  node,
MaterialMap materials 
)

◆ ParseScalarAttribute()

bool ParseScalarAttribute ( const tinyxml2::XMLElement *  node,
const char *  attribute_name,
double val 
)

Parses a scalar attribute of node named attribute_name into val.

Returns
false if the attribute is not present
Exceptions
std::invalid_argumentif the attribute doesn't contain a single numeric value.

◆ ParseStringAttribute()

bool ParseStringAttribute ( const tinyxml2::XMLElement *  node,
const char *  attribute_name,
std::string *  val 
)

Parses a string attribute of node named attribute_name into val.

If the attribute is not present, val will be cleared.

Returns
false if the attribute is not present

◆ ParseThreeVectorAttribute()

bool ParseThreeVectorAttribute ( const tinyxml2::XMLElement *  node,
const char *  attribute_name,
Eigen::Vector3d *  val 
)

Parses a three vector value from parameter node, which is an XML node.

Parses a three vector value from parameter node, which is an XML node.

The value is specified by an attribute within the XML whose name is apecified by parameter attribute_name. This method also supports a three vector specified by a single scalar value, which it automatically converts into a three vector by using the same scalar value for all three dimensions.

Parameters
[in]nodeA pointer to the XML element node that contains an attribute with a three vector or a scalar value.
[in]attribute_nameThe name of the attribute containing the three vector or scalar value.
[out]valThe three vector where the results should be stored.
Returns
false if the attribute is not present
Exceptions
std::invalid_argumentIf any problem is encountered parsing the three vector value.

◆ ParseVectorAttribute() [1/2]

bool ParseVectorAttribute ( const tinyxml2::XMLElement *  node,
const char *  attribute_name,
Eigen::Vector3d *  val 
)

Parses an attribute of node named attribute_name consisting of 3 scalar values into val.

Returns
false if the attribute is not present
Exceptions
std::invalid_argumentif the attribute doesn't contain three numeric values.

◆ ParseVectorAttribute() [2/2]

bool ParseVectorAttribute ( const tinyxml2::XMLElement *  node,
const char *  attribute_name,
Eigen::Vector4d *  val 
)

Parses an attribute of node named attribute_name consisting of 4 scalar values into val.

Returns
false if the attribute is not present
Exceptions
std::invalid_argumentif the attribute doesn't contain four numeric values.

◆ ParseVisual() [1/2]

geometry::GeometryInstance drake::multibody::internal::ParseVisual ( const std::string &  parent_element_name,
const PackageMap package_map,
const std::string &  root_dir,
const tinyxml2::XMLElement *  node,
MaterialMap materials 
)

Parses a "visual" element in node.

Parameters
[in]parent_element_nameThe name of the parent link element, used to construct default geometry names and for error reporting.
[in,out]materialsThe MaterialMap is used to look up materials which are referenced by name only in the visual element. New materials which are specified by both color and name will be added to the map and can be used by later visual elements. Material definitions may be repeated if the material properties are identical.

◆ ParseVisual() [2/2]

geometry::GeometryInstance drake::multibody::internal::ParseVisual ( const std::string &  parent_element_name,
const PackageMap package_map,
const std::string &  root_dir,
const XMLElement *  node,
MaterialMap materials 
)

◆ RefFromPtrOrThrow()

const MultibodyPlant<T>& drake::multibody::internal::RefFromPtrOrThrow ( const MultibodyPlant< T > *const  plant)

If plant is not nullptr, return a reference to the MultibodyPlant to which it points.

Exceptions
std::invalid_argumentif plant is nullptr.

◆ ResolveUri()

std::string ResolveUri ( const std::string &  uri,
const PackageMap package_map,
const std::string &  root_dir 
)

Resolves the full path of a URI.

If uri starts with "package:" or "model:", the ROS packages specified in package_map are searched. Otherwise, uri is appended to the end of root_dir (if it's not already an absolute path) and checked for existence. If the file does not exist or is not found, a warning is printed to std::cerr and an empty string is returned.

Parameters
[in]uriThe name of the resource to find.
[in]package_mapA map where the keys are ROS package names and the values are the paths to the packages. This is only used if filename starts with "package:"or "model:".
[in]root_dirThe root directory to look in. This is only used when filename does not start with "package:".
Returns
The file's full path or an empty string if the file is not found or does not exist.

◆ ResolveVisualUri()

sdf::Visual ResolveVisualUri ( const sdf::Visual &  original,
const multibody::PackageMap package_map,
const std::string &  root_dir 
)

Given an sdf::Visual object representing a <visual> element from an SDF file, this method makes a new Visual object which resolves the uri for the mesh element, if present.

If the mesh element is not present, the new object will be identical to the original. See parsers::ResolveFilename() for more detail on this operation.

Exceptions
std::runtime_errorif the <mesh> tag is present but missing <uri> or if the file referenced in <uri> can not be found.

◆ TEST_P() [1/8]

drake::multibody::internal::TEST_P ( MultibodyPlantHydroelasticTractionTests  ,
VanillaTraction   
)

◆ TEST_P() [2/8]

drake::multibody::internal::TEST_P ( MultibodyPlantHydroelasticTractionTests  ,
TractionWithFriction   
)

◆ TEST_P() [3/8]

drake::multibody::internal::TEST_P ( MultibodyPlantHydroelasticTractionTests  ,
TractionWithDissipation   
)

◆ TEST_P() [4/8]

drake::multibody::internal::TEST_P ( MultibodyPlantHydroelasticTractionTests  ,
VanillaTractionOverPatch   
)

◆ TEST_P() [5/8]

drake::multibody::internal::TEST_P ( MultibodyPlantHydroelasticTractionTests  ,
FrictionalTractionOverPatch   
)

◆ TEST_P() [6/8]

drake::multibody::internal::TEST_P ( MultibodyPlantHydroelasticTractionTests  ,
TractionOverPatchWithDissipation   
)

◆ TEST_P() [7/8]

drake::multibody::internal::TEST_P ( HydroelasticReportingTests  ,
LinearTraction   
)

◆ TEST_P() [8/8]

drake::multibody::internal::TEST_P ( HydroelasticReportingTests  ,
LinearSlipVelocity   
)

◆ ToRigidTransform()

math::RigidTransformd ToRigidTransform ( const ignition::math::Pose3d &  pose)

Helper function to express an ignition::math::Pose3d instance as a RigidTransform instance.

◆ ToVector3()

Eigen::Vector3d ToVector3 ( const ignition::math::Vector3d &  vector)

Helper function to express an ignition::math::Vector3d instance as a Vector3d instance.

◆ UpdateContextConfiguration() [1/4]

void UpdateContextConfiguration ( drake::systems::Context< double > *  context,
const MultibodyPlant< double > &  plant,
const Eigen::Ref< const VectorX< double >> &  q 
)

Check if the generalized positions in context are the same as q.

If they are not the same, then reset context's generalized positions to q. Otherwise, leave context unchanged. The intention is to avoid dirtying the computation cache, given it is ticket-based rather than hash-based.

◆ UpdateContextConfiguration() [2/4]

void drake::multibody::internal::UpdateContextConfiguration ( drake::systems::Context< double > *  context,
const MultibodyPlant< double > &  plant,
const Eigen::Ref< const AutoDiffVecXd > &  q 
)

◆ UpdateContextConfiguration() [3/4]

void drake::multibody::internal::UpdateContextConfiguration ( drake::systems::Context< double > *  context,
const MultibodyPlant< double > &  plant,
const Eigen::Ref< const VectorX< AutoDiffXd >> &  q 
)

◆ UpdateContextConfiguration() [4/4]

void UpdateContextConfiguration ( systems::Context< AutoDiffXd > *  context,
const MultibodyPlant< AutoDiffXd > &  plant,
const Eigen::Ref< const AutoDiffVecXd > &  q 
)

Variable Documentation

◆ kPrismaticType

const char kPrismaticType[] = "prismatic"

◆ kRevoluteType

const char kRevoluteType[] = "revolute"

◆ kWorldBodyName

const char kWorldBodyName[] = "DefaultWorldBodyName"

◆ poses

const RigidTransform<double> poses[]
Initial value:
= {
RigidTransform<double>(
math::RotationMatrix<double>::MakeYRotation(M_PI_4),
}
Eigen::Matrix< Scalar, 3, 1 > Vector3
A column vector of size 3, templated on scalar type.
Definition: eigen_types.h:40
static const RigidTransform< double > & Identity()
Returns the identity RigidTransform (corresponds to coincident frames).
Definition: rigid_transform.h:203