Drake
Drake C++ Documentation
RobotDiagramBuilder< T > Class Template Reference

Detailed Description

template<typename T>
class drake::planning::RobotDiagramBuilder< T >

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.

Template Parameters
TThe 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::Parserparser ()
 Gets the contained Parser (mutable). More...
 
template<typename T1 = T, typename std::enable_if_t< std::is_same_v< T1, double >> * = nullptr>
const multibody::Parserparser () 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
 
RobotDiagramBuilderoperator= (const RobotDiagramBuilder &)=delete
 
 RobotDiagramBuilder (RobotDiagramBuilder &&)=delete
 
RobotDiagramBuilderoperator= (RobotDiagramBuilder &&)=delete
 

Constructor & Destructor Documentation

◆ RobotDiagramBuilder() [1/3]

RobotDiagramBuilder ( const RobotDiagramBuilder< T > &  )
delete

◆ RobotDiagramBuilder() [2/3]

◆ RobotDiagramBuilder() [3/3]

RobotDiagramBuilder ( double  time_step = 0.001)
explicit

Constructs with the specified time step for the contained plant.

Parameters
time_stepGoverns 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()

Member Function Documentation

◆ Build()

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.

Exceptions
exceptionwhen IsDiagramBuilt() already.

◆ builder() [1/2]

systems::DiagramBuilder<T>& builder ( )

Gets the contained DiagramBuilder (mutable).

Do not call Build() on the return value; instead, call Build() on this.

Exceptions
exceptionwhen IsDiagramBuilt() already.

◆ builder() [2/2]

const systems::DiagramBuilder<T>& builder ( ) const

Gets the contained DiagramBuilder (readonly).

Exceptions
exceptionwhen IsDiagramBuilt() already.

◆ IsDiagramBuilt()

bool IsDiagramBuilt ( ) const

Checks if the diagram has already been built.

◆ operator=() [1/2]

RobotDiagramBuilder& operator= ( RobotDiagramBuilder< T > &&  )
delete

◆ operator=() [2/2]

RobotDiagramBuilder& operator= ( const RobotDiagramBuilder< T > &  )
delete

◆ parser() [1/2]

multibody::Parser& parser ( )

Gets the contained Parser (mutable).

Exceptions
exceptionwhen IsDiagramBuilt() already.

◆ parser() [2/2]

const multibody::Parser& parser ( ) const

Gets the contained Parser (readonly).

Exceptions
exceptionwhen IsDiagramBuilt() already.

◆ plant() [1/2]

Gets the contained plant (mutable).

Exceptions
exceptionwhen IsDiagramBuilt() already.

◆ plant() [2/2]

const multibody::MultibodyPlant<T>& plant ( ) const

Gets the contained plant (readonly).

Exceptions
exceptionwhen IsDiagramBuilt() already.

◆ scene_graph() [1/2]

geometry::SceneGraph<T>& scene_graph ( )

Gets the contained scene graph (mutable).

Exceptions
exceptionwhen IsDiagramBuilt() already.

◆ scene_graph() [2/2]

const geometry::SceneGraph<T>& scene_graph ( ) const

Gets the contained scene graph (readonly).

Exceptions
exceptionwhen IsDiagramBuilt() already.

The documentation for this class was generated from the following file: