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). | |
| operator std::tuple< MultibodyPlant< T > *&, geometry::SceneGraph< T > *& > () | |
| For assignment to a std::tie of pointers. | |
Public Attributes | |
| MultibodyPlant< T > & | plant |
| geometry::SceneGraph< T > & | scene_graph |
Friends | |
| AddMultibodyPlantSceneGraphResult | internal::AddMultibodyPlantSceneGraphFromShared (systems::DiagramBuilder< T > *, std::shared_ptr< MultibodyPlant< T > >, std::shared_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 |