mc_control::MCController Class Reference

MCController is the base class to implement all controllers. It assumes that at least two robots are provided. The first is considered as the "main" robot. Some common constraints and a posture task are defined (but not added to the solver) for this robot. More...

#include <mc_control/MCController.h>

Inheritance diagram for mc_control::MCController:
Collaboration diagram for mc_control::MCController:

Classes

struct  DeprecatedAnchorFrame
 

Public Types

using Backend = mc_solver::QPSolver::Backend
 

Public Member Functions

virtual ~MCController ()
 
virtual bool run ()
 
virtual void createObserverPipelines (const mc_rtc::Configuration &config)
 
virtual bool runObserverPipelines ()
 
virtual bool resetObserverPipelines ()
 Reset the observers. More...
 
bool hasObserverPipeline (const std::string &name) const
 
bool hasObserverPipeline () const
 
const std::vector< mc_observers::ObserverPipeline > & observerPipelines () const
 
std::vector< mc_observers::ObserverPipeline > & observerPipelines ()
 
const mc_observers::ObserverPipelineobserverPipeline (const std::string &name) const
 
mc_observers::ObserverPipelineobserverPipeline (const std::string &name)
 
const mc_observers::ObserverPipelineobserverPipeline () const
 
mc_observers::ObserverPipelineobserverPipeline ()
 
bool run (mc_solver::FeedbackType fType)
 
virtual void stop ()
 
virtual void reset (const ControllerResetData &reset_data)
 
void addCollisions (const std::string &r1, const std::string &r2, const std::vector< mc_rbdyn::Collision > &collisions)
 
bool hasCollision (const std::string &r1, const std::string &r2, const mc_rbdyn::Collision &col) const noexcept
 
bool hasCollision (const std::string &r1, const std::string &r2, const std::string &c1, const std::string &c2) const noexcept
 
void removeCollisions (const std::string &r1, const std::string &r2, const std::vector< mc_rbdyn::Collision > &collisions)
 
void removeCollisions (const std::string &r1, const std::string &r2)
 
void addContact (const Contact &c)
 
void removeContact (const Contact &c)
 
void clearContacts ()
 
const ContactSetcontacts () const
 
bool hasContact (const Contact &c) const
 
bool hasRobot (const std::string &robot) const noexcept
 
const mc_rbdyn::Robotsrobots () const noexcept
 
mc_rbdyn::Robotsrobots () noexcept
 
const mc_solver::QPSolversolver () const noexcept
 
mc_solver::QPSolversolver () noexcept
 
mc_rtc::Loggerlogger () noexcept
 
std::shared_ptr< mc_rtc::gui::StateBuildergui () const noexcept
 
mc_rtc::DataStoredatastore () noexcept
 
const mc_rtc::DataStoredatastore () const noexcept
 
virtual void supported_robots (std::vector< std::string > &out) const
 
mc_rbdyn::RobotloadRobot (mc_rbdyn::RobotModulePtr rm, const std::string &name)
 
void removeRobot (const std::string &name)
 
mc_rtc::Configurationconfig ()
 
const mc_rtc::Configurationconfig () const
 
Grippergripper (const std::string &robot, const std::string &gripper)
 
template<typename T = void>
void anchorFrame (const sva::PTransformd &)
 
template<typename T = void>
void anchorFrameReal (const sva::PTransformd &)
 
template<typename T = void>
const sva::PTransformd & anchorFrame () const
 
template<typename T = void>
const sva::PTransformd & anchorFrameReal () const
 
mc_rtc::Configuration robot_config (const std::string &robot_name) const
 
mc_rtc::Configuration robot_config (const mc_rbdyn::Robot &robot) const
 
Accessors to the control robots
const mc_rbdyn::Robotrobot () const noexcept
 
mc_rbdyn::Robotrobot () noexcept
 
const mc_rbdyn::Robotrobot (const std::string &name) const
 
mc_rbdyn::Robotrobot (const std::string &name)
 
const mc_rbdyn::Robotenv () const noexcept
 
mc_rbdyn::Robotenv () noexcept
 
Accessors to the real robots
const mc_rbdyn::RobotsrealRobots () const noexcept
 
mc_rbdyn::RobotsrealRobots () noexcept
 
const mc_rbdyn::RobotrealRobot () const noexcept
 
mc_rbdyn::RobotrealRobot () noexcept
 
const mc_rbdyn::RobotrealRobot (const std::string &name) const
 
mc_rbdyn::RobotrealRobot (const std::string &name)
 
Accessors to the output robots

Output robots should be used by interface and plugin that need to get a view of the complete system being controlled.

const mc_rbdyn::RobotsoutputRobots () const noexcept
 
mc_rbdyn::RobotsoutputRobots () noexcept
 
const mc_rbdyn::RobotoutputRobot () const noexcept
 
mc_rbdyn::RobotoutputRobot () noexcept
 
const mc_rbdyn::RobotoutputRobot (const std::string &name) const
 
mc_rbdyn::RobotoutputRobot (const std::string &name)
 
Accessors to the output real robots

These robots are used by the various interfaces to send control commands to the robots, and by the ROS plugin to publish a complete visualization of the robots (including non-controlled joints)

const mc_rbdyn::RobotsoutputRealRobots () const noexcept
 
mc_rbdyn::RobotsoutputRealRobots () noexcept
 
const mc_rbdyn::RobotoutputRealRobot () const noexcept
 
mc_rbdyn::RobotoutputRealRobot () noexcept
 
const mc_rbdyn::RobotoutputRealRobot (const std::string &name) const
 
mc_rbdyn::RobotoutputRealRobot (const std::string &name)
 

Static Public Member Functions

static void set_loading_location (std::string_view location)
 
static void set_name (std::string_view name)
 

Public Attributes

const double timeStep
 
mc_rtc::unique_ptr< mc_solver::ContactConstraintcontactConstraint
 
mc_rtc::unique_ptr< mc_solver::DynamicsConstraintdynamicsConstraint
 
mc_rtc::unique_ptr< mc_solver::KinematicsConstraintkinematicsConstraint
 
mc_rtc::unique_ptr< mc_solver::CollisionsConstraintselfCollisionConstraint
 
mc_rtc::unique_ptr< mc_solver::CompoundJointConstraintcompoundJointConstraint
 
std::shared_ptr< mc_tasks::PostureTaskpostureTask
 
const std::string name_
 
const std::string loading_location_
 

Protected Types

using ContactTableDataT = std::tuple< std::string, std::string, std::string, std::string, std::string, double >
 
using duration_ms = std::chrono::duration< double, std::milli >
 

Protected Member Functions

 MCController (std::shared_ptr< mc_rbdyn::RobotModule > robot, double dt, ControllerParameters params={})
 
 MCController (std::shared_ptr< mc_rbdyn::RobotModule > robot, double dt, const mc_rtc::Configuration &config, ControllerParameters params={})
 
 MCController (const std::vector< std::shared_ptr< mc_rbdyn::RobotModule >> &robot_modules, double dt, ControllerParameters params={})
 
 MCController (const std::vector< std::shared_ptr< mc_rbdyn::RobotModule >> &robot_modules, double dt, const mc_rtc::Configuration &config, ControllerParameters params={})
 
mc_rbdyn::RobotloadRobot (mc_rbdyn::RobotModulePtr rm, const std::string &name, mc_rbdyn::Robots &robots, const mc_rbdyn::LoadRobotParameters &params)
 
void addRobotToLog (const mc_rbdyn::Robot &robot)
 
void addRobotToGUI (const mc_rbdyn::Robot &robot)
 
void updateContacts ()
 

Protected Attributes

std::shared_ptr< mc_solver::QPSolverqpsolver
 
mc_rbdyn::RobotsPtr outputRobots_
 
mc_rbdyn::RobotsPtr outputRealRobots_
 
std::vector< mc_rbdyn::RobotConverterconverters_
 
std::vector< mc_observers::ObserverPipelineobserverPipelines_
 
std::shared_ptr< mc_rtc::Loggerlogger_
 
std::shared_ptr< mc_rtc::gui::StateBuildergui_
 
mc_rtc::Configuration config_
 
mc_rtc::DataStore datastore_
 
std::vector< mc_solver::ConstraintSetPtrconstraints_
 
std::shared_ptr< mc_solver::ContactConstraintcontact_constraint_ = nullptr
 
std::map< std::pair< std::string, std::string >, std::shared_ptr< mc_solver::CollisionsConstraint > > collision_constraints_
 
ContactSet contacts_
 
bool contacts_changed_
 
std::vector< ContactTableDataTcontacts_table_
 
duration_ms updateContacts_dt_ {0}
 

Friends

struct MCGlobalController
 

Detailed Description

MCController is the base class to implement all controllers. It assumes that at least two robots are provided. The first is considered as the "main" robot. Some common constraints and a posture task are defined (but not added to the solver) for this robot.

Member Typedef Documentation

◆ Backend

Shortcut for the Backend enum type

◆ ContactTableDataT

using mc_control::MCController::ContactTableDataT = std::tuple<std::string, std::string, std::string, std::string, std::string, double>
protected

Data shown in the contacts' table: R1, R1Surface, R2, R2Surface, DoF, Friction

◆ duration_ms

using mc_control::MCController::duration_ms = std::chrono::duration<double, std::milli>
protected

Constructor & Destructor Documentation

◆ ~MCController()

virtual mc_control::MCController::~MCController ( )
virtual

◆ MCController() [1/4]

mc_control::MCController::MCController ( std::shared_ptr< mc_rbdyn::RobotModule robot,
double  dt,
ControllerParameters  params = {} 
)
protected

Builds a controller with a single robot. The env/ground environment is automatically added

Parameters
robotPointer to the main RobotModule
dtTimestep of the controller
paramsExtra-parameters for the constructor

◆ MCController() [2/4]

mc_control::MCController::MCController ( std::shared_ptr< mc_rbdyn::RobotModule robot,
double  dt,
const mc_rtc::Configuration config,
ControllerParameters  params = {} 
)
protected

Builds a controller with a single robot. The env/ground environment is automatically added

Parameters
robotPointer to the main RobotModule
dtTimestep of the controller
configConfiguration of the controller
paramsExtra-parameters for the constructor

◆ MCController() [3/4]

mc_control::MCController::MCController ( const std::vector< std::shared_ptr< mc_rbdyn::RobotModule >> &  robot_modules,
double  dt,
ControllerParameters  params = {} 
)
protected

Builds a controller with multiple robots

Parameters
robotsCollection of robot modules used by the controller
dtTimestep of the controller
paramsExtra-parameters for the constructor

◆ MCController() [4/4]

mc_control::MCController::MCController ( const std::vector< std::shared_ptr< mc_rbdyn::RobotModule >> &  robot_modules,
double  dt,
const mc_rtc::Configuration config,
ControllerParameters  params = {} 
)
protected

Builds a controller with multiple robots

Parameters
robotsCollection of robot modules used by the controller
dtTimestep of the controller
configController configuration
paramsExtra-parameters for the constructor

Member Function Documentation

◆ addCollisions()

void mc_control::MCController::addCollisions ( const std::string &  r1,
const std::string &  r2,
const std::vector< mc_rbdyn::Collision > &  collisions 
)

Add collisions-pair between two robots

If the r1-r2 collision manager does not exist yet, it is created and added to the solver.

◆ addContact()

void mc_control::MCController::addContact ( const Contact c)

Add a contact between two robots

No effect if the contact is already present.

◆ addRobotToGUI()

void mc_control::MCController::addRobotToGUI ( const mc_rbdyn::Robot robot)
protected

Add a control robot to the GUI

◆ addRobotToLog()

void mc_control::MCController::addRobotToLog ( const mc_rbdyn::Robot robot)
protected

Add a control robot to the log

◆ anchorFrame() [1/2]

template<typename T = void>
const sva::PTransformd& mc_control::MCController::anchorFrame ( ) const
inline
Deprecated:
The observer's anchor frame is now provided by a callback on the datastore. For further information, please refer to the observer's tutorial: https://jrl-umi3218.github.io/mc_rtc/tutorials/recipes/observers.html

◆ anchorFrame() [2/2]

