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>
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::ObserverPipeline & | observerPipeline (const std::string &name) const |
mc_observers::ObserverPipeline & | observerPipeline (const std::string &name) |
const mc_observers::ObserverPipeline & | observerPipeline () const |
mc_observers::ObserverPipeline & | observerPipeline () |
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 ContactSet & | contacts () const |
bool | hasContact (const Contact &c) const |
bool | hasRobot (const std::string &robot) const noexcept |
const mc_rbdyn::Robots & | robots () const noexcept |
mc_rbdyn::Robots & | robots () noexcept |
const mc_solver::QPSolver & | solver () const noexcept |
mc_solver::QPSolver & | solver () noexcept |
mc_rtc::Logger & | logger () noexcept |
std::shared_ptr< mc_rtc::gui::StateBuilder > | gui () const noexcept |
mc_rtc::DataStore & | datastore () noexcept |
const mc_rtc::DataStore & | datastore () const noexcept |
virtual void | supported_robots (std::vector< std::string > &out) const |
mc_rbdyn::Robot & | loadRobot (mc_rbdyn::RobotModulePtr rm, const std::string &name) |
void | removeRobot (const std::string &name) |
mc_rtc::Configuration & | config () |
const mc_rtc::Configuration & | config () const |
Gripper & | gripper (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::Robot & | robot () const noexcept |
mc_rbdyn::Robot & | robot () noexcept |
const mc_rbdyn::Robot & | robot (const std::string &name) const |
mc_rbdyn::Robot & | robot (const std::string &name) |
const mc_rbdyn::Robot & | env () const noexcept |
mc_rbdyn::Robot & | env () noexcept |
Accessors to the real robots | |
const mc_rbdyn::Robots & | realRobots () const noexcept |
mc_rbdyn::Robots & | realRobots () noexcept |
const mc_rbdyn::Robot & | realRobot () const noexcept |
mc_rbdyn::Robot & | realRobot () noexcept |
const mc_rbdyn::Robot & | realRobot (const std::string &name) const |
mc_rbdyn::Robot & | realRobot (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::Robots & | outputRobots () const noexcept |
mc_rbdyn::Robots & | outputRobots () noexcept |
const mc_rbdyn::Robot & | outputRobot () const noexcept |
mc_rbdyn::Robot & | outputRobot () noexcept |
const mc_rbdyn::Robot & | outputRobot (const std::string &name) const |
mc_rbdyn::Robot & | outputRobot (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::Robots & | outputRealRobots () const noexcept |
mc_rbdyn::Robots & | outputRealRobots () noexcept |
const mc_rbdyn::Robot & | outputRealRobot () const noexcept |
mc_rbdyn::Robot & | outputRealRobot () noexcept |
const mc_rbdyn::Robot & | outputRealRobot (const std::string &name) const |
mc_rbdyn::Robot & | outputRealRobot (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::ContactConstraint > | contactConstraint |
mc_rtc::unique_ptr< mc_solver::DynamicsConstraint > | dynamicsConstraint |
mc_rtc::unique_ptr< mc_solver::KinematicsConstraint > | kinematicsConstraint |
mc_rtc::unique_ptr< mc_solver::CollisionsConstraint > | selfCollisionConstraint |
mc_rtc::unique_ptr< mc_solver::CompoundJointConstraint > | compoundJointConstraint |
std::shared_ptr< mc_tasks::PostureTask > | postureTask |
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::Robot & | loadRobot (mc_rbdyn::RobotModulePtr rm, const std::string &name, mc_rbdyn::Robots &robots, const mc_rbdyn::LoadRobotParameters ¶ms) |
void | addRobotToLog (const mc_rbdyn::Robot &robot) |
void | addRobotToGUI (const mc_rbdyn::Robot &robot) |
void | updateContacts () |
Protected Attributes | |
std::shared_ptr< mc_solver::QPSolver > | qpsolver |
mc_rbdyn::RobotsPtr | outputRobots_ |
mc_rbdyn::RobotsPtr | outputRealRobots_ |
std::vector< mc_rbdyn::RobotConverter > | converters_ |
std::vector< mc_observers::ObserverPipeline > | observerPipelines_ |
std::shared_ptr< mc_rtc::Logger > | logger_ |
std::shared_ptr< mc_rtc::gui::StateBuilder > | gui_ |
mc_rtc::Configuration | config_ |
mc_rtc::DataStore | datastore_ |
std::vector< mc_solver::ConstraintSetPtr > | constraints_ |
std::shared_ptr< mc_solver::ContactConstraint > | contact_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< ContactTableDataT > | contacts_table_ |
duration_ms | updateContacts_dt_ {0} |
Friends | |
struct | MCGlobalController |
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.
Shortcut for the Backend enum type
|
protected |
Data shown in the contacts' table: R1, R1Surface, R2, R2Surface, DoF, Friction
|
protected |
|
virtual |
|
protected |
Builds a controller with a single robot. The env/ground environment is automatically added
robot | Pointer to the main RobotModule |
dt | Timestep of the controller |
params | Extra-parameters for the constructor |
|
protected |
Builds a controller with a single robot. The env/ground environment is automatically added
robot | Pointer to the main RobotModule |
dt | Timestep of the controller |
config | Configuration of the controller |
params | Extra-parameters for the constructor |
|
protected |
Builds a controller with multiple robots
robots | Collection of robot modules used by the controller |
dt | Timestep of the controller |
params | Extra-parameters for the constructor |
|
protected |
Builds a controller with multiple robots
robots | Collection of robot modules used by the controller |
dt | Timestep of the controller |
config | Controller configuration |
params | Extra-parameters for the constructor |
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.
void mc_control::MCController::addContact | ( | const Contact & | c | ) |
Add a contact between two robots
No effect if the contact is already present.
|
protected |
Add a control robot to the GUI
|
protected |
Add a control robot to the log
|
inline |
|
inline |
|
inline |
|
inline |
void mc_control::MCController::clearContacts | ( | ) |
Remove all contacts
|
inline |
Access or modify controller configuration
|
inline |
Access controller configuration (const)
const ContactSet& mc_control::MCController::contacts | ( | ) | const |
Access the current contacts
|
virtual |
Create state observation pipelines from configuration
Please refer to the ObserverPipelines JSON Schema for supported configuration options.
|
inlinenoexcept |
Provides access to the shared datastore (const)
|
inlinenoexcept |
Provides access to the shared datastore
|
inlinenoexcept |
|
inlinenoexcept |
Non-const variant of env()
Gripper& mc_control::MCController::gripper | ( | const std::string & | robot, |
const std::string & | gripper | ||
) |
Access a gripper by robot's name and gripper's name
robot | Name of the robot |
gripper | Name of the gripper |
If | the robot's name is not valid or the gripper's name is not valid |
|
inlinenoexcept |
Returns mc_rtc::gui::StateBuilder ptr
|
noexcept |
Returns true if the given collision is active
|
noexcept |
Returns true if the given collision is active
bool mc_control::MCController::hasContact | ( | const Contact & | c | ) | const |
Check if a contact is already present
bool mc_control::MCController::hasObserverPipeline | ( | ) | const |
True if this controller has at least one state observation pipeline
bool mc_control::MCController::hasObserverPipeline | ( | const std::string & | name | ) | const |
Whether this controller contains a pipeline with the provided name
name | Name of the pipeline |
|
inlinenoexcept |
Returns true if the robot is part of the controller
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)
rm | RobotModule used to load the robot |
name | Name of the robot |
|
protected |
Load an additional robot into the controller
name | Name of the robot |
rm | RobotModule used to load the robot |
robots | Robots in which this robot will be loaded |
updateNrVars | When true, update the number of variables in the QP problem. |
|
inlinenoexcept |
Returns mc_rtc::Logger instance
mc_observers::ObserverPipeline& mc_control::MCController::observerPipeline | ( | ) |
Non-const variant
const mc_observers::ObserverPipeline& mc_control::MCController::observerPipeline | ( | ) | const |
Provides const access to the main observer pipeline (first pipeline)
if | this controller does not have any pipeline |
mc_observers::ObserverPipeline& mc_control::MCController::observerPipeline | ( | const std::string & | name | ) |
Non-const variant
const mc_observers::ObserverPipeline& mc_control::MCController::observerPipeline | ( | const std::string & | name | ) | const |
Provides const access to a state-observation pipeline
if | no pipeline with that name exist |
std::vector<mc_observers::ObserverPipeline>& mc_control::MCController::observerPipelines | ( | ) |
Non-const variant
const std::vector<mc_observers::ObserverPipeline>& mc_control::MCController::observerPipelines | ( | ) | const |
Provides const access to the state observation pipelines defined in this controller
|
inlinenoexcept |
Return the main mc_rbdyn::Robot real robot instance
|
inlinenoexcept |
Non-const variant of outputRealRobot()
|
inline |
Non-const variant of outputRealRobot(name)
|
inline |
Return the mc_rbdyn::Robot controlled by this controller
|
inlinenoexcept |
Return the mc_rbdyn::Robots real robots instance
|
inlinenoexcept |
Non-const variant of outputRealRobots()
|
inlinenoexcept |
|
inlinenoexcept |
Non-const variant of outputRobot()
|
inline |
Non-const variant of outputRobot(name)
|
inline |
|
inlinenoexcept |
|
inlinenoexcept |
Non-const variant of outputRobots()
|
inlinenoexcept |
Return the main mc_rbdyn::Robot real robot instance
|
inlinenoexcept |
Non-const variant of realRobot()
|
inline |
Non-const variant of realRobot(name)
|
inline |
Return the mc_rbdyn::Robot controlled by this controller
|
inlinenoexcept |
Return the mc_rbdyn::Robots real robots instance
|
inlinenoexcept |
Non-const variant of realRobots()
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.
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.
void mc_control::MCController::removeContact | ( | const Contact & | c | ) |
Remove a contact between two robots
No effect if the contact is already absent.
void mc_control::MCController::removeRobot | ( | const std::string & | name | ) |
Remove a robot from the controller
name | Name of the robot to remove |
|
virtual |
Reset the controller with data provided by ControllerResetData. This is called at two possible points during a simulation/live execution:
reset_data | Contains information allowing to reset the controller properly |
if | the main robot is not supported (see supported_robots()) |
Reimplemented in mc_control::MCPythonController, and mc_control::fsm::Controller.
|
virtual |
Reset the observers.
This function is called after the reset() function.
|
inlinenoexcept |
|
inlinenoexcept |
Non-const variant of robot()
|
inline |
Non-const variant of robot(name)
|
inline |
Return the mc_rbdyn::Robot controlled by this controller
mc_rtc::Configuration mc_control::MCController::robot_config | ( | const mc_rbdyn::Robot & | robot | ) | const |
Same as robot_config(robot.module().name)
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):
|
inlinenoexcept |
Return the mc_rbdyn::Robots controlled by this controller
|
inlinenoexcept |
Non-const variant of robots()
|
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.
Reimplemented in mc_control::fsm::Controller, and mc_control::MCPythonController.
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
fType | Type of feedback used in the solver |
|
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)
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).
|
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
|
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
|
inlinenoexcept |
Return the mc_solver::QPSolver instance attached to this controller
|
inlinenoexcept |
Non-const variant of solver()
|
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.
|
virtual |
Returns a list of robots supported by the controller.
out | Vector of supported robots designed by name (as returned by RobotModule::name()) |
|
protected |
Update the contacts (or their DoFs) if needed
|
friend |
|
protected |
Collision managers for robot-pair (r1, r2), if r1 == r2 this is effectively a self-collision manager
mc_rtc::unique_ptr<mc_solver::CompoundJointConstraint> mc_control::MCController::compoundJointConstraint |
Compound joint constraint for the main robot
|
protected |
Keep track of the configuration of the controller
|
protected |
Holds dynamics, kinematics and contact constraints that are added from the start by the controller
|
protected |
Keep track of the contact constraint
mc_rtc::unique_ptr<mc_solver::ContactConstraint> mc_control::MCController::contactConstraint |
Contact constraint for the main robot
|
protected |
FSM contacts
|
protected |
True if contacts were changed in the previous round
|
protected |
Used in GUI display
|
protected |
Control to canonical converters
|
protected |
DataStore to share variables/objects between different parts of the framework (states...)
mc_rtc::unique_ptr<mc_solver::DynamicsConstraint> mc_control::MCController::dynamicsConstraint |
Dynamics constraints for the main robot
|
protected |
GUI state builder
mc_rtc::unique_ptr<mc_solver::KinematicsConstraint> mc_control::MCController::kinematicsConstraint |
Kinematics constraints for the main robot
const std::string mc_control::MCController::loading_location_ |
Stores the loading location provided by the loader via set_loading_location
|
protected |
Logger provided by MCGlobalController
const std::string mc_control::MCController::name_ |
|
protected |
State observation pipelines for this controller
|
protected |
|
protected |
Load robots used for output (display/control)
These robots use the canonical model representation defined in the robot module.
std::shared_ptr<mc_tasks::PostureTask> mc_control::MCController::postureTask |
Posture task for the main robot
|
protected |
QP solver
mc_rtc::unique_ptr<mc_solver::CollisionsConstraint> mc_control::MCController::selfCollisionConstraint |
Self collisions constraint for the main robot
const double mc_control::MCController::timeStep |
Controller timestep
|
protected |
Monitor updateContacts runtime