mc_control::MCPythonController Struct Reference

#include <mc_control/mc_python_controller.h>

Inheritance diagram for mc_control::MCPythonController:
Collaboration diagram for mc_control::MCPythonController:

Public Member Functions

 MCPythonController (const std::vector< std::shared_ptr< mc_rbdyn::RobotModule >> &robots, double dt)
 
virtual void reset (const ControllerResetData &reset_data) override
 
virtual bool run () override
 
- Public Member Functions inherited from mc_control::MCController
virtual ~MCController ()
 
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 ()
 
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
 
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
 
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)
 
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)
 
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)
 

Public Attributes

std::function< bool()> run_callback
 
std::function< void(const ControllerResetData &)> reset_callback
 
std::function< bool()> handle_python_error
 
- Public Attributes inherited from mc_control::MCController
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_
 

Additional Inherited Members

- Public Types inherited from mc_control::MCController
using Backend = mc_solver::QPSolver::Backend
 
- Static Public Member Functions inherited from mc_control::MCController
static void set_loading_location (std::string_view location)
 
static void set_name (std::string_view name)
 
- Protected Types inherited from mc_control::MCController
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 inherited from mc_control::MCController
 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 inherited from mc_control::MCController
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}
 

Constructor & Destructor Documentation

◆ MCPythonController()

mc_control::MCPythonController::MCPythonController ( const std::vector< std::shared_ptr< mc_rbdyn::RobotModule >> &  robots,
double  dt 
)

Member Function Documentation

◆ reset()

virtual void mc_control::MCPythonController::reset ( const ControllerResetData reset_data)
overridevirtual

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 from mc_control::MCController.

◆ run()

virtual bool mc_control::MCPythonController::run ( )
overridevirtual

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 from mc_control::MCController.

Member Data Documentation

◆ handle_python_error

std::function<bool()> mc_control::MCPythonController::handle_python_error

◆ reset_callback

std::function<void(const ControllerResetData &)> mc_control::MCPythonController::reset_callback

◆ run_callback

std::function<bool()> mc_control::MCPythonController::run_callback

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