template<typename T = void>
void mc_control::MCController::anchorFrame ( const sva::PTransformd &  )
inline
Deprecated:
The observer's anchor frame is now provided by a callback on the datastore. For further information, please refer to the observer's tutorial: https://jrl-umi3218.github.io/mc_rtc/tutorials/recipes/observers.html

◆ anchorFrameReal() [1/2]

template<typename T = void>
const sva::PTransformd& mc_control::MCController::anchorFrameReal ( ) const
inline
Deprecated:
The observer's anchor frame is now provided by a callback on the datastore. For further information, please refer to the observer's tutorial: https://jrl-umi3218.github.io/mc_rtc/tutorials/recipes/observers.html

◆ anchorFrameReal() [2/2]

template<typename T = void>
void mc_control::MCController::anchorFrameReal ( const sva::PTransformd &  )
inline
Deprecated:
The observer's anchor frame is now provided by a callback on the datastore. For further information, please refer to the observer's tutorial: https://jrl-umi3218.github.io/mc_rtc/tutorials/recipes/observers.html

◆ clearContacts()

void mc_control::MCController::clearContacts ( )

Remove all contacts

◆ config() [1/2]

mc_rtc::Configuration& mc_control::MCController::config ( )
inline

Access or modify controller configuration

◆ config() [2/2]

const mc_rtc::Configuration& mc_control::MCController::config ( ) const
inline

Access controller configuration (const)

◆ contacts()

const ContactSet& mc_control::MCController::contacts ( ) const

Access the current contacts

◆ createObserverPipelines()

virtual void mc_control::MCController::createObserverPipelines ( const mc_rtc::Configuration config)
virtual

Create state observation pipelines from configuration

Please refer to the ObserverPipelines JSON Schema for supported configuration options.

See also
mc_observers::ObserverPipeline

◆ datastore() [1/2]

const mc_rtc::DataStore& mc_control::MCController::datastore ( ) const
inlinenoexcept

Provides access to the shared datastore (const)

◆ datastore() [2/2]

mc_rtc::DataStore& mc_control::MCController::datastore ( )
inlinenoexcept

Provides access to the shared datastore

◆ env() [1/2]

const mc_rbdyn::Robot& mc_control::MCController::env ( ) const
inlinenoexcept

Return the env "robot"

Note
In multi-robot scenarios, the env robot is either:
  1. The first robot with zero dof
  2. The last robot provided at construction

◆ env() [2/2]

mc_rbdyn::Robot& mc_control::MCController::env ( )
inlinenoexcept

Non-const variant of env()

◆ gripper()

Gripper& mc_control::MCController::gripper ( const std::string &  robot,
const std::string &  gripper 
)

Access a gripper by robot's name and gripper's name

Parameters
robotName of the robot
gripperName of the gripper
Exceptions
Ifthe robot's name is not valid or the gripper's name is not valid

◆ gui()

std::shared_ptr<mc_rtc::gui::StateBuilder> mc_control::MCController::gui ( ) const
inlinenoexcept

◆ hasCollision() [1/2]

bool mc_control::MCController::hasCollision ( const std::string &  r1,
const std::string &  r2,
const mc_rbdyn::Collision col 
) const
noexcept

Returns true if the given collision is active

◆ hasCollision() [2/2]

bool mc_control::MCController::hasCollision ( const std::string &  r1,
const std::string &  r2,
const std::string &  c1,
const std::string &  c2 
) const
noexcept

Returns true if the given collision is active

◆ hasContact()

bool mc_control::MCController::hasContact ( const Contact c) const

Check if a contact is already present

◆ hasObserverPipeline() [1/2]

bool mc_control::MCController::hasObserverPipeline ( ) const

True if this controller has at least one state observation pipeline

◆ hasObserverPipeline() [2/2]

bool mc_control::MCController::hasObserverPipeline ( const std::string &  name) const

Whether this controller contains a pipeline with the provided name

Parameters
nameName of the pipeline

◆ hasRobot()

bool mc_control::MCController::hasRobot ( const std::string &  robot) const
inlinenoexcept

Returns true if the robot is part of the controller

◆ loadRobot() [1/2]

