Drake
Drake C++ Documentation
Loading...
Searching...
No Matches
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.
 ~RobotDiagramBuilder ()
systems::DiagramBuilder< T > & builder ()
 Gets the contained DiagramBuilder (mutable).
const systems::DiagramBuilder< T > & builder () const
 Gets the contained DiagramBuilder (readonly).
template<typename T1 = T, typename std::enable_if_t< std::is_same_v< T1, double > > * = nullptr>
multibody::Parserparser ()
 Gets the contained Parser (mutable).
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).
multibody::MultibodyPlant< T > & plant ()
 Gets the contained plant (mutable).
const multibody::MultibodyPlant< T > & plant () const
 Gets the contained plant (readonly).
geometry::SceneGraph< T > & scene_graph ()
 Gets the contained scene graph (mutable).
const geometry::SceneGraph< T > & scene_graph () const
 Gets the contained scene graph (readonly).
bool IsDiagramBuilt () const
 Checks if the diagram has already been built.
std::unique_ptr< RobotDiagram< T > > Build ()
 Builds the diagram and returns the diagram plus plant and scene graph in a RobotDiagram.
internal::BuildResultForPython< T > BuildForPython ()
 (Internal use only) Performs all the actions of Build().
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]

template<typename T>
RobotDiagramBuilder ( const RobotDiagramBuilder< T > & )
delete

◆ RobotDiagramBuilder() [2/3]

template<typename T>
RobotDiagramBuilder ( RobotDiagramBuilder< T > && )
delete

◆ RobotDiagramBuilder() [3/3]

template<typename T>
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()

template<typename T>
~RobotDiagramBuilder ( )

Member Function Documentation

◆ Build()

template<typename T>
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]

template<typename T>
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]

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

Gets the contained DiagramBuilder (readonly).

Exceptions
exceptionwhen IsDiagramBuilt() already.

◆ BuildForPython()

template<typename T>
internal::BuildResultForPython< T > BuildForPython ( )

(Internal use only) Performs all the actions of Build().

In addition, transfers ownership of both the built diagram and the internal builder on return.

Exceptions
exceptionwhen IsDiagramBuilt() already.

◆ IsDiagramBuilt()

template<typename T>
bool IsDiagramBuilt ( ) const

Checks if the diagram has already been built.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ parser() [1/2]

template<typename T>
template<typename T1 = T, typename std::enable_if_t< std::is_same_v< T1, double > > * = nullptr>
multibody::Parser & parser ( )

Gets the contained Parser (mutable).

Exceptions
exceptionwhen IsDiagramBuilt() already.

◆ parser() [2/2]

template<typename T>
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).

Exceptions
exceptionwhen IsDiagramBuilt() already.

◆ plant() [1/2]

template<typename T>
multibody::MultibodyPlant< T > & plant ( )

Gets the contained plant (mutable).

Exceptions
exceptionwhen IsDiagramBuilt() already.

◆ plant() [2/2]

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

Gets the contained plant (readonly).

Exceptions
exceptionwhen IsDiagramBuilt() already.

◆ scene_graph() [1/2]

template<typename T>
geometry::SceneGraph< T > & scene_graph ( )

Gets the contained scene graph (mutable).

Exceptions
exceptionwhen IsDiagramBuilt() already.

◆ scene_graph() [2/2]

template<typename T>
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: