mc_control::MCGlobalController Struct Reference

#include <mc_control/mc_global_controller.h>

Classes

struct  GlobalConfiguration
 Store the controller configuration. More...
 

Public Types

using QuaternionMapAllocator = Eigen::aligned_allocator< std::pair< const std::string, Eigen::Quaterniond > >
 
using QuaternionMap = std::map< std::string, Eigen::Quaterniond, std::less< std::string >, QuaternionMapAllocator >
 

Public Member Functions

 MCGlobalController (const std::string &conf="", std::shared_ptr< mc_rbdyn::RobotModule > rm=nullptr)
 Create the global controller. More...
 
 MCGlobalController (const GlobalConfiguration &conf)
 Create the global controller with an existing GlobalConfiguration instance. More...
 
 ~MCGlobalController ()
 Destructor. More...
 
std::vector< std::string > enabled_controllers () const
 Returns a list of enabled controllers. More...
 
std::vector< std::string > loaded_controllers () const
 Returns a list of all the loaded controllers, whether they are enabled or not. More...
 
std::vector< std::string > loaded_robots () const
 Returns a list of all the loaded robots, whether they are enabled or not. More...
 
std::shared_ptr< mc_rbdyn::RobotModuleget_robot_module ()
 Returns the main robot module. More...
 
std::string current_controller () const
 Returns the name of the current controller. More...
 
void init (const std::vector< double > &initq)
 Initialize the default controller with the given configuration. More...
 
void init (const std::vector< double > &initq, const std::array< double, 7 > &initAttitude)
 Initialize robot attitude from encoders and the floating base attitude. More...
 
void init (const std::vector< double > &initq, const sva::PTransformd &initAttitude)
 Initialize robot attitude from encoders and the floating base attitude. More...
 
void init (const std::map< std::string, std::vector< double >> &initqs={}, const std::map< std::string, sva::PTransformd > &initAttitudes={})
 Initialize multiple robots to the given configuration and attitude. More...
 
void reset (const std::map< std::string, std::vector< double >> &resetqs={}, const std::map< std::string, sva::PTransformd > &resetAttitudes={})
 Fully reset the current controller to the given initial state. More...
 
bool run ()
 Runs one step of the controller. More...
 
ControllerServerserver ()
 Access the server. More...
 
MCControllercontroller () noexcept
 Access the current controller. More...
 
const MCControllercontroller () const noexcept
 Const access to current controller. More...
 
double timestep () const
 Get the controller timestep. More...
 
const std::vector< std::string > & ref_joint_order ()
 Access the reference joint order. More...
 
const GlobalConfigurationconfiguration () const
 Access the global controller configuration. More...
 
void add_controller_module_paths (const std::vector< std::string > &paths)
 Add the given directories to the controller search path. More...
 
bool AddController (const std::string &name)
 Add a controller to the enabled list. More...
 
bool AddController (const std::string &name, std::shared_ptr< mc_control::MCController > controller)
 Add an already created controller to the enabled list. More...
 
bool EnableController (const std::string &name)
 Switch to the requested controller. More...
 
void refreshLog ()
 Create a new log file for the current controller. More...
 
Sensing

These functions are used to communicate sensors' information to the controller. Each function sets the requested sensor to both the control robots() instance and the real realRobots() instance.

void setSensorPosition (const Eigen::Vector3d &pos)
 Sets the main robot position sensor (control+real) More...
 
void setSensorPosition (const std::string &robotName, const Eigen::Vector3d &pos)
 Sets a robot's position sensor (control+real) More...
 
void setSensorPositions (const std::map< std::string, Eigen::Vector3d > &poses)
 Set multiple body sensors' position for the main robot (control+real) More...
 
void setSensorPositions (const std::string &robotName, const std::map< std::string, Eigen::Vector3d > &poses)
 Set multiple body sensors' position for the specified robot (control+real) More...
 
void setSensorOrientation (const Eigen::Quaterniond &ori)
 Sets the main robot orientation sensor (control + real) More...
 
void setSensorOrientation (const std::string &robotName, const Eigen::Quaterniond &ori)
 Sets the main robot orientation sensor (control + real) More...
 
void setSensorOrientations (const QuaternionMap &oris)
 Set multiple body sensors' orientation for the main robot (control+real) More...
 
void setSensorOrientations (const std::string &robotName, const QuaternionMap &oris)
 Set multiple body sensors' orientation for the specified robot (control+real) More...
 
void setSensorLinearVelocity (const Eigen::Vector3d &vel)
 Sets the main robot linear velocity sensor (control+real) More...
 
void setSensorLinearVelocity (const std::string &robotName, const Eigen::Vector3d &vel)
 Sets the specified robot linear velocity sensor (control+real) More...
 
void setSensorLinearVelocities (const std::map< std::string, Eigen::Vector3d > &linearVels)
 Set multiple body sensor's linear velocities for the main robot (control+real) More...
 
void setSensorLinearVelocities (const std::string &robotName, const std::map< std::string, Eigen::Vector3d > &linearVels)
 Set multiple body sensor's linear velocities for the specified robot (control+real) More...
 
void setSensorAngularVelocity (const Eigen::Vector3d &vel)
 Sets the main robot angular velocity sensor (control+real) More...
 
void setSensorAngularVelocity (const std::string &robotName, const Eigen::Vector3d &vel)
 Sets the specified robot angular velocity sensor (control+real) More...
 