mc_rbdyn::Robot& mc_control::MCController::loadRobot ( mc_rbdyn::RobotModulePtr  rm,
const std::string &  name 
)

Load an additional robot into the controller (and its corresponding realRobot instance)

Parameters
rmRobotModule used to load the robot
nameName of the robot
Returns
The loaded control robot. You may access the corresponding real robot through realRobots().robot(name)

◆ loadRobot() [2/2]

mc_rbdyn::Robot& mc_control::MCController::loadRobot ( mc_rbdyn::RobotModulePtr  rm,
const std::string &  name,
mc_rbdyn::Robots robots,
const mc_rbdyn::LoadRobotParameters params 
)
protected

Load an additional robot into the controller

Parameters
nameName of the robot
rmRobotModule used to load the robot
robotsRobots in which this robot will be loaded
updateNrVarsWhen true, update the number of variables in the QP problem.
Returns
The loaded robot

◆ logger()

mc_rtc::Logger& mc_control::MCController::logger ( )
inlinenoexcept

Returns mc_rtc::Logger instance

◆ observerPipeline() [1/4]

mc_observers::ObserverPipeline& mc_control::MCController::observerPipeline ( )

Non-const variant

◆ observerPipeline() [2/4]

const mc_observers::ObserverPipeline& mc_control::MCController::observerPipeline ( ) const

Provides const access to the main observer pipeline (first pipeline)

Exceptions
ifthis controller does not have any pipeline

◆ observerPipeline() [3/4]

mc_observers::ObserverPipeline& mc_control::MCController::observerPipeline ( const std::string &  name)

Non-const variant

◆ observerPipeline() [4/4]

const mc_observers::ObserverPipeline& mc_control::MCController::observerPipeline ( const std::string &  name) const

Provides const access to a state-observation pipeline

Exceptions
ifno pipeline with that name exist

◆ observerPipelines() [1/2]

std::vector<mc_observers::ObserverPipeline>& mc_control::MCController::observerPipelines ( )

Non-const variant

◆ observerPipelines() [2/2]

const std::vector<mc_observers::ObserverPipeline>& mc_control::MCController::observerPipelines ( ) const

Provides const access to the state observation pipelines defined in this controller

◆ outputRealRobot() [1/4]

const mc_rbdyn::Robot& mc_control::MCController::outputRealRobot ( ) const
inlinenoexcept

Return the main mc_rbdyn::Robot real robot instance

◆ outputRealRobot() [2/4]

mc_rbdyn::Robot& mc_control::MCController::outputRealRobot ( )
inlinenoexcept

Non-const variant of outputRealRobot()

◆ outputRealRobot() [3/4]

mc_rbdyn::Robot& mc_control::MCController::outputRealRobot ( const std::string &  name)
inline

Non-const variant of outputRealRobot(name)

◆ outputRealRobot() [4/4]

const mc_rbdyn::Robot& mc_control::MCController::outputRealRobot ( const std::string &  name) const
inline

Return the mc_rbdyn::Robot controlled by this controller

Exceptions
std::runtime_errorif the robot does not exist

◆ outputRealRobots() [1/2]

const mc_rbdyn::Robots& mc_control::MCController::outputRealRobots ( ) const
inlinenoexcept

Return the mc_rbdyn::Robots real robots instance

◆ outputRealRobots() [2/2]

mc_rbdyn::Robots& mc_control::MCController::outputRealRobots ( )
inlinenoexcept

Non-const variant of outputRealRobots()

◆ outputRobot() [1/4]

const mc_rbdyn::Robot& mc_control::MCController::outputRobot ( ) const
inlinenoexcept

Return the main robot's output instance

◆ outputRobot() [2/4]

mc_rbdyn::Robot& mc_control::MCController::outputRobot ( )
inlinenoexcept

Non-const variant of outputRobot()

◆ outputRobot() [3/4]

mc_rbdyn::Robot& mc_control::MCController::outputRobot ( const std::string &  name)
inline

Non-const variant of outputRobot(name)

◆ outputRobot() [4/4]

const mc_rbdyn::Robot& mc_control::MCController::outputRobot ( const std::string &  name) const
inline

