Storage for a combined diagram builder, plant, and scene graph.
When T == double, a parser (and package map) is also available.
This class is a convenient syntactic sugar to help build a robot diagram, especially in C++ code where it simplifies object lifetime tracking and downcasting of the plant and scene graph references.
T | The scalar type, which must be one of the default scalars. |
#include <drake/planning/robot_diagram_builder.h>
Public Member Functions | |
RobotDiagramBuilder (double time_step=0.001) | |
Constructs with the specified time step for the contained plant. More... | |
~RobotDiagramBuilder () | |
systems::DiagramBuilder< T > & | builder () |
Gets the contained DiagramBuilder (mutable). More... | |
const systems::DiagramBuilder< T > & | builder () const |
Gets the contained DiagramBuilder (readonly). More... | |
template<typename T1 = T, typename std::enable_if_t< std::is_same_v< T1, double >> * = nullptr> | |
multibody::Parser & | parser () |
Gets the contained Parser (mutable). More... | |
template<typename T1 = T, typename std::enable_if_t< std::is_same_v< T1, double >> * = nullptr> | |
const multibody::Parser & | parser () const |
Gets the contained Parser (readonly). More... | |
multibody::MultibodyPlant< T > & | plant () |
Gets the contained plant (mutable). More... | |
const multibody::MultibodyPlant< T > & | plant () const |
Gets the contained plant (readonly). More... | |
geometry::SceneGraph< T > & | scene_graph () |
Gets the contained scene graph (mutable). More... | |
const geometry::SceneGraph< T > & | scene_graph () const |
Gets the contained scene graph (readonly). More... | |
bool | IsDiagramBuilt () const |
Checks if the diagram has already been built. More... | |
std::unique_ptr< RobotDiagram< T > > | Build () |
Builds the diagram and returns the diagram plus plant and scene graph in a RobotDiagram. More... | |
Does not allow copy, move, or assignment | |
RobotDiagramBuilder (const RobotDiagramBuilder &)=delete | |
RobotDiagramBuilder & | operator= (const RobotDiagramBuilder &)=delete |
RobotDiagramBuilder (RobotDiagramBuilder &&)=delete | |
RobotDiagramBuilder & | operator= (RobotDiagramBuilder &&)=delete |
|
delete |
|
delete |
|
explicit |
Constructs with the specified time step for the contained plant.
time_step | Governs whether the MultibodyPlant is modeled as a discrete system (time_step > 0 ) or as a continuous system (time_step = 0 ). See Simulation of Multibody Systems with Frictional Contact for further details. The default here matches the default value from multibody::MultibodyPlantConfig. |
~RobotDiagramBuilder | ( | ) |
std::unique_ptr<RobotDiagram<T> > Build | ( | ) |
Builds the diagram and returns the diagram plus plant and scene graph in a RobotDiagram.
The plant will be finalized during this function, unless it's already been finalized.
exception | when IsDiagramBuilt() already. |
systems::DiagramBuilder<T>& builder | ( | ) |
Gets the contained DiagramBuilder (mutable).
Do not call Build() on the return value; instead, call Build() on this.
exception | when IsDiagramBuilt() already. |
const systems::DiagramBuilder<T>& builder | ( | ) | const |
Gets the contained DiagramBuilder (readonly).
exception | when IsDiagramBuilt() already. |
bool IsDiagramBuilt | ( | ) | const |
Checks if the diagram has already been built.
|
delete |
|
delete |
multibody::Parser& parser | ( | ) |
Gets the contained Parser (mutable).
exception | when IsDiagramBuilt() already. |
const multibody::Parser& parser | ( | ) | const |
Gets the contained Parser (readonly).
exception | when IsDiagramBuilt() already. |
multibody::MultibodyPlant<T>& plant | ( | ) |
Gets the contained plant (mutable).
exception | when IsDiagramBuilt() already. |
const multibody::MultibodyPlant<T>& plant | ( | ) | const |
Gets the contained plant (readonly).
exception | when IsDiagramBuilt() already. |
geometry::SceneGraph<T>& scene_graph | ( | ) |
Gets the contained scene graph (mutable).
exception | when IsDiagramBuilt() already. |
const geometry::SceneGraph<T>& scene_graph | ( | ) | const |
Gets the contained scene graph (readonly).
exception | when IsDiagramBuilt() already. |