void setSensorAngularVelocities (const std::map< std::string, Eigen::Vector3d > &angularVels)
 Set multiple body sensor's angular velocities for the main robot (control + real) More...
 
void setSensorAngularVelocities (const std::string &robotName, const std::map< std::string, Eigen::Vector3d > &angularVels)
 Set multiple body sensor's angular velocities for the specified robot (control + real) More...
 
MC_RTC_DEPRECATED void setSensorAcceleration (const Eigen::Vector3d &acc)
 Sets the main robot acceleration (control+real) More...
 
MC_RTC_DEPRECATED void setSensorAccelerations (const std::map< std::string, Eigen::Vector3d > &accels)
 
void setSensorLinearAcceleration (const Eigen::Vector3d &acc)
 Sets the main robot linear acceleration (control+real) More...
 
void setSensorLinearAcceleration (const std::string &robotName, const Eigen::Vector3d &acc)
 Sets the specified robot linear acceleration (control+real) More...
 
void setSensorLinearAccelerations (const std::map< std::string, Eigen::Vector3d > &accels)
 Set multiple body sensors' linear acceleration for a given robot for the main robot (control+real) More...
 
void setSensorLinearAccelerations (const std::string &robotName, const std::map< std::string, Eigen::Vector3d > &accels)
 Set multiple body sensors' linear acceleration for a given robot for the specified robot (control+real) More...
 
void setSensorAngularAcceleration (const Eigen::Vector3d &acc)
 Sets the main robot angular acceleration (control+real) More...
 
void setSensorAngularAcceleration (const std::string &robotName, const Eigen::Vector3d &acc)
 Sets the specified robot angular acceleration (control+real) More...
 
void setSensorAngularAccelerations (const std::map< std::string, Eigen::Vector3d > &accels)
 Set multiple body sensors' angular acceleration for a given robot for the main robot (control+real) More...
 
void setSensorAngularAccelerations (const std::string &robotName, const std::map< std::string, Eigen::Vector3d > &accels)
 Set multiple body sensors' angular acceleration for the specifiedrobot (control+real) More...
 
void setEncoderValues (const std::vector< double > &eValues)
 Sets the main robot actual joints' values (control+real) More...
 
void setEncoderValues (const std::string &robotName, const std::vector< double > &eValues)
 
void setEncoderVelocities (const std::vector< double > &eVelocities)
 Sets the main robot's actual joint velocities (control+real) More...
 
void setEncoderVelocities (const std::string &robotName, const std::vector< double > &eVelocities)
 Sets the main robot position sensor (control+real) More...
 
void setJointTorques (const std::vector< double > &tValues)
 Sets the main robot's actual joint torques (control+real) More...
 
void setJointTorques (const std::string &robotName, const std::vector< double > &tValues)
 
void setWrenches (const std::map< std::string, sva::ForceVecd > &wrenches)
 Force sensors' readings provided by the sensors (sets control+real) More...
 
void setWrenches (const std::string &robotName, const std::map< std::string, sva::ForceVecd > &wrenches)
 Force sensors' readings for the specified robot (control + real) More...
 
MC_RTC_DEPRECATED void setWrenches (unsigned int robotIndex, const std::map< std::string, sva::ForceVecd > &wrenches)
 
void setJointMotorTemperature (const std::string &joint, double temperature)
 Motor temperature reading provided by the JointSensor for the main robot (sets control+real) More...
 
void setJointMotorTemperature (const std::string &robotName, const std::string &joint, double temperature)
 Motor temperature reading provided by the JointSensor for the specified robot (sets control+real) More...
 
void setJointMotorTemperatures (const std::map< std::string, double > &temperatures)
 Motor temperature readings provided by multiple JointSensors for the main robot (sets control+real) More...
 
void setJointMotorTemperatures (const std::string &robotName, const std::map< std::string, double > &temperatures)
 Motor temperature readings provided by multiple JointSensors for the specified robot (sets control+real) More...
 
void setJointDriverTemperature (const std::string &joint, double temperature)
 Driver temperature reading provided by the JointSensor for the main robot (sets control+real) More...
 
void setJointDriverTemperature (const std::string &robotName, const std::string &joint, double temperature)
 Driver temperature reading provided by the JointSensor for the specified robot (sets control+real) More...
 
void setJointDriverTemperatures (const std::map< std::string, double > &temperatures)
 Driver temperature readings provided by multiple JointSensors for the main robot (sets control+real) More...
 
void setJointDriverTemperatures (const std::string &robotName, const std::map< std::string, double > &temperatures)
 Driver temperature readings provided by multiple JointSensors for the specified robot (sets control+real) More...
 
void setJointMotorCurrent (const std::string &joint, double current)
 Motor current reading provided by the JointSensor for the main robot (sets control+real) More...
 
void setJointMotorCurrent (const std::string &robotName, const std::string &joint, double current)
 Motor current reading provided by the JointSensor for the specified robot (sets control+real) More...
 
void setJointMotorCurrents (const std::map< std::string, double > &currents)
 Motor current readings provided by multiple JointSensors for the main robot (sets control+real) More...
 
void setJointMotorCurrents (const std::string &robotName, const std::map< std::string, double > &currents)
 Motor current readings provided by multiple JointSensors for the specified robot (sets control+real) More...
 
void setJointMotorStatus (const std::string &joint, bool status)
 Motor status provided by the JointSensor for the main robot (sets control+real) More...
 
void setJointMotorStatus (const std::string &robotName, const std::string &joint, bool status)
 Motor status provided by the JointSensor for the specified robot (sets control+real) More...
 