Return an output robot by name

Exceptions
std::runtime_errorif the robot does not exist

◆ outputRobots() [1/2]

const mc_rbdyn::Robots& mc_control::MCController::outputRobots ( ) const
inlinenoexcept

Return the output robots

◆ outputRobots() [2/2]

mc_rbdyn::Robots& mc_control::MCController::outputRobots ( )
inlinenoexcept

Non-const variant of outputRobots()

◆ realRobot() [1/4]

const mc_rbdyn::Robot& mc_control::MCController::realRobot ( ) const
inlinenoexcept

Return the main mc_rbdyn::Robot real robot instance

◆ realRobot() [2/4]

mc_rbdyn::Robot& mc_control::MCController::realRobot ( )
inlinenoexcept

Non-const variant of realRobot()

◆ realRobot() [3/4]

mc_rbdyn::Robot& mc_control::MCController::realRobot ( const std::string &  name)
inline

Non-const variant of realRobot(name)

◆ realRobot() [4/4]

const mc_rbdyn::Robot& mc_control::MCController::realRobot ( const std::string &  name) const
inline

Return the mc_rbdyn::Robot controlled by this controller

Exceptions
std::runtime_errorif the robot does not exist

◆ realRobots() [1/2]

const mc_rbdyn::Robots& mc_control::MCController::realRobots ( ) const
inlinenoexcept

Return the mc_rbdyn::Robots real robots instance

◆ realRobots() [2/2]

mc_rbdyn::Robots& mc_control::MCController::realRobots ( )
inlinenoexcept

Non-const variant of realRobots()

◆ removeCollisions() [1/2]

void mc_control::MCController::removeCollisions ( const std::string &  r1,
const std::string &  r2 
)

Remove all collision-pair between two robots

If the r1-r2 collision manager does not exist yet, this has no effect.

◆ removeCollisions() [2/2]

void mc_control::MCController::removeCollisions ( const std::string &  r1,
const std::string &  r2,
const std::vector< mc_rbdyn::Collision > &  collisions 
)

Remove collisions-pair between two robots

If the r1-r2 collision manager does not exist yet, this has no effect.

◆ removeContact()

void mc_control::MCController::removeContact ( const Contact c)

Remove a contact between two robots

No effect if the contact is already absent.

◆ removeRobot()

void mc_control::MCController::removeRobot ( const std::string &  name)

Remove a robot from the controller

Parameters
nameName of the robot to remove

◆ reset()

virtual void mc_control::MCController::reset ( const ControllerResetData reset_data)
virtual

Reset the controller with data provided by ControllerResetData. This is called at two possible points during a simulation/live execution:

  1. Actual start
  2. Switch from a previous (MCController-like) controller In the first case, the data comes from the simulation/controller. In the second case, the data comes from the previous MCController instance.
    Parameters
    reset_dataContains information allowing to reset the controller properly
    Note
    The default implementation reset the main robot's state to that provided by reset_data (with a null speed/acceleration). It maintains the contacts as they were set by the controller previously.
    Exceptions
    ifthe main robot is not supported (see supported_robots())

Reimplemented in mc_control::MCPythonController, and mc_control::fsm::Controller.

◆ resetObserverPipelines()

virtual bool mc_control::MCController::resetObserverPipelines ( )
virtual

Reset the observers.

This function is called after the reset() function.

Returns
True when all observers have been succesfully reset.

◆ robot() [1/4]

const mc_rbdyn::Robot& mc_control::MCController::robot ( ) const
inlinenoexcept

Return the main robot (first robot provided in the constructor)

◆ robot() [2/4]

mc_rbdyn::Robot& mc_control::MCController::robot ( )
inlinenoexcept

Non-const variant of robot()

◆ robot() [3/4]

mc_rbdyn::Robot& mc_control::MCController::robot ( const std::string &  name)
inline

Non-const variant of robot(name)

◆ robot() [4/4]

const mc_rbdyn::Robot& mc_control::MCController::robot ( const std::string &  name) const
inline

Return the mc_rbdyn::Robot controlled by this controller

Exceptions
std::runtime_errorif the robot does not exist

◆ robot_config() [1/2]

