Drake
BodyNodeTopology Struct Reference

Data structure to store the topological information associated with a tree node. More...

#include <drake/multibody/multibody_tree/multibody_tree_topology.h>

Collaboration diagram for BodyNodeTopology:
[legend]

Public Member Functions

 BodyNodeTopology ()
 Default construction to invalid configuration. More...
 
 BodyNodeTopology (BodyNodeIndex index_in, int level_in, BodyNodeIndex parent_node_in, BodyIndex body_in, BodyIndex parent_body_in, MobilizerIndex mobilizer_in)
 Constructor specifying the topological information for a tree node. More...
 
bool operator== (const BodyNodeTopology &other) const
 Returns true if all members of this topology are exactly equal to the members of other. More...
 
int get_num_children () const
 Returns the number of children to this node. More...
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 BodyNodeTopology (const BodyNodeTopology &)=default
 
BodyNodeTopologyoperator= (const BodyNodeTopology &)=default
 
 BodyNodeTopology (BodyNodeTopology &&)=default
 
BodyNodeTopologyoperator= (BodyNodeTopology &&)=default
 

Public Attributes

BodyNodeIndex index {}
 Unique index of this node in the MultibodyTree. More...
 
int level {-1}
 Depth level in the MultibodyTree, level = 0 for the world. More...
 
BodyNodeIndex parent_body_node
 The unique index to the parent BodyNode of this node. More...
 
BodyIndex body
 
BodyIndex parent_body
 
MobilizerIndex mobilizer
 
std::vector< BodyNodeIndexchild_nodes
 The list of child body nodes to this node. More...
 
int num_mobilizer_positions {0}
 Start and number of dofs for this node's mobilizer. More...
 
int mobilizer_positions_start {0}
 
int num_mobilizer_velocities {0}
 
int mobilizer_velocities_start {0}
 
int mobilizer_velocities_start_in_v {0}
 
int num_flexible_positions {0}
 Start and number of dofs for this node's body (flexible dofs). More...
 
int flexible_positions_start {0}
 
int num_flexible_velocities {0}
 
int flexible_velocities_start {0}
 

Detailed Description

Data structure to store the topological information associated with a tree node.

A tree node essentially consists of a body and its inboard mobilizer. A body node is in charge of the computations associated to that body and mobilizer, especially within a base-to-tip or tip-to-base recursion. As the topological entity associated with a tree node (and specifically a MultibodyTree node), this struct contains information regarding parent and child nodes, parent and child bodies, etc.

Constructor & Destructor Documentation

BodyNodeTopology ( const BodyNodeTopology )
default
BodyNodeTopology ( )
inline

Default construction to invalid configuration.

BodyNodeTopology ( BodyNodeIndex  index_in,
int  level_in,
BodyNodeIndex  parent_node_in,
BodyIndex  body_in,
BodyIndex  parent_body_in,
MobilizerIndex  mobilizer_in 
)
inline

Constructor specifying the topological information for a tree node.

A tree node is instantiated for each body in the multibody system and it contains, in addition to that particular body, the inboard mobilizer connecting the body to the rest of the tree inwards (i.e. towards the world or root of the tree) from the mobilizer.

Parameters
index_inThe unique index for this body node.
level_inThe level (depth or generation) in the tree structure.
parent_node_inThe parent node, in a tree structure sense, of this node.
body_inThe index to the body associated with this node.
parent_body_inThe parent body, in a tree structure sense, to body_in. In other words, parent_body_in is the body associated with node parent_node_in.
mobilizer_inThe index to the mobilizer associated with this node.

Member Function Documentation

int get_num_children ( ) const
inline

Returns the number of children to this node.

BodyNodeTopology& operator= ( BodyNodeTopology &&  )
default
BodyNodeTopology& operator= ( const BodyNodeTopology )
default
bool operator== ( const BodyNodeTopology other) const
inline

Returns true if all members of this topology are exactly equal to the members of other.

Here is the call graph for this function:

Member Data Documentation

BodyIndex body
std::vector<BodyNodeIndex> child_nodes

The list of child body nodes to this node.

int flexible_positions_start {0}
int flexible_velocities_start {0}
BodyNodeIndex index {}

Unique index of this node in the MultibodyTree.

int level {-1}

Depth level in the MultibodyTree, level = 0 for the world.

MobilizerIndex mobilizer
int mobilizer_positions_start {0}
int mobilizer_velocities_start {0}
int mobilizer_velocities_start_in_v {0}
int num_flexible_positions {0}

Start and number of dofs for this node's body (flexible dofs).

int num_flexible_velocities {0}
int num_mobilizer_positions {0}

Start and number of dofs for this node's mobilizer.

int num_mobilizer_velocities {0}
BodyIndex parent_body
BodyNodeIndex parent_body_node

The unique index to the parent BodyNode of this node.


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