void setJointMotorStatuses (const std::map< std::string, bool > &statuses)
 Motor status provided by multiple JointSensors for the main robot (sets control+real) More...
 
void setJointMotorStatuses (const std::string &robotName, const std::map< std::string, bool > &statuses)
 Motor status provided by multiple JointSensors for the specified robot (sets control+real) More...
 
Grippers

These functions can be used to manipulate the grippers through the global controller interface

void setGripperTargetQ (const std::string &robot, const std::string &name, const std::vector< double > &q)
 Set the opening target(s) for a given robot/gripper. More...
 
void setGripperOpenPercent (const std::string &robot, double pOpen)
 Set the gripper opening percentage for all grippers in a robot. More...
 
void setGripperOpenPercent (const std::string &robot, const std::string &name, double pOpen)
 Set the gripper opening percentage for a given robot/gripper. More...
 
Services

These functions acts as a proxy between the caller and the current controller.

bool GoToHalfSitPose_service ()
 Returns to half-sit pose after an experiment. More...
 
bool GoToHalfSitPose ()
 See mc_rtc::MCGlobalController::GoToHalfSitPose_service. More...
 

Public Attributes

bool running = false
 Returns true if the controller is running. More...
 

Protected Member Functions

Internal sensing helpers

These functions only set the sensor(s) for the provided robot reference. They are expected to be called twice: once for both the robot() and once for the corresponding realRobot() instances.

void setSensorPositions (mc_rbdyn::Robot &robot, const std::map< std::string, Eigen::Vector3d > &poses)
 Set multiple body sensors' position for a given robot. More...
 
void setSensorAngularAccelerations (mc_rbdyn::Robot &robot, const std::map< std::string, Eigen::Vector3d > &accels)
 Set multiple body sensors' angular acceleration for a given robot. More...
 
void setSensorLinearAccelerations (mc_rbdyn::Robot &robot, const std::map< std::string, Eigen::Vector3d > &accels)
 Set multiple body sensors' linear acceleration for a given robot. More...
 
MC_RTC_DEPRECATED void setSensorAccelerations (mc_rbdyn::Robot &robot, const std::map< std::string, Eigen::Vector3d > &accels)
 
void setSensorOrientations (mc_rbdyn::Robot &robot, const QuaternionMap &oris)
 Set multiple body sensors' orientation for a given robot. More...
 
void setSensorLinearVelocities (mc_rbdyn::Robot &robot, const std::map< std::string, Eigen::Vector3d > &linearVels)
 Set multiple body sensor's linear velocities for a given robot. More...
 
void setSensorAngularVelocities (mc_rbdyn::Robot &robot, const std::map< std::string, Eigen::Vector3d > &angularVels)
 Set multiple body sensor's angular velocities for a given robot. More...
 

Member Typedef Documentation

◆ QuaternionMap

using mc_control::MCGlobalController::QuaternionMap = std::map<std::string, Eigen::Quaterniond, std::less<std::string>, QuaternionMapAllocator>

◆ QuaternionMapAllocator

using mc_control::MCGlobalController::QuaternionMapAllocator = Eigen::aligned_allocator<std::pair<const std::string, Eigen::Quaterniond> >

Constructor & Destructor Documentation

◆ MCGlobalController() [1/2]

mc_control::MCGlobalController::MCGlobalController ( const std::string &  conf = "",
std::shared_ptr< mc_rbdyn::RobotModule rm = nullptr 
)

Create the global controller.

The global controller is in charge of handling incoming data (sensors, encoders...), passing it to the Controller instance and finally hand out the result to the simulation/robot.

An additional configuration file can be passed at construction but multiple configuration files are read by default:

  • a global configuration file read from INSTALL_PREFIX/etc/mc_rtc.conf
  • a global configuration file read from $HOME/.config/mc_rtc/mc_rtc.conf

The configuration provided overrides settings in the local configuration which overrides settings in the global configuration

Global settings include the controller timestep, the main robot, publication and logging options.

For each controller a specific setting file will be loaded from:

  • $CONTROLLER_INSTALL_PREFIX/etc/$CONTROLLER_NAME.conf
  • $HOME/.config/mc_rtc/controllers/$CONTROLLER_NAME.conf

Global settings found in controller-specific configuration files will be discarded.

Note
On Windows, user configuration files are retrieved from $APPDATA/mc_rtc
Parameters
confAdditional configuration to load

◆ MCGlobalController() [2/2]

mc_control::MCGlobalController::MCGlobalController ( const GlobalConfiguration conf)

Create the global controller with an existing GlobalConfiguration instance.

◆ ~MCGlobalController()

mc_control::MCGlobalController::~MCGlobalController ( )

Destructor.

Member Function Documentation

◆ add_controller_module_paths()

void mc_control::MCGlobalController::add_controller_module_paths ( const std::vector< std::string > &  paths)

Add the given directories to the controller search path.

Calling this function with the same arguments multiple times effectively refresh the loaded controller list

e.g. the following code will rescan all directories

add_controller_module_paths(configuration().controller_module_paths));

◆ AddController() [1/2]

bool mc_control::MCGlobalController::AddController ( const std::string &  name)

Add a controller to the enabled list.

This call enables a controller that was not enabled but loaded. If the provided name does not exist then it does nothing and returns false. Otherwise, the controller is created, added to the enabled map and the function returns true.

Parameters
nameName of the controller to add

◆ AddController() [2/2]