mc_rtc::Configuration mc_control::MCController::robot_config ( const mc_rbdyn::Robot robot) const

Same as robot_config(robot.module().name)

◆ robot_config() [2/2]

mc_rtc::Configuration mc_control::MCController::robot_config ( const std::string &  robot_name) const

Load a robot specific configuration (if any)

The following files are loaded (in that order):

  • ${loading_location}/${name()}/${robot_name}.conf|yaml
  • ${HOME}/.config/mc_rtc/controllers/${name()}/${robot_name}.conf|yaml (Linux/macOS)
  • ${APPDATA}/mc_rtc/controllers/${name()}/${robot_name}.conf|yaml (Windows)

◆ robots() [1/2]

const mc_rbdyn::Robots& mc_control::MCController::robots ( ) const
inlinenoexcept

Return the mc_rbdyn::Robots controlled by this controller

◆ robots() [2/2]

mc_rbdyn::Robots& mc_control::MCController::robots ( )
inlinenoexcept

Non-const variant of robots()

◆ run() [1/2]

virtual bool mc_control::MCController::run ( )
virtual

This function is called at each time step of the process driving the robot (i.e. simulation or robot's controller). This function is the most likely to be overriden for complex controller behaviours.

Returns
True if the solver succeeded, false otherwise
Note
This is meant to run in real-time hence some precaution should apply (e.g. no i/o blocking calls, no thread instantiation and such)
The default implementation does the bare minimum (i.e. call run on QPSolver) It is recommended to use it in your override.

Reimplemented in mc_control::fsm::Controller, and mc_control::MCPythonController.

◆ run() [2/2]

bool mc_control::MCController::run ( mc_solver::FeedbackType  fType)

Can be called in derived class instead of run to use a feedback strategy different from the default one

Parameters
fTypeType of feedback used in the solver

◆ runObserverPipelines()

virtual bool mc_control::MCController::runObserverPipelines ( )
virtual

This function is called before the run() function at each time step of the process driving the robot (i.e. simulation or robot's controller). The default behaviour is to call the run() function of each loaded observer and update the realRobot instance when desired.

This is meant to run in real-time hence some precaution should apply (e.g. no i/o blocking calls, no thread instantiation and such)

Note
Some estimators are likely to require extra information from the control. Each observer has access to the MCController instance, and may access all information available from it (robots, etc). In addition some observers may require additional information that is not part of the MCController instance. In that case, it may be provided though the Datastore (see each observer's documentation for specific requirements).
If the default pipeline behaviour does not suit you, you may override this method.
Returns
true if all observers ran as expected, false otherwise

◆ set_loading_location()

static void mc_control::MCController::set_loading_location ( std::string_view  location)
static

Called by mc_rtc::ObjectLoader to inform the controller of its loading location For example, if the CoM controller is loaded from the library in /usr/local/lib/mc_controller/com.so then this is /usr/local/lib/mc_controller/

The value is stored in a thread_local variable and is meant to be used in the constructor of MCController

◆ set_name()

static void mc_control::MCController::set_name ( std::string_view  name)
static

Called by mc_rtc::ObjectLoader to set the name of the controller

The value is stored in a thread_local variable and is meant to be used in the constructor of MCController

◆ solver() [1/2]

const mc_solver::QPSolver& mc_control::MCController::solver ( ) const
inlinenoexcept

Return the mc_solver::QPSolver instance attached to this controller

◆ solver() [2/2]

mc_solver::QPSolver& mc_control::MCController::solver ( )
inlinenoexcept

Non-const variant of solver()

◆ stop()

virtual void mc_control::MCController::stop ( )
virtual

This function is called when the controller is stopped.

The default implementation does nothing.

For example, it can be overriden to signal threads launched by the controller to pause.

◆ supported_robots()

virtual void mc_control::MCController::supported_robots ( std::vector< std::string > &  out) const
virtual

Returns a list of robots supported by the controller.

Parameters
outVector of supported robots designed by name (as returned by RobotModule::name())
Note
  • Default implementation returns an empty list which indicates that all robots are supported.
  • If the list is not empty, only the robots in that list are allowed to be used with the controller. The main robot will be checked against the list of supported robots upon call to reset(), and an exception will be thrown if the robot is not supported.

◆ updateContacts()

void mc_control::MCController::updateContacts ( )
protected

Update the contacts (or their DoFs) if needed

Friends And Related Function Documentation

◆ MCGlobalController

friend struct MCGlobalController
friend

Member Data Documentation

◆ collision_constraints_

std::map<std::pair<std::string, std::string>, std::shared_ptr<mc_solver::CollisionsConstraint> > mc_control::MCController::collision_constraints_
protected

Collision managers for robot-pair (r1, r2), if r1 == r2 this is effectively a self-collision manager

◆ compoundJointConstraint

mc_rtc::unique_ptr<mc_solver::CompoundJointConstraint> mc_control::MCController::compoundJointConstraint

Compound joint constraint for the main robot

◆ config_

mc_rtc::Configuration mc_control::MCController::config_
protected

Keep track of the configuration of the controller

◆ constraints_

std::vector<mc_solver::ConstraintSetPtr> mc_control::MCController::constraints_
protected

Holds dynamics, kinematics and contact constraints that are added from the start by the controller

◆ contact_constraint_

std::shared_ptr<mc_solver::ContactConstraint> mc_control::MCController::contact_constraint_ = nullptr
protected

Keep track of the contact constraint

◆ contactConstraint

mc_rtc::unique_ptr<mc_solver::ContactConstraint> mc_control::MCController::contactConstraint

Contact constraint for the main robot

◆ contacts_

ContactSet mc_control::MCController::contacts_
protected

FSM contacts

◆ contacts_changed_

bool mc_control::MCController::contacts_changed_
protected

True if contacts were changed in the previous round

◆ contacts_table_

std::vector<ContactTableDataT> mc_control::MCController::contacts_table_
protected

Used in GUI display

◆ converters_

std::vector<mc_rbdyn::RobotConverter> mc_control::MCController::converters_
protected

Control to canonical converters

◆ datastore_

mc_rtc::DataStore mc_control::MCController::datastore_
protected

DataStore to share variables/objects between different parts of the framework (states...)

◆ dynamicsConstraint

mc_rtc::unique_ptr<mc_solver::DynamicsConstraint> mc_control::MCController::dynamicsConstraint

Dynamics constraints for the main robot

◆ gui_

std::shared_ptr<mc_rtc::gui::StateBuilder> mc_control::MCController::gui_
protected

GUI state builder

◆ kinematicsConstraint

mc_rtc::unique_ptr<mc_solver::KinematicsConstraint> mc_control::MCController::kinematicsConstraint

Kinematics constraints for the main robot

◆ loading_location_

const std::string mc_control::MCController::loading_location_

Stores the loading location provided by the loader via set_loading_location

◆ logger_

std::shared_ptr<mc_rtc::Logger> mc_control::MCController::logger_
protected

Logger provided by MCGlobalController

◆ name_

const std::string mc_control::MCController::name_

◆ observerPipelines_

std::vector<mc_observers::ObserverPipeline> mc_control::MCController::observerPipelines_
protected

State observation pipelines for this controller

◆ outputRealRobots_

mc_rbdyn::RobotsPtr mc_control::MCController::outputRealRobots_
protected

◆ outputRobots_

mc_rbdyn::RobotsPtr mc_control::MCController::outputRobots_
protected

Load robots used for output (display/control)

These robots use the canonical model representation defined in the robot module.

◆ postureTask

std::shared_ptr<mc_tasks::PostureTask> mc_control::MCController::postureTask

Posture task for the main robot

◆ qpsolver

std::shared_ptr<mc_solver::QPSolver> mc_control::MCController::qpsolver
protected

QP solver

◆ selfCollisionConstraint

mc_rtc::unique_ptr<mc_solver::CollisionsConstraint> mc_control::MCController::selfCollisionConstraint

Self collisions constraint for the main robot

◆ timeStep

const double mc_control::MCController::timeStep

Controller timestep

◆ updateContacts_dt_

duration_ms mc_control::MCController::updateContacts_dt_ {0}
protected

Monitor updateContacts runtime


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