Temporary result from AddMultibodyPlantSceneGraph
.
This cannot be constructed outside of this method.
T | The scalar type, which must be one of the default scalars. |
#include <drake/multibody/plant/multibody_plant.h>
Public Member Functions | |
operator MultibodyPlant< T > & () | |
For assignment to a plant reference (ignoring the scene graph). More... | |
operator std::tuple< MultibodyPlant< T > *&, geometry::SceneGraph< T > *& > () | |
For assignment to a std::tie of pointers. More... | |
Public Attributes | |
MultibodyPlant< T > & | plant |
geometry::SceneGraph< T > & | scene_graph |
Friends | |
AddMultibodyPlantSceneGraphResult | AddMultibodyPlantSceneGraph (systems::DiagramBuilder< T > *, std::unique_ptr< MultibodyPlant< T >>, std::unique_ptr< geometry::SceneGraph< T >>) |
operator MultibodyPlant< T > & | ( | ) |
For assignment to a plant reference (ignoring the scene graph).
operator std::tuple< MultibodyPlant< T > *&, geometry::SceneGraph< T > *& > | ( | ) |
For assignment to a std::tie of pointers.
|
friend |
MultibodyPlant<T>& plant |
geometry::SceneGraph<T>& scene_graph |