#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::RobotModule > | get_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... | |
ControllerServer & | server () |
Access the server. More... | |
MCController & | controller () noexcept |
Access the current controller. More... | |
const MCController & | controller () 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 GlobalConfiguration & | configuration () 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 > ¤ts) |
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 > ¤ts) |
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... | |
using mc_control::MCGlobalController::QuaternionMap = std::map<std::string, Eigen::Quaterniond, std::less<std::string>, QuaternionMapAllocator> |
using mc_control::MCGlobalController::QuaternionMapAllocator = Eigen::aligned_allocator<std::pair<const std::string, Eigen::Quaterniond> > |
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:
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:
Global settings found in controller-specific configuration files will be discarded.
conf | Additional configuration to load |
mc_control::MCGlobalController::MCGlobalController | ( | const GlobalConfiguration & | conf | ) |
Create the global controller with an existing GlobalConfiguration instance.
mc_control::MCGlobalController::~MCGlobalController | ( | ) |
Destructor.
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));
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.
name | Name of the controller to add |
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.
name | Name of the controller to add |
controller | Controller to add |
const GlobalConfiguration& mc_control::MCGlobalController::configuration | ( | ) | const |
Access the global controller configuration.
|
inlinenoexcept |
Const access to current controller.
|
inlinenoexcept |
Access the current controller.
std::string mc_control::MCGlobalController::current_controller | ( | ) | const |
Returns the name of the current controller.
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.
name | Name of the new controller to load |
std::vector<std::string> mc_control::MCGlobalController::enabled_controllers | ( | ) | const |
Returns a list of enabled controllers.
std::shared_ptr<mc_rbdyn::RobotModule> mc_control::MCGlobalController::get_robot_module | ( | ) |
Returns the main robot module.
bool mc_control::MCGlobalController::GoToHalfSitPose | ( | ) |
See mc_rtc::MCGlobalController::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
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.
initqs | Initial joints configuration for each robot, for each robot this data is expected in the corresponding ref_joint_order |
initAttitudes | Initial world position for each robot |
void mc_control::MCGlobalController::init | ( | const std::vector< double > & | initq | ) |
Initialize the default controller with the given configuration.
initq | initial joints configuration |
logical_exception | if the bodysensor does not exist or the joint configuration does not have the same size as the reference joint order |
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.
initq | Initial joints configuration |
initAttitude | Attitude of the floating base provided as a quaternion [qw, qx, qy, qz, tx, ty, tz] |
void mc_control::MCGlobalController::init | ( | const std::vector< double > & | initq, |
const sva::PTransformd & | initAttitude | ||
) |
Initialize robot attitude from encoders and the floating base attitude.
initq | Initial joints configuration |
initAttitude | Attitude of the floating base |
std::vector<std::string> mc_control::MCGlobalController::loaded_controllers | ( | ) | const |
Returns a list of all the loaded controllers, whether they are enabled or not.
std::vector<std::string> mc_control::MCGlobalController::loaded_robots | ( | ) | const |
Returns a list of all the loaded robots, whether they are enabled or not.
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.
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.
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.
initqs | Initial joints configuration for each robot, for each robot this data is expected in the corresponding ref_joint_order |
initAttitudes | Initial world position for each robot |
bool mc_control::MCGlobalController::run | ( | ) |
Runs one step of the controller.
ControllerServer& mc_control::MCGlobalController::server | ( | ) |
Access the server.
void mc_control::MCGlobalController::setEncoderValues | ( | const std::string & | robotName, |
const std::vector< double > & | eValues | ||
) |
Set actual joint values for the specified robot (control + real)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
eValues | Actual joint values provided by encoders |
If | the specified robot does not exist |
void mc_control::MCGlobalController::setEncoderValues | ( | const std::vector< double > & | eValues | ) |
Sets the main robot actual joints' values (control+real)
eValues | Actual joint values provided by encoders |
void mc_control::MCGlobalController::setEncoderVelocities | ( | const std::string & | robotName, |
const std::vector< double > & | eVelocities | ||
) |
Sets the main robot position sensor (control+real)
pos | Position given by a sensor |
If | the robot does not have any body sensor |
void mc_control::MCGlobalController::setEncoderVelocities | ( | const std::vector< double > & | eVelocities | ) |
Sets the main robot's actual joint velocities (control+real)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
eVelocities | Actual joint velocities |
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.
robot | Name of the robot |
name | Name of the gripper |
pOpen | Opening percentage (0: closed, 1: open) |
void mc_control::MCGlobalController::setGripperOpenPercent | ( | const std::string & | robot, |
double | pOpen | ||
) |
Set the gripper opening percentage for all grippers in a robot.
robot | Name of the robot |
pOpen | Opening percentage (0: closed, 1: open) |
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.
robot | Name of the robot |
name | Name of the gripper |
q | Active joints values |
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)
joint | name of the joint to which sensor is attached |
temperature | driver temperature reading in Celcius |
If | the robot does not have any JointSensor at joint |
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)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
joint | name of the joint to which sensor is attached |
temperature | driver temperature reading in Celcius |
If | the robot does not have any JointSensor at joint |
If | the specified robot does not exist |
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)
temperatures | map of joint name to driver temperature in Celcius |
If | any of the joint sensors do not exist |
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)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
temperatures | map of joint name to driver temperature in Celcius |
If | any of the joint sensors do not exist |
If | the specified robot does not exist |
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)
joint | name of the joint to which sensor is attached |
current | motor current reading in Amperes |
If | the robot does not have any JointSensor at joint |
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)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
joint | name of the joint to which sensor is attached |
current | motor current reading in Amperes |
If | the robot does not have any JointSensor at joint |
If | the specified robot does not exist |
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)
currents | map of joint name to motor current in Amperes |
If | any of the joint sensors do not exist |
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)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
currents | map of joint name to motor current in Amperes |
If | any of the joint sensors do not exist |
If | the specified robot does not exist |
void mc_control::MCGlobalController::setJointMotorStatus | ( | const std::string & | joint, |
bool | status | ||
) |
Motor status provided by the JointSensor for the main robot (sets control+real)
joint | name of the joint to which sensor is attached |
status | motor ON/OFF status |
If | the robot does not have any JointSensor at joint |
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)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
joint | name of the joint to which sensor is attached |
status | motor ON/OFF status |
If | the robot does not have any JointSensor at joint |
If | the specified robot does not exist |
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)
statuses | map of joint name to motor status |
If | any of the joint sensors do not exist |
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)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
statuses | map of joint name to motor status |
If | any of the joint sensors do not exist |
If | the specified robot does not exist |
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)
joint | name of the joint to which sensor is attached |
temperature | motor temperature reading in Celcius |
If | the robot does not have any JointSensor at joint |
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)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
joint | name of the joint to which sensor is attached |
temperature | motor temperature reading in Celcius |
If | the robot does not have any JointSensor at joint |
If | the specified robot does not exist |
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)
temperatures | map of joint name to motor temperature in Celcius |
If | any of the joint sensors do not exist |
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)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
temperatures | map of joint name to motor temperature in Celcius |
If | any of the joint sensors do not exist |
If | the specified robot does not exist |
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)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
tValues | Actual joint torques (provided by sensors) |
If | the specified robot does not exist |
void mc_control::MCGlobalController::setJointTorques | ( | const std::vector< double > & | tValues | ) |
Sets the main robot's actual joint torques (control+real)
tValues | Actual joint torques (provided by sensors) |
MC_RTC_DEPRECATED void mc_control::MCGlobalController::setSensorAcceleration | ( | const Eigen::Vector3d & | acc | ) |
Sets the main robot acceleration (control+real)
MC_RTC_DEPRECATED void mc_control::MCGlobalController::setSensorAccelerations | ( | const std::map< std::string, Eigen::Vector3d > & | accels | ) |
|
protected |
void mc_control::MCGlobalController::setSensorAngularAcceleration | ( | const Eigen::Vector3d & | acc | ) |
Sets the main robot angular acceleration (control+real)
acc | Angular acceleration given by a sensor |
If | the robot does not have any body sensor |
void mc_control::MCGlobalController::setSensorAngularAcceleration | ( | const std::string & | robotName, |
const Eigen::Vector3d & | acc | ||
) |
Sets the specified robot angular acceleration (control+real)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
acc | Angular acceleration |
If | the specified robot does not exist |
If | the robot does not have any body sensor |
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)
accels | Map of body sensor names to linear accelerations |
If | any of the body sensors do not exist in the robot |
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)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
accels | Map of body sensor names to linear accelerations |
If | the specified robot does not exist |
If | any of the body sensors do not exist in the robot |
|
protected |
Set multiple body sensors' angular acceleration for a given robot.
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)
angularVels | map of body sensor name to angular velocity |
If | any of the body sensors do not exist in the robot |
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)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
angularVels | map of body sensor name to angular velocity |
If | the specified robot does not exist |
If | any of the body sensors do not exist in the robot |
|
protected |
Set multiple body sensor's angular velocities for a given robot.
void mc_control::MCGlobalController::setSensorAngularVelocity | ( | const Eigen::Vector3d & | vel | ) |
Sets the main robot angular velocity sensor (control+real)
vel | Angular velocity given by a sensor |
If | the robot does not have any body sensor |
void mc_control::MCGlobalController::setSensorAngularVelocity | ( | const std::string & | robotName, |
const Eigen::Vector3d & | vel | ||
) |
Sets the specified robot angular velocity sensor (control+real)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
vel | Angular velocity given by a sensor |
If | the specified robot does not exist |
If | the robot does not have any body sensor |
void mc_control::MCGlobalController::setSensorLinearAcceleration | ( | const Eigen::Vector3d & | acc | ) |
Sets the main robot linear acceleration (control+real)
acc | Linear acceleration given by a sensor |
void mc_control::MCGlobalController::setSensorLinearAcceleration | ( | const std::string & | robotName, |
const Eigen::Vector3d & | acc | ||
) |
Sets the specified robot linear acceleration (control+real)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
acc | Linear acceleration |
If | the specified robot does not exist |
If | the robot does not have any body sensor |
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)
accels | Map of body sensor names to linear accelerations |
If | any of the body sensors do not exist in the robot |
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)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
accels | Map of body sensor names to linear accelerations |
If | the specified robot does not exist |
If | any of the body sensors do not exist in the robot |
|
protected |
Set multiple body sensors' linear acceleration for a given robot.
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)
linearVels | map of BodySensor name to the corresponding velocity |
If | any of the body sensors do not exist in the robot |
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)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
linearVels | map of BodySensor name to the corresponding velocity |
If | the specified robot does not exist |
If | any of the body sensors do not exist in the robot |
|
protected |
Set multiple body sensor's linear velocities for a given robot.
void mc_control::MCGlobalController::setSensorLinearVelocity | ( | const Eigen::Vector3d & | vel | ) |
Sets the main robot linear velocity sensor (control+real)
vel | Linear velocity given by a sensor |
If | the robot does not have any body sensor |
void mc_control::MCGlobalController::setSensorLinearVelocity | ( | const std::string & | robotName, |
const Eigen::Vector3d & | vel | ||
) |
Sets the specified robot linear velocity sensor (control+real)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
vel | Linear velocity given by a sensor |
If | the specified robot does not exist |
If | the robot does not have any body sensor |
void mc_control::MCGlobalController::setSensorOrientation | ( | const Eigen::Quaterniond & | ori | ) |
Sets the main robot orientation sensor (control + real)
ori | Orientation given by a sensor |
If | the robot does not have any body sensor |
void mc_control::MCGlobalController::setSensorOrientation | ( | const std::string & | robotName, |
const Eigen::Quaterniond & | ori | ||
) |
Sets the main robot orientation sensor (control + real)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
If | the specified robot does not exist |
If | the robot does not have any body sensor |
void mc_control::MCGlobalController::setSensorOrientations | ( | const QuaternionMap & | oris | ) |
Set multiple body sensors' orientation for the main robot (control+real)
oris | Map of sensor name -> orientation |
If | any of the sensors does not exist in the robot |
void mc_control::MCGlobalController::setSensorOrientations | ( | const std::string & | robotName, |
const QuaternionMap & | oris | ||
) |
Set multiple body sensors' orientation for the specified robot (control+real)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
If | the specified robot does not exist |
If | any of the sensors does not exist in the robot |
|
protected |
Set multiple body sensors' orientation for a given robot.
void mc_control::MCGlobalController::setSensorPosition | ( | const Eigen::Vector3d & | pos | ) |
Sets the main robot position sensor (control+real)
pos | Position given by a sensor |
If | the robot does not have any body sensor |
void mc_control::MCGlobalController::setSensorPosition | ( | const std::string & | robotName, |
const Eigen::Vector3d & | pos | ||
) |
Sets a robot's position sensor (control+real)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
pos | Position given by a sensor |
If | the robot does not have any body sensor |
If | the specified robot does not exist |
void mc_control::MCGlobalController::setSensorPositions | ( | const std::map< std::string, Eigen::Vector3d > & | poses | ) |
Set multiple body sensors' position for the main robot (control+real)
poses | Map of sensor name -> position |
If | one of the sensors does not exist in the robot |
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)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
poses | Map of sensor name -> position |
If | any of the sensors does not exist in the robot |
If | the specified robot does not exist |
|
protected |
Set multiple body sensors' position for a given robot.
void mc_control::MCGlobalController::setWrenches | ( | const std::map< std::string, sva::ForceVecd > & | wrenches | ) |
Force sensors' readings provided by the sensors (sets control+real)
wrenches | map of force sensor name to wrenches |
if | any of the force sensors do not exist |
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)
robotName | Name of the robot to which the sensor values will be assigned. A robot with that name must exist in both robots() and realRobots() instances. |
wrenches | map of force sensor name to wrenches |
If | the specified robot does not exist |
if | any of the force sensors do not exist |
MC_RTC_DEPRECATED void mc_control::MCGlobalController::setWrenches | ( | unsigned int | robotIndex, |
const std::map< std::string, sva::ForceVecd > & | wrenches | ||
) |
double mc_control::MCGlobalController::timestep | ( | ) | const |
Get the controller timestep.
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