mc_rbdyn::RobotModule Struct Reference

#include <mc_rbdyn/RobotModule.h>

Collaboration diagram for mc_rbdyn::RobotModule:

Classes

struct  FrameDescription
 
struct  Gripper
 

Public Types

using bounds_t = std::vector< std::map< std::string, std::vector< double > >>
 
using accelerationBounds_t = std::vector< std::map< std::string, std::vector< double > >>
 
using jerkBounds_t = std::vector< std::map< std::string, std::vector< double > >>
 
using torqueDerivativeBounds_t = std::vector< std::map< std::string, std::vector< double > >>
 

Public Member Functions

 RobotModule (const std::string &path, const std::string &name)
 
 RobotModule (const std::string &path, const std::string &name, const std::string &urdf_path)
 
 RobotModule (const std::string &name, const rbd::parsers::ParserResult &res)
 
void init (const rbd::parsers::ParserResult &res)
 
const std::vector< std::map< std::string, std::vector< double > > > & bounds () const
 
const std::vector< std::map< std::string, std::vector< double > > > & accelerationBounds () const
 
const std::vector< std::map< std::string, std::vector< double > > > & jerkBounds () const
 
const std::vector< std::map< std::string, std::vector< double > > > & torqueDerivativeBounds () const
 
const std::map< std::string, std::vector< double > > & stance () const
 
const std::map< std::string, std::pair< std::string, std::string > > & convexHull () const
 
const std::map< std::string, std::pair< std::string, S_ObjectPtr > > & collisionObjects () const
 
const std::map< std::string, std::pair< std::string, std::string > > & stpbvHull () const
 
const std::map< std::string, sva::PTransformd > & collisionTransforms () const
 
const std::vector< Flexibility > & flexibility () const
 
const std::vector< ForceSensor > & forceSensors () const
 
const BodySensorVectorbodySensors () const
 
const std::vector< JointSensor > & jointSensors () const
 
const Springssprings () const
 
const std::vector< mc_rbdyn::Collision > & minimalSelfCollisions () const
 
const std::vector< mc_rbdyn::Collision > & commonSelfCollisions () const
 
const std::vector< Gripper > & grippers () const
 
const Gripper::SafetygripperSafety () const
 
const std::vector< std::string > & ref_joint_order () const
 
const std::array< double, 7 > & default_attitude () const
 
const mc_rbdyn::lipm_stabilizer::StabilizerConfigurationdefaultLIPMStabilizerConfiguration () const
 
void boundsFromURDF (const rbd::parsers::Limits &limits)
 
void expand_stance ()
 
void make_default_ref_joint_order ()
 
const CompoundJointConstraintDescriptionVectorcompoundJoints () const
 
const std::vector< std::string > & parameters () const
 
const std::vector< std::string > & canonicalParameters () const
 
std::string real_urdf () const
 
const DevicePtrVectordevices () const
 
const std::vector< FrameDescription > & frames () const noexcept
 

Public Attributes

RobotConverterConfig controlToCanonicalConfig
 
std::function< void(const mc_rbdyn::Robot &control, mc_rbdyn::Robot &canonical)> controlToCanonicalPostProcess
 
std::string path
 
std::string name
 
std::string urdf_path
 
std::string rsdf_dir
 
std::string calib_dir
 
rbd::MultiBody mb
 
rbd::MultiBodyConfig mbc
 
rbd::MultiBodyGraph mbg
 
bounds_t _bounds
 
accelerationBounds_t _accelerationBounds
 
jerkBounds_t _jerkBounds
 
torqueDerivativeBounds_t _torqueDerivativeBounds
 
std::map< std::string, std::vector< double > > _stance
 
std::map< std::string, std::pair< std::string, std::string > > _convexHull
 
std::map< std::string, std::pair< std::string, S_ObjectPtr > > _collisionObjects
 
std::map< std::string, std::pair< std::string, std::string > > _stpbvHull
 
VisualMap _visual
 
VisualMap _collision
 
std::map< std::string, sva::PTransformd > _collisionTransforms
 
std::vector< Flexibility_flexibility
 
std::vector< ForceSensor_forceSensors
 
BodySensorVector _bodySensors
 
std::vector< JointSensor_jointSensors
 
Springs _springs
 
std::vector< mc_rbdyn::Collision_minimalSelfCollisions
 
std::vector< mc_rbdyn::Collision_commonSelfCollisions
 