bool mc_control::MCGlobalController::AddController ( const std::string &  name,
std::shared_ptr< mc_control::MCController controller 
)

Add an already created controller to the enabled list.

This call adds a controller that was created through another mean than MCGlobalController internal mechanism.

The function returns false and does nothing if name is already among the enabled controllers or if controller is a null pointer.

Parameters
nameName of the controller to add
controllerController to add

◆ configuration()

const GlobalConfiguration& mc_control::MCGlobalController::configuration ( ) const

Access the global controller configuration.

◆ controller() [1/2]

const MCController& mc_control::MCGlobalController::controller ( ) const
inlinenoexcept

Const access to current controller.

◆ controller() [2/2]

MCController& mc_control::MCGlobalController::controller ( )
inlinenoexcept

Access the current controller.

◆ current_controller()

std::string mc_control::MCGlobalController::current_controller ( ) const

Returns the name of the current controller.

◆ EnableController()

bool mc_control::MCGlobalController::EnableController ( const std::string &  name)

Switch to the requested controller.

If the requested controller is not enabled, does not exist or is already running then this call has no effect. Otherwise, it will trigger a controller switch at the next run call.

Parameters
nameName of the new controller to load

◆ enabled_controllers()

std::vector<std::string> mc_control::MCGlobalController::enabled_controllers ( ) const

Returns a list of enabled controllers.

◆ get_robot_module()

std::shared_ptr<mc_rbdyn::RobotModule> mc_control::MCGlobalController::get_robot_module ( )

Returns the main robot module.

◆ GoToHalfSitPose()

bool mc_control::MCGlobalController::GoToHalfSitPose ( )

See mc_rtc::MCGlobalController::GoToHalfSitPose_service.

◆ GoToHalfSitPose_service()

bool mc_control::MCGlobalController::GoToHalfSitPose_service ( )

Returns to half-sit pose after an experiment.

This service enables the HalfSitPose controller which only drives the robot back to half-sitting posture while avoiding auto-collisions

◆ init() [1/4]

void mc_control::MCGlobalController::init ( const std::map< std::string, std::vector< double >> &  initqs = {},
const std::map< std::string, sva::PTransformd > &  initAttitudes = {} 
)

Initialize multiple robots to the given configuration and attitude.

If some robots' configuration or position is not provided then the robot module data is used to initialize the robot.

Parameters
initqsInitial joints configuration for each robot, for each robot this data is expected in the corresponding ref_joint_order
initAttitudesInitial world position for each robot

◆ init() [2/4]

void mc_control::MCGlobalController::init ( const std::vector< double > &  initq)

Initialize the default controller with the given configuration.

  • The initial joint configuration provided as the initq argument.
  • The initial floating base attitude is set from body sensors or the robot module depending on your controller's configuration (default: robot module)
InitAttitudeFromSensor: true,
InitAttitudeSensor: FloatingBase
Parameters
initqinitial joints configuration
Note
When implementing an interface, the sensors must be set prior to calling this method.
Exceptions
logical_exceptionif the bodysensor does not exist or the joint configuration does not have the same size as the reference joint order

◆ init() [3/4]

void mc_control::MCGlobalController::init ( const std::vector< double > &  initq,
const std::array< double, 7 > &  initAttitude 
)

Initialize robot attitude from encoders and the floating base attitude.

Parameters
initqInitial joints configuration
initAttitudeAttitude of the floating base provided as a quaternion [qw, qx, qy, qz, tx, ty, tz]

◆ init() [4/4]

void mc_control::MCGlobalController::init ( const std::vector< double > &  initq,
const sva::PTransformd &  initAttitude 
)

Initialize robot attitude from encoders and the floating base attitude.

Parameters
initqInitial joints configuration
initAttitudeAttitude of the floating base

◆ loaded_controllers()

std::vector<std::string> mc_control::MCGlobalController::loaded_controllers ( ) const

Returns a list of all the loaded controllers, whether they are enabled or not.

◆ loaded_robots()

std::vector<std::string> mc_control::MCGlobalController::loaded_robots ( ) const

Returns a list of all the loaded robots, whether they are enabled or not.

◆ ref_joint_order()

const std::vector<std::string>& mc_control::MCGlobalController::ref_joint_order ( )

Access the reference joint order.

This is provided by mc_rbdyn::RobotModule and represents the joint's order in the native control system of the robot.

◆ refreshLog()

void mc_control::MCGlobalController::refreshLog ( )

Create a new log file for the current controller.

The purpose is to split the log file for long-running controller, therefore this does not restart the timer of the controller so multiple log files could be stitched together.

◆ reset()

void mc_control::MCGlobalController::reset ( const std::map< std::string, std::vector< double >> &  resetqs = {},
const std::map< std::string, sva::PTransformd > &  resetAttitudes = {} 
)

Fully reset the current controller to the given initial state.

This deletes then re-create the current controller so that it is started from scratch.

If some robots' configuration or position is not provided then the robot module data is used to initialize the robot.

Parameters
initqsInitial joints configuration for each robot, for each robot this data is expected in the corresponding ref_joint_order
initAttitudesInitial world position for each robot

◆ run()

bool mc_control::MCGlobalController::run ( )

Runs one step of the controller.

Returns
True if the current controller succeeded, false otherwise

◆ server()

ControllerServer& mc_control::MCGlobalController::server ( )

Access the server.

◆ setEncoderValues() [1/2]

void mc_control::MCGlobalController::setEncoderValues ( const std::string &  robotName,
const std::vector< double > &  eValues 
)

Set actual joint values for the specified robot (control + real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
eValuesActual joint values provided by encoders
Exceptions
Ifthe specified robot does not exist

◆ setEncoderValues() [2/2]

void mc_control::MCGlobalController::setEncoderValues ( const std::vector< double > &  eValues)

Sets the main robot actual joints' values (control+real)

Parameters
eValuesActual joint values provided by encoders
Note
It is expected that these values follow the order given by ref_joint_order

◆ setEncoderVelocities() [1/2]

void mc_control::MCGlobalController::setEncoderVelocities ( const std::string &  robotName,
const std::vector< double > &  eVelocities 
)

Sets the main robot position sensor (control+real)

Parameters
posPosition given by a sensor
Exceptions
Ifthe robot does not have any body sensor

◆ setEncoderVelocities() [2/2]

void mc_control::MCGlobalController::setEncoderVelocities ( const std::vector< double > &  eVelocities)

Sets the main robot's actual joint velocities (control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
eVelocitiesActual joint velocities
Note
It is expected that these values follow the order given by ref_joint_order

◆ setGripperOpenPercent() [1/2]

void mc_control::MCGlobalController::setGripperOpenPercent ( const std::string &  robot,
const std::string &  name,
double  pOpen 
)

Set the gripper opening percentage for a given robot/gripper.

Parameters
robotName of the robot
nameName of the gripper
pOpenOpening percentage (0: closed, 1: open)

◆ setGripperOpenPercent() [2/2]

void mc_control::MCGlobalController::setGripperOpenPercent ( const std::string &  robot,
double  pOpen 
)

Set the gripper opening percentage for all grippers in a robot.

Parameters
robotName of the robot
pOpenOpening percentage (0: closed, 1: open)

◆ setGripperTargetQ()

void mc_control::MCGlobalController::setGripperTargetQ ( const std::string &  robot,
const std::string &  name,
const std::vector< double > &  q 
)

Set the opening target(s) for a given robot/gripper.

Parameters
robotName of the robot
nameName of the gripper
qActive joints values

◆ setJointDriverTemperature() [1/2]

void mc_control::MCGlobalController::setJointDriverTemperature ( const std::string &  joint,
double  temperature 
)

Driver temperature reading provided by the JointSensor for the main robot (sets control+real)

Parameters
jointname of the joint to which sensor is attached
temperaturedriver temperature reading in Celcius
Exceptions
Ifthe robot does not have any JointSensor at joint

◆ setJointDriverTemperature() [2/2]

void mc_control::MCGlobalController::setJointDriverTemperature ( const std::string &  robotName,
const std::string &  joint,
double  temperature 
)

Driver temperature reading provided by the JointSensor for the specified robot (sets control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
jointname of the joint to which sensor is attached
temperaturedriver temperature reading in Celcius
Exceptions
Ifthe robot does not have any JointSensor at joint
Ifthe specified robot does not exist

◆ setJointDriverTemperatures() [1/2]

void mc_control::MCGlobalController::setJointDriverTemperatures ( const std::map< std::string, double > &  temperatures)

Driver temperature readings provided by multiple JointSensors for the main robot (sets control+real)

Parameters
temperaturesmap of joint name to driver temperature in Celcius
Exceptions
Ifany of the joint sensors do not exist

◆ setJointDriverTemperatures() [2/2]

void mc_control::MCGlobalController::setJointDriverTemperatures ( const std::string &  robotName,
const std::map< std::string, double > &  temperatures 
)

Driver temperature readings provided by multiple JointSensors for the specified robot (sets control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
temperaturesmap of joint name to driver temperature in Celcius
Exceptions
Ifany of the joint sensors do not exist
Ifthe specified robot does not exist

◆ setJointMotorCurrent() [1/2]

void mc_control::MCGlobalController::setJointMotorCurrent ( const std::string &  joint,
double  current 
)

Motor current reading provided by the JointSensor for the main robot (sets control+real)

Parameters
jointname of the joint to which sensor is attached
currentmotor current reading in Amperes
Exceptions
Ifthe robot does not have any JointSensor at joint

◆ setJointMotorCurrent() [2/2]

void mc_control::MCGlobalController::setJointMotorCurrent ( const std::string &  robotName,
const std::string &  joint,
double  current 
)

Motor current reading provided by the JointSensor for the specified robot (sets control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
jointname of the joint to which sensor is attached
currentmotor current reading in Amperes
Exceptions
Ifthe robot does not have any JointSensor at joint
Ifthe specified robot does not exist

◆ setJointMotorCurrents() [1/2]

void mc_control::MCGlobalController::setJointMotorCurrents ( const std::map< std::string, double > &  currents)

Motor current readings provided by multiple JointSensors for the main robot (sets control+real)

Parameters
currentsmap of joint name to motor current in Amperes
Exceptions
Ifany of the joint sensors do not exist

◆ setJointMotorCurrents() [2/2]

void mc_control::MCGlobalController::setJointMotorCurrents ( const std::string &  robotName,
const std::map< std::string, double > &  currents 
)

Motor current readings provided by multiple JointSensors for the specified robot (sets control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
currentsmap of joint name to motor current in Amperes
Exceptions
Ifany of the joint sensors do not exist
Ifthe specified robot does not exist

◆ setJointMotorStatus() [1/2]

void mc_control::MCGlobalController::setJointMotorStatus ( const std::string &  joint,
bool  status 
)

Motor status provided by the JointSensor for the main robot (sets control+real)

Parameters
jointname of the joint to which sensor is attached
statusmotor ON/OFF status
Exceptions
Ifthe robot does not have any JointSensor at joint

◆ setJointMotorStatus() [2/2]

void mc_control::MCGlobalController::setJointMotorStatus ( const std::string &  robotName,
const std::string &  joint,
bool  status 
)

Motor status provided by the JointSensor for the specified robot (sets control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
jointname of the joint to which sensor is attached
statusmotor ON/OFF status
Exceptions
Ifthe robot does not have any JointSensor at joint
Ifthe specified robot does not exist

◆ setJointMotorStatuses() [1/2]

void mc_control::MCGlobalController::setJointMotorStatuses ( const std::map< std::string, bool > &  statuses)

Motor status provided by multiple JointSensors for the main robot (sets control+real)

Parameters
statusesmap of joint name to motor status
Exceptions
Ifany of the joint sensors do not exist

◆ setJointMotorStatuses() [2/2]

void mc_control::MCGlobalController::setJointMotorStatuses ( const std::string &  robotName,
const std::map< std::string, bool > &  statuses 
)

Motor status provided by multiple JointSensors for the specified robot (sets control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
statusesmap of joint name to motor status
Exceptions
Ifany of the joint sensors do not exist
Ifthe specified robot does not exist

◆ setJointMotorTemperature() [1/2]

void mc_control::MCGlobalController::setJointMotorTemperature ( const std::string &  joint,
double  temperature 
)

Motor temperature reading provided by the JointSensor for the main robot (sets control+real)

Parameters
jointname of the joint to which sensor is attached
temperaturemotor temperature reading in Celcius
Exceptions
Ifthe robot does not have any JointSensor at joint

◆ setJointMotorTemperature() [2/2]

void mc_control::MCGlobalController::setJointMotorTemperature ( const std::string &  robotName,
const std::string &  joint,
double  temperature 
)

Motor temperature reading provided by the JointSensor for the specified robot (sets control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
jointname of the joint to which sensor is attached
temperaturemotor temperature reading in Celcius
Exceptions
Ifthe robot does not have any JointSensor at joint
Ifthe specified robot does not exist

◆ setJointMotorTemperatures() [1/2]

void mc_control::MCGlobalController::setJointMotorTemperatures ( const std::map< std::string, double > &  temperatures)

Motor temperature readings provided by multiple JointSensors for the main robot (sets control+real)

Parameters
temperaturesmap of joint name to motor temperature in Celcius
Exceptions
Ifany of the joint sensors do not exist

◆ setJointMotorTemperatures() [2/2]

void mc_control::MCGlobalController::setJointMotorTemperatures ( const std::string &  robotName,
const std::map< std::string, double > &  temperatures 
)

Motor temperature readings provided by multiple JointSensors for the specified robot (sets control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
temperaturesmap of joint name to motor temperature in Celcius
Exceptions
Ifany of the joint sensors do not exist
Ifthe specified robot does not exist

◆ setJointTorques() [1/2]

void mc_control::MCGlobalController::setJointTorques ( const std::string &  robotName,
const std::vector< double > &  tValues 
)

Set the acutal joint torques for the specified robot (control + real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
tValuesActual joint torques (provided by sensors)
Exceptions
Ifthe specified robot does not exist

◆ setJointTorques() [2/2]

void mc_control::MCGlobalController::setJointTorques ( const std::vector< double > &  tValues)

Sets the main robot's actual joint torques (control+real)

Parameters
tValuesActual joint torques (provided by sensors)
Note
It is expected that these values follow the order given by ref_joint_order

◆ setSensorAcceleration()

MC_RTC_DEPRECATED void mc_control::MCGlobalController::setSensorAcceleration ( const Eigen::Vector3d &  acc)

Sets the main robot acceleration (control+real)

Deprecated:
in favor of setSensorLinearAcceleration(const Eigen::Vector3d &);

◆ setSensorAccelerations() [1/2]

MC_RTC_DEPRECATED void mc_control::MCGlobalController::setSensorAccelerations ( const std::map< std::string, Eigen::Vector3d > &  accels)

◆ setSensorAccelerations() [2/2]

MC_RTC_DEPRECATED void mc_control::MCGlobalController::setSensorAccelerations ( mc_rbdyn::Robot robot,
const std::map< std::string, Eigen::Vector3d > &  accels 
)
protected
Deprecated:
in favor of void setSensorLinearAccelerations(mc_rbdyn::Robot & robot, const std::map<std::string, Eigen::Vector3d> &);

◆ setSensorAngularAcceleration() [1/2]

void mc_control::MCGlobalController::setSensorAngularAcceleration ( const Eigen::Vector3d &  acc)

Sets the main robot angular acceleration (control+real)

Parameters
accAngular acceleration given by a sensor
Exceptions
Ifthe robot does not have any body sensor

◆ setSensorAngularAcceleration() [2/2]

void mc_control::MCGlobalController::setSensorAngularAcceleration ( const std::string &  robotName,
const Eigen::Vector3d &  acc 
)

Sets the specified robot angular acceleration (control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
accAngular acceleration
Exceptions
Ifthe specified robot does not exist
Ifthe robot does not have any body sensor

◆ setSensorAngularAccelerations() [1/3]

void mc_control::MCGlobalController::setSensorAngularAccelerations ( const std::map< std::string, Eigen::Vector3d > &  accels)

Set multiple body sensors' angular acceleration for a given robot for the main robot (control+real)

Parameters
accelsMap of body sensor names to linear accelerations
Exceptions
Ifany of the body sensors do not exist in the robot

◆ setSensorAngularAccelerations() [2/3]

void mc_control::MCGlobalController::setSensorAngularAccelerations ( const std::string &  robotName,
const std::map< std::string, Eigen::Vector3d > &  accels 
)

Set multiple body sensors' angular acceleration for the specifiedrobot (control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
accelsMap of body sensor names to linear accelerations
Exceptions
Ifthe specified robot does not exist
Ifany of the body sensors do not exist in the robot

◆ setSensorAngularAccelerations() [3/3]

void mc_control::MCGlobalController::setSensorAngularAccelerations ( mc_rbdyn::Robot robot,
const std::map< std::string, Eigen::Vector3d > &  accels 
)
protected

Set multiple body sensors' angular acceleration for a given robot.

◆ setSensorAngularVelocities() [1/3]

void mc_control::MCGlobalController::setSensorAngularVelocities ( const std::map< std::string, Eigen::Vector3d > &  angularVels)

Set multiple body sensor's angular velocities for the main robot (control + real)

Parameters
angularVelsmap of body sensor name to angular velocity
Exceptions
Ifany of the body sensors do not exist in the robot

◆ setSensorAngularVelocities() [2/3]

void mc_control::MCGlobalController::setSensorAngularVelocities ( const std::string &  robotName,
const std::map< std::string, Eigen::Vector3d > &  angularVels 
)

Set multiple body sensor's angular velocities for the specified robot (control + real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
angularVelsmap of body sensor name to angular velocity
Exceptions
Ifthe specified robot does not exist
Ifany of the body sensors do not exist in the robot

◆ setSensorAngularVelocities() [3/3]

void mc_control::MCGlobalController::setSensorAngularVelocities ( mc_rbdyn::Robot robot,
const std::map< std::string, Eigen::Vector3d > &  angularVels 
)
protected

Set multiple body sensor's angular velocities for a given robot.

◆ setSensorAngularVelocity() [1/2]

void mc_control::MCGlobalController::setSensorAngularVelocity ( const Eigen::Vector3d &  vel)

Sets the main robot angular velocity sensor (control+real)

Parameters
velAngular velocity given by a sensor
Exceptions
Ifthe robot does not have any body sensor

◆ setSensorAngularVelocity() [2/2]

void mc_control::MCGlobalController::setSensorAngularVelocity ( const std::string &  robotName,
const Eigen::Vector3d &  vel 
)

Sets the specified robot angular velocity sensor (control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
velAngular velocity given by a sensor
Exceptions
Ifthe specified robot does not exist
Ifthe robot does not have any body sensor

◆ setSensorLinearAcceleration() [1/2]

void mc_control::MCGlobalController::setSensorLinearAcceleration ( const Eigen::Vector3d &  acc)

Sets the main robot linear acceleration (control+real)

Parameters
accLinear acceleration given by a sensor

◆ setSensorLinearAcceleration() [2/2]

void mc_control::MCGlobalController::setSensorLinearAcceleration ( const std::string &  robotName,
const Eigen::Vector3d &  acc 
)

Sets the specified robot linear acceleration (control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
accLinear acceleration
Exceptions
Ifthe specified robot does not exist
Ifthe robot does not have any body sensor

◆ setSensorLinearAccelerations() [1/3]

void mc_control::MCGlobalController::setSensorLinearAccelerations ( const std::map< std::string, Eigen::Vector3d > &  accels)

Set multiple body sensors' linear acceleration for a given robot for the main robot (control+real)

Parameters
accelsMap of body sensor names to linear accelerations
Exceptions
Ifany of the body sensors do not exist in the robot

◆ setSensorLinearAccelerations() [2/3]

void mc_control::MCGlobalController::setSensorLinearAccelerations ( const std::string &  robotName,
const std::map< std::string, Eigen::Vector3d > &  accels 
)

Set multiple body sensors' linear acceleration for a given robot for the specified robot (control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
accelsMap of body sensor names to linear accelerations
Exceptions
Ifthe specified robot does not exist
Ifany of the body sensors do not exist in the robot

◆ setSensorLinearAccelerations() [3/3]

void mc_control::MCGlobalController::setSensorLinearAccelerations ( mc_rbdyn::Robot robot,
const std::map< std::string, Eigen::Vector3d > &  accels 
)
protected

Set multiple body sensors' linear acceleration for a given robot.

◆ setSensorLinearVelocities() [1/3]

void mc_control::MCGlobalController::setSensorLinearVelocities ( const std::map< std::string, Eigen::Vector3d > &  linearVels)

Set multiple body sensor's linear velocities for the main robot (control+real)

Parameters
linearVelsmap of BodySensor name to the corresponding velocity
Exceptions
Ifany of the body sensors do not exist in the robot

◆ setSensorLinearVelocities() [2/3]

void mc_control::MCGlobalController::setSensorLinearVelocities ( const std::string &  robotName,
const std::map< std::string, Eigen::Vector3d > &  linearVels 
)

Set multiple body sensor's linear velocities for the specified robot (control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
linearVelsmap of BodySensor name to the corresponding velocity
Exceptions
Ifthe specified robot does not exist
Ifany of the body sensors do not exist in the robot

◆ setSensorLinearVelocities() [3/3]

void mc_control::MCGlobalController::setSensorLinearVelocities ( mc_rbdyn::Robot robot,
const std::map< std::string, Eigen::Vector3d > &  linearVels 
)
protected

Set multiple body sensor's linear velocities for a given robot.

◆ setSensorLinearVelocity() [1/2]

void mc_control::MCGlobalController::setSensorLinearVelocity ( const Eigen::Vector3d &  vel)

Sets the main robot linear velocity sensor (control+real)

Parameters
velLinear velocity given by a sensor
Exceptions
Ifthe robot does not have any body sensor

◆ setSensorLinearVelocity() [2/2]

void mc_control::MCGlobalController::setSensorLinearVelocity ( const std::string &  robotName,
const Eigen::Vector3d &  vel 
)

Sets the specified robot linear velocity sensor (control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
velLinear velocity given by a sensor
Exceptions
Ifthe specified robot does not exist
Ifthe robot does not have any body sensor

◆ setSensorOrientation() [1/2]

void mc_control::MCGlobalController::setSensorOrientation ( const Eigen::Quaterniond &  ori)

Sets the main robot orientation sensor (control + real)

Parameters
oriOrientation given by a sensor
Note
By convention, this rotation should be given from the inertial frame (i.e. a fixed frame in the real world) to a sensor frame of the robot.
Exceptions
Ifthe robot does not have any body sensor

◆ setSensorOrientation() [2/2]

void mc_control::MCGlobalController::setSensorOrientation ( const std::string &  robotName,
const Eigen::Quaterniond &  ori 
)

Sets the main robot orientation sensor (control + real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
Exceptions
Ifthe specified robot does not exist
Ifthe robot does not have any body sensor
See also
setSensorOrientation(const Eigen::Quaterniond & ori)

◆ setSensorOrientations() [1/3]

void mc_control::MCGlobalController::setSensorOrientations ( const QuaternionMap oris)

Set multiple body sensors' orientation for the main robot (control+real)

Parameters
orisMap of sensor name -> orientation
Exceptions
Ifany of the sensors does not exist in the robot
See also
setSensorOrientation(const Eigen::Quaterniond & ori)

◆ setSensorOrientations() [2/3]

void mc_control::MCGlobalController::setSensorOrientations ( const std::string &  robotName,
const QuaternionMap oris 
)

Set multiple body sensors' orientation for the specified robot (control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
Exceptions
Ifthe specified robot does not exist
Ifany of the sensors does not exist in the robot
See also
setSensorOrientation(const Eigen::Quaterniond & ori)

◆ setSensorOrientations() [3/3]

void mc_control::MCGlobalController::setSensorOrientations ( mc_rbdyn::Robot robot,
const QuaternionMap oris 
)
protected

Set multiple body sensors' orientation for a given robot.

◆ setSensorPosition() [1/2]

void mc_control::MCGlobalController::setSensorPosition ( const Eigen::Vector3d &  pos)

Sets the main robot position sensor (control+real)

Parameters
posPosition given by a sensor
Exceptions
Ifthe robot does not have any body sensor

◆ setSensorPosition() [2/2]

void mc_control::MCGlobalController::setSensorPosition ( const std::string &  robotName,
const Eigen::Vector3d &  pos 
)

Sets a robot's position sensor (control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
posPosition given by a sensor
Exceptions
Ifthe robot does not have any body sensor
Ifthe specified robot does not exist

◆ setSensorPositions() [1/3]

void mc_control::MCGlobalController::setSensorPositions ( const std::map< std::string, Eigen::Vector3d > &  poses)

Set multiple body sensors' position for the main robot (control+real)

Parameters
posesMap of sensor name -> position
Exceptions
Ifone of the sensors does not exist in the robot

◆ setSensorPositions() [2/3]

void mc_control::MCGlobalController::setSensorPositions ( const std::string &  robotName,
const std::map< std::string, Eigen::Vector3d > &  poses 
)

Set multiple body sensors' position for the specified robot (control+real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
posesMap of sensor name -> position
Exceptions
Ifany of the sensors does not exist in the robot
Ifthe specified robot does not exist

◆ setSensorPositions() [3/3]

void mc_control::MCGlobalController::setSensorPositions ( mc_rbdyn::Robot robot,
const std::map< std::string, Eigen::Vector3d > &  poses 
)
protected

Set multiple body sensors' position for a given robot.

◆ setWrenches() [1/3]

void mc_control::MCGlobalController::setWrenches ( const std::map< std::string, sva::ForceVecd > &  wrenches)

Force sensors' readings provided by the sensors (sets control+real)

Parameters
wrenchesmap of force sensor name to wrenches
Exceptions
ifany of the force sensors do not exist

◆ setWrenches() [2/3]

void mc_control::MCGlobalController::setWrenches ( const std::string &  robotName,
const std::map< std::string, sva::ForceVecd > &  wrenches 
)

Force sensors' readings for the specified robot (control + real)

Parameters
robotNameName of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances.
wrenchesmap of force sensor name to wrenches
Exceptions
Ifthe specified robot does not exist
ifany of the force sensors do not exist

◆ setWrenches() [3/3]

MC_RTC_DEPRECATED void mc_control::MCGlobalController::setWrenches ( unsigned int  robotIndex,
const std::map< std::string, sva::ForceVecd > &  wrenches 
)

◆ timestep()

double mc_control::MCGlobalController::timestep ( ) const

Get the controller timestep.

Member Data Documentation

◆ running

bool mc_control::MCGlobalController::running = false

Returns true if the controller is running.

To prevent any serious issues, the controller will stop when the underlying MCController instance fails to run


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