std::vector< Gripper_grippers
 
Gripper::Safety _gripperSafety
 
std::vector< std::string > _ref_joint_order
 
std::array< double, 7 > _default_attitude = {{1., 0., 0., 0., 0., 0., 0.}}
 
CompoundJointConstraintDescriptionVector _compoundJoints
 
std::vector< std::string > _parameters
 
std::vector< std::string > _canonicalParameters
 
mc_rbdyn::lipm_stabilizer::StabilizerConfiguration _lipmStabilizerConfig
 
std::string _real_urdf
 
DevicePtrVector _devices
 
std::vector< FrameDescription_frames
 

Member Typedef Documentation

◆ accelerationBounds_t

using mc_rbdyn::RobotModule::accelerationBounds_t = std::vector<std::map<std::string, std::vector<double> >>

Holds information regarding the additional acceleration bounds (specified in addition to urdf limits)

The vector should have 2 entries:

  • lower/upper acceleration bounds

Each entry is a map joint name <-> bound

◆ bounds_t

using mc_rbdyn::RobotModule::bounds_t = std::vector<std::map<std::string, std::vector<double> >>

Holds information regarding the bounds (specified in the urdf)

The vector should have 6 entries:

  • lower/upper position bounds
  • lower/upper velocity bounds
  • lower/upper torque bounds

Each entry is a map joint name <-> bound

◆ jerkBounds_t

using mc_rbdyn::RobotModule::jerkBounds_t = std::vector<std::map<std::string, std::vector<double> >>

Holds information regarding the additional jerk bounds (specified in addition to urdf limits)

The vector should have 2 entries:

  • lower/upper jerk bounds

Each entry is a map joint name <-> bound

◆ torqueDerivativeBounds_t

using mc_rbdyn::RobotModule::torqueDerivativeBounds_t = std::vector<std::map<std::string, std::vector<double> >>

Holds information regarding the additional torque-derivative bounds (specified in addition to urdf limits)

The vector should have 2 entries:

  • lower/upper torque-derivative bounds

Each entry is a map joint name <-> bound

Constructor & Destructor Documentation

◆ RobotModule() [1/3]

mc_rbdyn::RobotModule::RobotModule ( const std::string &  path,
const std::string &  name 
)
inline

Construct from a provided path and name

As a result:

  • name is defined as name
  • path is defined as path
  • urdf_path is path + /urdf/ + name + .urdf
  • rsdf_dir is path + /rsdf/ + name
  • calib_dir is path + /calib/ + name:q

No further action is taken. This constructor is useful to inherit from

Parameters
pathPath to the robot description
nameName of the robot

◆ RobotModule() [2/3]

mc_rbdyn::RobotModule::RobotModule ( const std::string &  path,
const std::string &  name,
const std::string &  urdf_path 
)
inline

Construct from a provided path, name and urdf_path

See also
RobotModule(const std::string &, const std::string &)

The different is that urdf_path is defined to urdf_path

Parameters
pathPath to the robot description
nameName of the robot
urdf_pathPath to the robot URDF

◆ RobotModule() [3/3]

mc_rbdyn::RobotModule::RobotModule ( const std::string &  name,
const rbd::parsers::ParserResult &  res 
)

Construct from a parser result

Member Function Documentation

◆ accelerationBounds()

const std::vector<std::map<std::string, std::vector<double> > >& mc_rbdyn::RobotModule::accelerationBounds ( ) const
inline

Returns the robot's acceleration bounds

The vector should hold 2 string -> vector<double> map

Each map's keys are joint names and values are joint limits.

They should be provided in the following order:

  • acceleration limits (lower/upper)

◆ bodySensors()

const BodySensorVector& mc_rbdyn::RobotModule::bodySensors ( ) const
inline

Return the body sensors of the robot

See also
mc_rbdyn::BodySensor for details on the expected data

◆ bounds()

const std::vector<std::map<std::string, std::vector<double> > >& mc_rbdyn::RobotModule::bounds ( ) const
inline

Returns the robot's bounds obtained from parsing a urdf

The vector should hold 6 string -> vector<double> map

Each map's keys are joint names and values are joint limits.

They should be provided in the following order:

  • joint limits (lower/upper)
  • velocity limits (lower/upper)
  • torque limits (lower/upper)

◆ boundsFromURDF()

void mc_rbdyn::RobotModule::boundsFromURDF ( const rbd::parsers::Limits &  limits)

Generate correct bounds from URDF bounds

URDF outputs bounds in {lower, upper, velocity, torque} forms

This function set _bounds to: {lower, upper, -velocity, velocity, -torque, torque}

◆ canonicalParameters()

const std::vector<std::string>& mc_rbdyn::RobotModule::canonicalParameters ( ) const
inline

Returns the list of parameters to get a RobotModule that is a canonical representation of this module

◆ collisionObjects()

const std::map<std::string, std::pair<std::string, S_ObjectPtr> >& mc_rbdyn::RobotModule::collisionObjects ( ) const
inline

Returns a map describing collision objects for the robot

A key defines a valid collision name, there should be no collision with the names convexHull()

A value is composed of two strings:

  1. the name of the body the object is attached to
  2. the collision object

The transformation between the convex and the body it's attached to are provided in a separate map see collisionTransforms()

◆ collisionTransforms()

const std::map<std::string, sva::PTransformd>& mc_rbdyn::RobotModule::collisionTransforms ( ) const
inline

Returns a map describing the transformation between convex/STPBV hulls and their parent bodies

A key defines the collision name. The value is the transformation between this collision object and its parent body

◆ commonSelfCollisions()

const std::vector<mc_rbdyn::Collision>& mc_rbdyn::RobotModule::commonSelfCollisions ( ) const
inline

Return a common self-collision set

This set of collision describe self-collisions that you want to enable for general applications. Generally this is a super-set of minimalSelfCollisions

See also
mc_rbdyn::Collision for details on the expected data

◆ compoundJoints()

const CompoundJointConstraintDescriptionVector& mc_rbdyn::RobotModule::compoundJoints ( ) const
inline

Returns a list of compound joint constraint description

See also
mc_rbdyn::CompoundJointConstraintDescription for details on the expected data

◆ convexHull()

const std::map<std::string, std::pair<std::string, std::string> >& mc_rbdyn::RobotModule::convexHull ( ) const
inline

Returns a map describing the convex hulls for the robot

A key defines a valid collision name, there should be no collision with the names in collisionObjects()

A value is composed of two strings:

  1. the name of the body the convex is attached to
  2. the path to the file containing the convex description

The transformation between the convex and the body it's attached to are provided in a separate map see collisionTransforms()

◆ default_attitude()

const std::array<double, 7>& mc_rbdyn::RobotModule::default_attitude ( ) const
inline

Return the default attitude of the floating base

This attitute is associated to the stance() configuration

◆ defaultLIPMStabilizerConfiguration()

const mc_rbdyn::lipm_stabilizer::StabilizerConfiguration& mc_rbdyn::RobotModule::defaultLIPMStabilizerConfiguration ( ) const
inline

Return default configuration for the lipm stabilizer

◆ devices()

const DevicePtrVector& mc_rbdyn::RobotModule::devices ( ) const
inline

Returns a list of non standard sensors supported by this module

◆ expand_stance()

void mc_rbdyn::RobotModule::expand_stance ( )

Add missing elements to the current module stance

If joints are present in the MultiBody but absent from the default stance, this will add a default value for this joint to the stance (the joint's zero configuration).

◆ flexibility()

const std::vector<Flexibility>& mc_rbdyn::RobotModule::flexibility ( ) const
inline

Return the flexibilities of the robot

See also
mc_rbdyn::Flexibility for details on the expected data

◆ forceSensors()

const std::vector<ForceSensor>& mc_rbdyn::RobotModule::forceSensors ( ) const
inline

Return the force sensors of the robot

See also
mc_rbdyn::ForceSensor for details on the expected data

◆ frames()

const std::vector<FrameDescription>& mc_rbdyn::RobotModule::frames ( ) const
inlinenoexcept

Returns a list of robot frames supported by this module

◆ grippers()

const std::vector<Gripper>& mc_rbdyn::RobotModule::grippers ( ) const
inline

Return the grippers in the robot

See also
mc_rbdyn::Gripper for details on the expected data

◆ gripperSafety()

const Gripper::Safety& mc_rbdyn::RobotModule::gripperSafety ( ) const
inline

Returns default gripper safety parameters if one is not provided by a gripper.

This can also be used to provide identical settings for every grippers in a robot

See also
mc_rbdyn::Gripper::Safety for details on the safety parameters

◆ init()

void mc_rbdyn::RobotModule::init ( const rbd::parsers::ParserResult &  res)

Initialize the module from a parser result

  • Initialize mb, mbc and mbg
  • Initial limits
  • Initialize _collisionTransforms
  • Initialize _visual
  • Create a default joint order
  • Create a default stance

◆ jerkBounds()

const std::vector<std::map<std::string, std::vector<double> > >& mc_rbdyn::RobotModule::jerkBounds ( ) const
inline

Returns the robot's jerk bounds

The vector should hold 2 string -> vector<double> map

Each map's keys are joint names and values are joint limits.

They should be provided in the following order:

  • jerk limits (lower/upper)

◆ jointSensors()

const std::vector<JointSensor>& mc_rbdyn::RobotModule::jointSensors ( ) const
inline

Return the joint sensors of the robot

See also
mc_rbdyn::JointSensor for details on the expected data

◆ make_default_ref_joint_order()

void mc_rbdyn::RobotModule::make_default_ref_joint_order ( )

Make a valid ref_joint_order

If ref_joint_order() is empty, this will generate a list of actuated joints in the order they appear in the kinematic tree

◆ minimalSelfCollisions()

const std::vector<mc_rbdyn::Collision>& mc_rbdyn::RobotModule::minimalSelfCollisions ( ) const
inline

Return a minimal self-collision set

This set of collision describe self-collisions that you always want to enable regardless of the application

See also
mc_rbdyn::Collision for details on the expected data

◆ parameters()

const std::vector<std::string>& mc_rbdyn::RobotModule::parameters ( ) const
inline

Returns the list of parameters passed to mc_rbdyn::RobotLoader::get_robot_module to obtain this module

◆ real_urdf()

std::string mc_rbdyn::RobotModule::real_urdf ( ) const
inline

Returns the path to a "real" URDF file

This will be used to show a visually distinct robot for displaying the control and observed models simulatenously.

This defaults to urdf_path

◆ ref_joint_order()

const std::vector<std::string>& mc_rbdyn::RobotModule::ref_joint_order ( ) const
inline

Return the reference (native controller) joint order of the robot

If it is empty, make_default_ref_joint_order() will be used to generate one

◆ springs()

const Springs& mc_rbdyn::RobotModule::springs ( ) const
inline

Return the springs of a robot

See also
mc_rbdyn::Spring for details on the expected data

◆ stance()

const std::map<std::string, std::vector<double> >& mc_rbdyn::RobotModule::stance ( ) const
inline

Returns a default configuration for the robot

Keys are joint names and values are joint configurations.

It should be ok to include joints that are not in the robot (e.g. generate the same default stance for variants of a robot. However, each actuated joint in the robot should have a valid entry, see expand_stance

For the floating base see default_attitude

◆ stpbvHull()

const std::map<std::string, std::pair<std::string, std::string> >& mc_rbdyn::RobotModule::stpbvHull ( ) const
inline

Returns a map describing the STPBV hulls for the robot

A key defines a valid collision name, a value is composed of two strings:

  1. the name of the body the convex is attached to
  2. the path to the file containing the STPBV description

The transformation between the STPBV and the body it's attached to are provided in a separate map see collisionTransforms()

◆ torqueDerivativeBounds()

const std::vector<std::map<std::string, std::vector<double> > >& mc_rbdyn::RobotModule::torqueDerivativeBounds ( ) const
inline

Returns the robot's torque-derivative bounds

The vector should hold 2 string -> vector<double> map

Each map's keys are joint names and values are joint limits.

They should be provided in the following order:

  • torque-derivative limits (lower/upper)

Member Data Documentation

◆ _accelerationBounds

accelerationBounds_t mc_rbdyn::RobotModule::_accelerationBounds

◆ _bodySensors

BodySensorVector mc_rbdyn::RobotModule::_bodySensors
See also
bodySensors()

◆ _bounds

bounds_t mc_rbdyn::RobotModule::_bounds
See also
bounds()

◆ _canonicalParameters

std::vector<std::string> mc_rbdyn::RobotModule::_canonicalParameters

◆ _collision

VisualMap mc_rbdyn::RobotModule::_collision

Holds collision representation of bodies in the robot

◆ _collisionObjects

std::map<std::string, std::pair<std::string, S_ObjectPtr> > mc_rbdyn::RobotModule::_collisionObjects

◆ _collisionTransforms

std::map<std::string, sva::PTransformd> mc_rbdyn::RobotModule::_collisionTransforms

◆ _commonSelfCollisions

std::vector<mc_rbdyn::Collision> mc_rbdyn::RobotModule::_commonSelfCollisions

◆ _compoundJoints

CompoundJointConstraintDescriptionVector mc_rbdyn::RobotModule::_compoundJoints

◆ _convexHull

std::map<std::string, std::pair<std::string, std::string> > mc_rbdyn::RobotModule::_convexHull
See also
convexHull()

◆ _default_attitude

std::array<double, 7> mc_rbdyn::RobotModule::_default_attitude = {{1., 0., 0., 0., 0., 0., 0.}}

◆ _devices

DevicePtrVector mc_rbdyn::RobotModule::_devices
See also
sensors()

◆ _flexibility

std::vector<Flexibility> mc_rbdyn::RobotModule::_flexibility
See also
flexibility()

◆ _forceSensors

std::vector<ForceSensor> mc_rbdyn::RobotModule::_forceSensors
See also
forceSensors()

◆ _frames

std::vector<FrameDescription> mc_rbdyn::RobotModule::_frames
See also
frames()

◆ _grippers

std::vector<Gripper> mc_rbdyn::RobotModule::_grippers
See also
grippers()

◆ _gripperSafety

Gripper::Safety mc_rbdyn::RobotModule::_gripperSafety
See also
gripperSafety()

◆ _jerkBounds

jerkBounds_t mc_rbdyn::RobotModule::_jerkBounds
See also
jerkBounds()

◆ _jointSensors

std::vector<JointSensor> mc_rbdyn::RobotModule::_jointSensors
See also
jointSensors()

◆ _lipmStabilizerConfig

◆ _minimalSelfCollisions

std::vector<mc_rbdyn::Collision> mc_rbdyn::RobotModule::_minimalSelfCollisions

◆ _parameters

std::vector<std::string> mc_rbdyn::RobotModule::_parameters
See also
parameters()

◆ _real_urdf

std::string mc_rbdyn::RobotModule::_real_urdf
See also
real_urdf()

◆ _ref_joint_order

std::vector<std::string> mc_rbdyn::RobotModule::_ref_joint_order

◆ _springs

Springs mc_rbdyn::RobotModule::_springs
See also
springs()

◆ _stance

std::map<std::string, std::vector<double> > mc_rbdyn::RobotModule::_stance
See also
stance()

◆ _stpbvHull

std::map<std::string, std::pair<std::string, std::string> > mc_rbdyn::RobotModule::_stpbvHull
See also
stpbvHull()

◆ _torqueDerivativeBounds

torqueDerivativeBounds_t mc_rbdyn::RobotModule::_torqueDerivativeBounds

◆ _visual

VisualMap mc_rbdyn::RobotModule::_visual

Holds visual representation of bodies in the robot

◆ calib_dir

std::string mc_rbdyn::RobotModule::calib_dir

Path to the robot's calib folder

◆ controlToCanonicalConfig

RobotConverterConfig mc_rbdyn::RobotModule::controlToCanonicalConfig

Returns the configuration for the control to canonical conversion

The default configuration:

  • copies the common configuration values from the control model to the canonical model
  • copies the initial encoders value into the canonical model for other joints
  • enforce mimic relations
  • copy the world pose of the control model to the canonical model

◆ controlToCanonicalPostProcess

std::function<void(const mc_rbdyn::Robot & control, mc_rbdyn::Robot & canonical)> mc_rbdyn::RobotModule::controlToCanonicalPostProcess
Initial value:
=
[](const mc_rbdyn::Robot &, mc_rbdyn::Robot &) {}

◆ mb

rbd::MultiBody mc_rbdyn::RobotModule::mb

RBDyn representation of this robot

◆ mbc

rbd::MultiBodyConfig mc_rbdyn::RobotModule::mbc

RBDyn configuration of this robot

◆ mbg

rbd::MultiBodyGraph mc_rbdyn::RobotModule::mbg

RBDyn graph representation of this robot

◆ name

std::string mc_rbdyn::RobotModule::name

(default) Name of the robot

◆ path

std::string mc_rbdyn::RobotModule::path

Path to the robot's description package

◆ rsdf_dir

std::string mc_rbdyn::RobotModule::rsdf_dir

Path to the robot's RSDF folder

◆ urdf_path

std::string mc_rbdyn::RobotModule::urdf_path

Path to the robot's URDF file


The documentation for this struct was generated from the following file:
mc_rbdyn::Robot
Definition: Robot.h:62