#include <mc_rbdyn/Robot.h>
Classes | |
struct | NewRobotToken |
Public Types | |
using | convex_pair_t = std::pair< std::string, S_ObjectPtr > |
Public Member Functions | |||
Robot (Robot &&) | |||
Robot & | operator= (Robot &&) | ||
~Robot () | |||
const std::string & | name () const | ||
const RobotModule & | module () const | ||
bool | jointHasJointSensor (const std::string &joint) const noexcept | ||
const JointSensor & | jointJointSensor (const std::string &joint) const | ||
const std::vector< JointSensor > & | jointSensors () const noexcept | ||
bool | hasJoint (const std::string &name) const | ||
bool | hasBody (const std::string &name) const | ||
bool | hasFrame (const std::string &name) const noexcept | ||
const RobotFrame & | frame (const std::string &name) const | ||
RobotFrame & | frame (const std::string &name) | ||
std::vector< std::string > | frames () const | ||
RobotFrame & | makeFrame (const std::string &name, RobotFrame &parent, sva::PTransformd X_p_f, bool baked=false) | ||
RobotFramePtr | makeTemporaryFrame (const std::string &name, const RobotFrame &parent, sva::PTransformd X_p_f, bool baked=false) const | ||
void | makeFrames (std::vector< mc_rbdyn::RobotModule::FrameDescription > frames) | ||
bool | hasSurface (const std::string &surface) const | ||
mc_rbdyn::Surface & | surface (const std::string &sName) | ||
const mc_rbdyn::Surface & | surface (const std::string &sName) const | ||
sva::PTransformd | surfacePose (const std::string &sName) const | ||
mc_rbdyn::Surface & | copySurface (const std::string &sName, const std::string &name) | ||
void | addSurface (mc_rbdyn::SurfacePtr surface, bool doNotReplace=true) | ||
const std::map< std::string, mc_rbdyn::SurfacePtr > & | surfaces () const | ||
std::vector< std::string > | availableSurfaces () const | ||
bool | hasConvex (const std::string &name) const | ||
convex_pair_t & | convex (const std::string &cName) | ||
const convex_pair_t & | convex (const std::string &cName) const | ||
const std::map< std::string, convex_pair_t > & | convexes () const | ||
void | addConvex (const std::string &name, const std::string &body, S_ObjectPtr convex, const sva::PTransformd &X_b_c=sva::PTransformd::Identity()) | ||
void | removeConvex (const std::string &name) | ||
const sva::PTransformd & | bodyTransform (const std::string &bName) const | ||
const sva::PTransformd & | bodyTransform (int bodyIndex) const | ||
const std::vector< sva::PTransformd > & | bodyTransforms () const | ||
const sva::PTransformd & | collisionTransform (const std::string &cName) const | ||
void | loadRSDFFromDir (const std::string &surfaceDir) | ||
std::map< std::string, std::vector< double > > | stance () const | ||
mc_rbdyn::Robots & | robots () noexcept | ||
const mc_rbdyn::Robots & | robots () const noexcept | ||
unsigned int | robotIndex () const | ||
void | forwardKinematics () | ||
void | forwardKinematics (rbd::MultiBodyConfig &mbc) const | ||
void | forwardVelocity () | ||
void | forwardVelocity (rbd::MultiBodyConfig &mbc) const | ||
void | forwardAcceleration (const sva::MotionVecd &A_0=sva::MotionVecd(Eigen::Vector6d::Zero())) | ||
void | forwardAcceleration (rbd::MultiBodyConfig &mbc, const sva::MotionVecd &A_0=sva::MotionVecd(Eigen::Vector6d::Zero())) const | ||
void | eulerIntegration (double step) | ||
void | eulerIntegration (rbd::MultiBodyConfig &mbc, double step) const | ||
const sva::PTransformd & | posW () const | ||
void | posW (const sva::PTransformd &pt) | ||
void | velW (const sva::MotionVecd &vel) | ||
const sva::MotionVecd & | velW () const | ||
void | accW (const sva::MotionVecd &acc) | ||
const sva::MotionVecd | accW () const | ||
mc_control::Gripper & | gripper (const std::string &gripper) | ||
const mc_control::Gripper & | gripper (const std::string &gripper) const | ||
bool | hasGripper (const std::string &gripper) const | ||
const std::unordered_map< std::string, mc_control::GripperPtr > & | grippersByName () const noexcept | ||
const std::vector< mc_control::GripperRef > & | grippers () const noexcept | ||
const RobotDataPtr | data () const noexcept | ||
mc_tvm::Robot & | tvmRobot () const | ||
mc_tvm::Convex & | tvmConvex (const std::string &name) const | ||
Robot (NewRobotToken, const std::string &name, Robots &robots, unsigned int robots_idx, bool loadFiles, const LoadRobotParameters ¶ms={}) | |||
Body sensors | |||
These functions are related to force sensors | |||
const BodySensor & | bodySensor () const noexcept | ||
void | addBodySensor (const BodySensor &sensor) | ||
bool | hasBodySensor (const std::string &name) const noexcept | ||
bool | bodyHasBodySensor (const std::string &body) const noexcept | ||
const BodySensor & | bodySensor (const std::string &name) const | ||
const BodySensor & | bodyBodySensor (const std::string &name) const | ||
const BodySensorVector & | bodySensors () const noexcept | ||
Returns the joint index of joint named
| |||
unsigned int | jointIndexByName (const std::string &name) const | ||
int | jointIndexInMBC (size_t jointIndex) const | ||
Returns the body index of joint named
| |||
unsigned int | bodyIndexByName (const std::string &name) const | ||
rbd::MultiBody & | mb () | ||
const rbd::MultiBody & | mb () const | ||
rbd::MultiBodyConfig & | mbc () | ||
const rbd::MultiBodyConfig & | mbc () const | ||
rbd::MultiBodyGraph & | mbg () | ||
const rbd::MultiBodyGraph & | mbg () const | ||
const std::vector< std::vector< double > > & | q () const | ||
const std::vector< std::vector< double > > & | alpha () const | ||
const std::vector< std::vector< double > > & | alphaD () const | ||
const std::vector< std::vector< double > > & | jointTorque () const | ||
const std::vector< std::vector< double > > & | controlTorque () const noexcept | ||
const std::vector< sva::PTransformd > & | bodyPosW () const | ||
const std::vector< sva::MotionVecd > & | bodyVelW () const | ||
const std::vector< sva::MotionVecd > & | bodyVelB () const | ||
const std::vector< sva::MotionVecd > & | bodyAccB () const | ||
std::vector< std::vector< double > > & | q () | ||
std::vector< std::vector< double > > & | alpha () | ||
std::vector< std::vector< double > > & | alphaD () | ||
std::vector< std::vector< double > > & | jointTorque () | ||
std::vector< std::vector< double > > & | controlTorque () noexcept | ||
std::vector< sva::PTransformd > & | bodyPosW () | ||
std::vector< sva::MotionVecd > & | bodyVelW () | ||
std::vector< sva::MotionVecd > & | bodyVelB () | ||
std::vector< sva::MotionVecd > & | bodyAccB () | ||
const sva::PTransformd & | bodyPosW (const std::string &name) const | ||
sva::PTransformd | X_b1_b2 (const std::string &b1, const std::string &b2) const | ||
const sva::MotionVecd & | bodyVelW (const std::string &name) const | ||
const sva::MotionVecd & | bodyVelB (const std::string &name) const | ||
const sva::MotionVecd & | bodyAccB (const std::string &name) const | ||
Eigen::Vector3d | com () const | ||
Eigen::Vector3d | comVelocity () const | ||
Eigen::Vector3d | comAcceleration () const | ||
sva::ForceVecd | surfaceWrench (const std::string &surfaceName) const | ||
sva::ForceVecd | bodyWrench (const std::string &bodyName) const | ||
Eigen::Vector2d | cop (const std::string &frame, double min_pressure=0.5) const | ||
Eigen::Vector3d | copW (const std::string &frame, double min_pressure=0.5) const | ||
sva::ForceVecd | netWrench (const std::vector< std::string > &sensorNames) const | ||
Computes net total wrench from a list of sensors. More... | |||
Eigen::Vector3d | zmp (const sva::ForceVecd &netTotalWrench, const Eigen::Vector3d &plane_p, const Eigen::Vector3d &plane_n, double minimalNetNormalForce=1.) const | ||
Actual ZMP computation from net total wrench and the ZMP plane. More... | |||
bool | zmp (Eigen::Vector3d &zmpOut, const sva::ForceVecd &netTotalWrench, const Eigen::Vector3d &plane_p, const Eigen::Vector3d &plane_n, double minimalNetNormalForce=1.) const noexcept | ||
Actual ZMP computation from net total wrench and the ZMP plane. More... | |||
Eigen::Vector3d | zmp (const sva::ForceVecd &netTotalWrench, const sva::PTransformd &zmpFrame, double minimalNetNormalForce=1.) const | ||
ZMP computation from net total wrench and a frame. More... | |||
bool | zmp (Eigen::Vector3d &zmpOut, const sva::ForceVecd &netTotalWrench, const sva::PTransformd &zmpFrame, double minimalNetNormalForce=1.) const noexcept | ||
ZMP computation from net total wrench and a frame. More... | |||
Eigen::Vector3d | zmp (const std::vector< std::string > &sensorNames, const Eigen::Vector3d &plane_p, const Eigen::Vector3d &plane_n, double minimalNetNormalForce=1.) const | ||
bool | zmp (Eigen::Vector3d &zmpOut, const std::vector< std::string > &sensorNames, const Eigen::Vector3d &plane_p, const Eigen::Vector3d &plane_n, double minimalNetNormalForce=1.) const noexcept | ||
Eigen::Vector3d | zmp (const std::vector< std::string > &sensorNames, const sva::PTransformd &zmpFrame, double minimalNetNormalForce=1.) const | ||
Computes the ZMP from sensor names and a frame. More... | |||
bool | zmp (Eigen::Vector3d &zmpOut, const std::vector< std::string > &sensorNames, const sva::PTransformd &zmpFrame, double minimalNetNormalForce=1.) const noexcept | ||
Computes the ZMP from sensor names and a frame. More... | |||
const std::vector< std::vector< double > > & | ql () const | ||
const std::vector< std::vector< double > > & | qu () const | ||
const std::vector< std::vector< double > > & | vl () const | ||
const std::vector< std::vector< double > > & | vu () const | ||
const std::vector< std::vector< double > > & | al () const | ||
const std::vector< std::vector< double > > & | au () const | ||
const std::vector< std::vector< double > > & | jl () const | ||
const std::vector< std::vector< double > > & | ju () const | ||
const std::vector< std::vector< double > > & | tl () const | ||
const std::vector< std::vector< double > > & | tu () const | ||
const std::vector< std::vector< double > > & | tdl () const | ||
const std::vector< std::vector< double > > & | tdu () const | ||
std::vector< std::vector< double > > & | ql () | ||
std::vector< std::vector< double > > & | qu () | ||
std::vector< std::vector< double > > & | vl () | ||
std::vector< std::vector< double > > & | vu () | ||
std::vector< std::vector< double > > & | al () | ||
std::vector< std::vector< double > > & | au () | ||
std::vector< std::vector< double > > & | jl () | ||
std::vector< std::vector< double > > & | ju () | ||
std::vector< std::vector< double > > & | tl () | ||
std::vector< std::vector< double > > & | tu () | ||
std::vector< std::vector< double > > & | tdl () | ||
std::vector< std::vector< double > > & | tdu () | ||
const std::vector< Flexibility > & | flexibility () const | ||
std::vector< Flexibility > & | flexibility () | ||
void | zmpTarget (const Eigen::Vector3d &zmp) | ||
const Eigen::Vector3d & | zmpTarget () const | ||
double | mass () const noexcept | ||
Joint sensors | |||
These functions give information about joints' status | |||
const std::vector< double > & | encoderValues () const noexcept | ||
const std::vector< double > & | encoderVelocities () const noexcept | ||
const std::vector< double > & | jointTorques () const noexcept | ||
const std::vector< std::string > & | refJointOrder () const | ||
Force sensors | |||
These functions are related to force sensors | |||
void | addForceSensor (const mc_rbdyn::ForceSensor &fs) | ||
bool | hasForceSensor (const std::string &name) const noexcept | ||
bool | bodyHasForceSensor (const std::string &body) const noexcept | ||
bool | surfaceHasForceSensor (const std::string &surface) const | ||
Checks if the surface has a force sensor directly attached to it. More... | |||
bool | bodyHasIndirectForceSensor (const std::string &body) const | ||
bool | surfaceHasIndirectForceSensor (const std::string &surface) const | ||
const ForceSensor & | forceSensor (const std::string &name) const | ||
const ForceSensor & | bodyForceSensor (const std::string &body) const | ||
const ForceSensor * | findBodyForceSensor (const std::string &body) const | ||
const ForceSensor & | surfaceForceSensor (const std::string &surfaceName) const | ||
const ForceSensor & | indirectBodyForceSensor (const std::string &body) const | ||
Return a force sensor directly or indirectly attached to a body. More... | |||
const ForceSensor & | indirectSurfaceForceSensor (const std::string &surface) const | ||
Return a force sensor directly or indirectly attached to a surface. More... | |||
const std::vector< ForceSensor > & | forceSensors () const noexcept | ||
Devices | |||
These functions are related to generic devices handling | |||
template<typename T > | |||
bool | hasDevice (const std::string &name) const noexcept | ||
template<typename T > | |||
bool | hasSensor (const std::string &name) const noexcept | ||
template<typename T > | |||
const T & | device (const std::string &name) const | ||
template<typename T > | |||
T & | device (const std::string &name) | ||
const DevicePtrVector & | devices () const noexcept | ||
template<typename T > | |||
const T & | sensor (const std::string &name) const | ||
template<typename T > | |||
T & | sensor (const std::string &name) | ||
void | addDevice (DevicePtr device) | ||
void | addSensor (SensorPtr sensor) | ||
Protected Member Functions | |
void | copyLoadedData (Robot &destination) const |
void | fixSurfaces () |
void | fixSurface (Surface &surface) |
void | fixCollisionTransforms () |
std::string | findIndirectForceSensorBodyName (const std::string &bodyName) const |
Finds the name of the body to which a force sensor is attached, starting from the provided body and going up the kinematic tree. More... | |
Friends | |
struct | Robots |
using mc_rbdyn::Robot::convex_pair_t = std::pair<std::string, S_ObjectPtr> |
mc_rbdyn::Robot::Robot | ( | Robot && | ) |
mc_rbdyn::Robot::~Robot | ( | ) |
mc_rbdyn::Robot::Robot | ( | NewRobotToken | , |
const std::string & | name, | ||
Robots & | robots, | ||
unsigned int | robots_idx, | ||
bool | loadFiles, | ||
const LoadRobotParameters & | params = {} |
||
) |
Invoked by Robots parent instance after mb/mbc/mbg/RobotModule are stored
When loadFiles is set to false, the convex and surfaces files are not loaded. This is used when copying one robot into another.
const sva::MotionVecd mc_rbdyn::Robot::accW | ( | ) | const |
Return the robot's floating base acceleration expressed in the inertial frame
void mc_rbdyn::Robot::accW | ( | const sva::MotionVecd & | acc | ) |
Update the robot's floating base acceleration.
vel | New floating base acceleration in the inertial frame. |
void mc_rbdyn::Robot::addBodySensor | ( | const BodySensor & | sensor | ) |
Add BodySensor to the robot
sensor | Body to add |
void mc_rbdyn::Robot::addConvex | ( | const std::string & | name, |
const std::string & | body, | ||
S_ObjectPtr | convex, | ||
const sva::PTransformd & | X_b_c = sva::PTransformd::Identity() |
||
) |
Add a convex online
This has no effect if name
is already a convex of the robot
name | Name of the convex |
body | Name of the convex's parent body |
convex | sch::Object object representing the convex |
X_b_c | Transformation fro the convex's parent body to the convex |
void mc_rbdyn::Robot::addDevice | ( | DevicePtr | device | ) |
Add a generic device to the robot
void mc_rbdyn::Robot::addForceSensor | ( | const mc_rbdyn::ForceSensor & | fs | ) |
Add a new force sensor to the robot
This also updates frames' sensors.
This does not load the calibration file for this sensor. It is up to the caller to do so if they have a file availble.
sensor | Sensor to be added to the robot |
If | a sensor with the same name already exists within this robot |
void mc_rbdyn::Robot::addSurface | ( | mc_rbdyn::SurfacePtr | surface, |
bool | doNotReplace = true |
||
) |
Adds a surface with a new name
std::vector<std::vector<double> >& mc_rbdyn::Robot::al | ( | ) |
Access the robot's angular lower acceleration limits
const std::vector<std::vector<double> >& mc_rbdyn::Robot::al | ( | ) | const |
Access the robot's angular lower acceleration limits (const)
std::vector<std::vector<double> >& mc_rbdyn::Robot::alpha | ( | ) |
Equivalent to robot.mbc().alpha
const std::vector<std::vector<double> >& mc_rbdyn::Robot::alpha | ( | ) | const |
Equivalent to robot.mbc().alpha (const)
std::vector<std::vector<double> >& mc_rbdyn::Robot::alphaD | ( | ) |
Equivalent to robot.mbc().alphaD
const std::vector<std::vector<double> >& mc_rbdyn::Robot::alphaD | ( | ) | const |
Equivalent to robot.mbc().alphaD (const)
std::vector<std::vector<double> >& mc_rbdyn::Robot::au | ( | ) |
Access the robot's angular upper acceleration limits
const std::vector<std::vector<double> >& mc_rbdyn::Robot::au | ( | ) | const |
Access the robot's angular upper acceleration limits (const)
std::vector<std::string> mc_rbdyn::Robot::availableSurfaces | ( | ) | const |
Returns a list of available surfaces
std::vector<sva::MotionVecd>& mc_rbdyn::Robot::bodyAccB | ( | ) |
Equivalent to robot.mbc().bodyAccB
const std::vector<sva::MotionVecd>& mc_rbdyn::Robot::bodyAccB | ( | ) | const |
Equivalent to robot.mbc().bodyAccB (const)
const sva::MotionVecd& mc_rbdyn::Robot::bodyAccB | ( | const std::string & | name | ) | const |
Access the acceleration of body name
in body coordinates
If | the body doest not exist within the robot |
const BodySensor& mc_rbdyn::Robot::bodyBodySensor | ( | const std::string & | name | ) | const |
Return a specific BodySensor by body name
name | Name of the body |
If | there is no sensor attached to the body |
const ForceSensor& mc_rbdyn::Robot::bodyForceSensor | ( | const std::string & | body | ) | const |
Return a force sensor attached to the provided body
body | Name of the body to which the sensor is attached |
If | no sensor is directly attached to this body |
|
inlinenoexcept |
Return true if the specified body has a body sensor attached to it
body | Body to query |
|
inlinenoexcept |
Check if the body has a force sensor directly attached to it
body | Name of the body to which the sensor is directly attached |
|
inline |
Check if the body has a force sensor attached to it (directly or indirectly)
body | Name of the body to which the sensor is (directly or indirectly) attached |
unsigned int mc_rbdyn::Robot::bodyIndexByName | ( | const std::string & | name | ) | const |
Access MultiBody representation of the robot
std::vector<sva::PTransformd>& mc_rbdyn::Robot::bodyPosW | ( | ) |
Equivalent to robot.mbc().bodyPosW
const std::vector<sva::PTransformd>& mc_rbdyn::Robot::bodyPosW | ( | ) | const |
Equivalent to robot.mbc().bodyPosW (const)
const sva::PTransformd& mc_rbdyn::Robot::bodyPosW | ( | const std::string & | name | ) | const |
Access the position of body name
in world coordinates
If | the body does not exist within the robot |
|
inlinenoexcept |
Return the first BodySensor in the robot (const)
const BodySensor& mc_rbdyn::Robot::bodySensor | ( | const std::string & | name | ) | const |
Return a specific BobySensor by name
name | Name of the sensor |
If | the sensor does not exist |
|
inlinenoexcept |
Return all body sensors (const)
const sva::PTransformd& mc_rbdyn::Robot::bodyTransform | ( | const std::string & | bName | ) | const |
Access transformation from body bName
to original base.
This can be used to correct transformations that were stored with the original base. Usually the robot's base is the original base so these transforms are identity.
const sva::PTransformd& mc_rbdyn::Robot::bodyTransform | ( | int | bodyIndex | ) | const |
Access body transform by index
const std::vector<sva::PTransformd>& mc_rbdyn::Robot::bodyTransforms | ( | ) | const |
Access body transform vector
std::vector<sva::MotionVecd>& mc_rbdyn::Robot::bodyVelB | ( | ) |
Equivalent to robot.mbc().bodyVelB
const std::vector<sva::MotionVecd>& mc_rbdyn::Robot::bodyVelB | ( | ) | const |
Equivalent to robot.mbc().bodyVelB (const)
const sva::MotionVecd& mc_rbdyn::Robot::bodyVelB | ( | const std::string & | name | ) | const |
Access the velocity of body name
in body coordinates
If | the body doest not exist within the robot |
std::vector<sva::MotionVecd>& mc_rbdyn::Robot::bodyVelW | ( | ) |
Equivalent to robot.mbc().bodyVelW
const std::vector<sva::MotionVecd>& mc_rbdyn::Robot::bodyVelW | ( | ) | const |
Equivalent to robot.mbc().bodyVelW (const)
const sva::MotionVecd& mc_rbdyn::Robot::bodyVelW | ( | const std::string & | name | ) | const |
Access the velocity of body name
in world coordinates
If | the body doest not exist within the robot |
sva::ForceVecd mc_rbdyn::Robot::bodyWrench | ( | const std::string & | bodyName | ) | const |
Compute the gravity-free wrench in body frame
bodyName | A body attached to a force sensor |
If | no sensor is attached to this surface |
const sva::PTransformd& mc_rbdyn::Robot::collisionTransform | ( | const std::string & | cName | ) | const |
Access transformation between the collision mesh and the body
Eigen::Vector3d mc_rbdyn::Robot::com | ( | ) | const |
Compute and returns the current robot's CoM
Eigen::Vector3d mc_rbdyn::Robot::comAcceleration | ( | ) | const |
Compute and returns the current robot's CoM acceleration
Eigen::Vector3d mc_rbdyn::Robot::comVelocity | ( | ) | const |
Compute and returns the current robot's CoM velocity
|
inlinenoexcept |
Access the desired control torque
|
inlinenoexcept |
Access the desired control torque
convex_pair_t& mc_rbdyn::Robot::convex | ( | const std::string & | cName | ) |
Access a convex named cName
const convex_pair_t& mc_rbdyn::Robot::convex | ( | const std::string & | cName | ) | const |
Access a convex named cName
(const)
const std::map<std::string, convex_pair_t>& mc_rbdyn::Robot::convexes | ( | ) | const |
Access all convexes available in this robot
Eigen::Vector2d mc_rbdyn::Robot::cop | ( | const std::string & | frame, |
double | min_pressure = 0.5 |
||
) | const |
Compute the cop in a given frame computed from gravity-free force measurements
frame | A frame attached to a force sensor |
min_pressure | Minimum pressure in N (default 0.5N). |
If | the frame does not exist or no sensor is attached to this frame |
Eigen::Vector3d mc_rbdyn::Robot::copW | ( | const std::string & | frame, |
double | min_pressure = 0.5 |
||
) | const |
Compute the cop in inertial frame compute from gravity-free force measurements
frame | A frame attached to a force sensor |
min_pressure | Minimum pressure in N (default 0.5N). |
If | the frame does not exist or no sensor is attached to this frame |
|
protected |
Copy loaded data from this robot to a new robot
mc_rbdyn::Surface& mc_rbdyn::Robot::copySurface | ( | const std::string & | sName, |
const std::string & | name | ||
) |
Copy an existing surface with a new name
|
inlinenoexcept |
Access the data associated to this object
|
inline |
Non-const variant
const T& mc_rbdyn::Robot::device | ( | const std::string & | name | ) | const |
Get a generic device of type T named name
The reference returned by this function is remains valid
name | Name of the device |
T | type of the device requested |
If | the device does not exist or does not have the right type |
|
inlinenoexcept |
Get all devices attached to a robot
|
inlinenoexcept |
Return the encoder values
|
inlinenoexcept |
Return the encoder velocities
void mc_rbdyn::Robot::eulerIntegration | ( | double | step | ) |
Apply Euler integration to the robot using step
timestep
void mc_rbdyn::Robot::eulerIntegration | ( | rbd::MultiBodyConfig & | mbc, |
double | step | ||
) | const |
Apply Euler integration to mbc
using the robot's mb() and step
timestep
const ForceSensor* mc_rbdyn::Robot::findBodyForceSensor | ( | const std::string & | body | ) | const |
Return a force sensor attached (directly or indirectly) to the given body
Returns a null pointer if no such sensor exists
|
protected |
Finds the name of the body to which a force sensor is attached, starting from the provided body and going up the kinematic tree.
bodyName | Name of the body to which the sensor is attached |
|
protected |
Used to set the collision transforms correctly
|
protected |
Used to set the specified surface X_b_s correctly
This function should only be called once per surface.
surfaces | Surface that need to be modified |
|
protected |
Used to set all robot surfaces' X_b_s correctly
This updates all surfaces in surfaces_ vector and should only be called once
std::vector<Flexibility>& mc_rbdyn::Robot::flexibility | ( | ) |
Return the flexibilities of the robot
const std::vector<Flexibility>& mc_rbdyn::Robot::flexibility | ( | ) | const |
Return the flexibilities of the robot (const)
const ForceSensor& mc_rbdyn::Robot::forceSensor | ( | const std::string & | name | ) | const |
Return a force sensor by name
name | Name of the sensor |
If | no sensor with this name exists |
|
inlinenoexcept |
Returns all force sensors (const)
void mc_rbdyn::Robot::forwardAcceleration | ( | const sva::MotionVecd & | A_0 = sva::MotionVecd(Eigen::Vector6d::Zero()) | ) |
Apply forward acceleration to the robot
void mc_rbdyn::Robot::forwardAcceleration | ( | rbd::MultiBodyConfig & | mbc, |
const sva::MotionVecd & | A_0 = sva::MotionVecd(Eigen::Vector6d::Zero()) |
||
) | const |
Apply forward acceleration to mbc
using the robot's mb()
void mc_rbdyn::Robot::forwardKinematics | ( | ) |
Apply forward kinematics to the robot
void mc_rbdyn::Robot::forwardKinematics | ( | rbd::MultiBodyConfig & | mbc | ) | const |
Apply forward kinematics to mbc
using the robot's mb()
void mc_rbdyn::Robot::forwardVelocity | ( | ) |
Apply forward velocity to the robot
void mc_rbdyn::Robot::forwardVelocity | ( | rbd::MultiBodyConfig & | mbc | ) | const |
Apply forward velocity to mbc
using the robot's mb()
|
inline |
Access the frame named name
(non-const)
If | the frame does not exist |
|
inline |
Access the frame named name
If | the frame does not exist |
std::vector<std::string> mc_rbdyn::Robot::frames | ( | ) | const |
Returns the list of available frames in this robot
mc_control::Gripper& mc_rbdyn::Robot::gripper | ( | const std::string & | gripper | ) |
Access a gripper by name
gripper | Gripper name |
If | the gripper does not exist within this robot |
const mc_control::Gripper& mc_rbdyn::Robot::gripper | ( | const std::string & | gripper | ) | const |
Access a gripper by name
gripper | Gripper name |
If | the gripper does not exist within this robot |
|
inlinenoexcept |
Access all grippers
|
inlinenoexcept |
bool mc_rbdyn::Robot::hasBody | ( | const std::string & | name | ) | const |
Returns true if the robot has a body named name
|
inlinenoexcept |
Return true if the robot has a body sensor named name
name | Name of the body sensor |
bool mc_rbdyn::Robot::hasConvex | ( | const std::string & | name | ) | const |
Check if a convex name
exists
|
noexcept |
Returns true if a generic device of type T and named name exists in the robot
name | Name of the device |
T | Type of device requested |
|
inlinenoexcept |
Check if a force sensor exists
name | Name of the sensor |
|
inlinenoexcept |
Returns true if the robot has a frame named name
bool mc_rbdyn::Robot::hasGripper | ( | const std::string & | gripper | ) | const |
Checks whether a gripper is part of this robot
bool mc_rbdyn::Robot::hasJoint | ( | const std::string & | name | ) | const |
Returns true if the robot has a joint named name
|
inlinenoexcept |
Alias for
bool mc_rbdyn::Robot::hasSurface | ( | const std::string & | surface | ) | const |
Check if a surface surface
exists
const ForceSensor& mc_rbdyn::Robot::indirectBodyForceSensor | ( | const std::string & | body | ) | const |
Return a force sensor directly or indirectly attached to a body.
When the sensor is not directly attached to the body, look up the kinematic chain until the root until a sensor is found.
If | no sensor is found between the body and the root |
const ForceSensor& mc_rbdyn::Robot::indirectSurfaceForceSensor | ( | const std::string & | surface | ) | const |
Return a force sensor directly or indirectly attached to a surface.
When the sensor is not directly attached to the surface, look up the kinematic chain until the root until a sensor is found.
surface | Name of surface indirectly attached to the sensor |
If | no sensor is found between the surface and the root |
std::vector<std::vector<double> >& mc_rbdyn::Robot::jl | ( | ) |
Access the robot's angular lower jerk limits
const std::vector<std::vector<double> >& mc_rbdyn::Robot::jl | ( | ) | const |
Access the robot's angular lower jerk limits (const)
|
inlinenoexcept |
Return true if the specified joint has a joint sensor attached to it
joint | Joint to query |
unsigned int mc_rbdyn::Robot::jointIndexByName | ( | const std::string & | name | ) | const |
Returns the joint index in the mbc of the joint with index jointIndex in refJointOrder
jointIndex | Joint index in refJointOrder |
If | jointIndex >= refJointOrder.size() |
int mc_rbdyn::Robot::jointIndexInMBC | ( | size_t | jointIndex | ) | const |
Returns the joint index in the mbc of the joint with index jointIndex in refJointOrder
jointIndex | Joint index in refJointOrder |
If | jointIndex >= refJointOrder.size() |
const JointSensor& mc_rbdyn::Robot::jointJointSensor | ( | const std::string & | joint | ) | const |
Return a specific JointSensor by joint name
joint | Name of the joint |
If | there is no sensor attached to the joint |
|
inlinenoexcept |
Return all joint sensors (const)
std::vector<std::vector<double> >& mc_rbdyn::Robot::jointTorque | ( | ) |
Equivalent to robot.mbc().jointTorque
const std::vector<std::vector<double> >& mc_rbdyn::Robot::jointTorque | ( | ) | const |
Equivalent to robot.mbc().jointTorque (const)
|
inlinenoexcept |
Return the joint torques from sensors
std::vector<std::vector<double> >& mc_rbdyn::Robot::ju | ( | ) |
Access the robot's angular upper jerk limits
const std::vector<std::vector<double> >& mc_rbdyn::Robot::ju | ( | ) | const |
Access the robot's angular upper jerk limits (const)
void mc_rbdyn::Robot::loadRSDFFromDir | ( | const std::string & | surfaceDir | ) |
Load surfaces from the directory surfaceDir
RobotFrame& mc_rbdyn::Robot::makeFrame | ( | const std::string & | name, |
RobotFrame & | parent, | ||
sva::PTransformd | X_p_f, | ||
bool | baked = false |
||
) |
Create a new frame attached to this robot
name | Name of the frame |
frame | Parent frame of this frame |
X_p_f | Transformation from the parent frame to the frame |
baked | Attach the newly created frame to parent parent's body rather than parent if true |
If | parent does not belong to this robot or if name already exists in this robot |
void mc_rbdyn::Robot::makeFrames | ( | std::vector< mc_rbdyn::RobotModule::FrameDescription > | frames | ) |
Create new frames attached to this robot
frames | Description of the frames |
If | any of the frames' parent does not belong to this robot or if name already exists in this robot |
RobotFramePtr mc_rbdyn::Robot::makeTemporaryFrame | ( | const std::string & | name, |
const RobotFrame & | parent, | ||
sva::PTransformd | X_p_f, | ||
bool | baked = false |
||
) | const |
Create a new temporary frame
The frame is not kept by the robot and cannot be found via frame or inside frames
The main purpose is to tie a frame lifetime to another object (e.g. a task, a constraint, a state...) that needs it
name | Name of the frame |
frame | Parent frame of this frame |
X_p_f | Transformation from the parent frame to the frame |
baked | Attach the newly created frame to parent parent's body rather than parent if true |
If | parent does not belong to this robot |
|
inlinenoexcept |
Compute and returns the mass of the robot
rbd::MultiBody& mc_rbdyn::Robot::mb | ( | ) |
Access MultiBody representation of the robot
const rbd::MultiBody& mc_rbdyn::Robot::mb | ( | ) | const |
Access MultiBody representation of the robot (const)
rbd::MultiBodyConfig& mc_rbdyn::Robot::mbc | ( | ) |
Access MultiBodyConfig of the robot's mb()
const rbd::MultiBodyConfig& mc_rbdyn::Robot::mbc | ( | ) | const |
Access MultiBodyConfig of the robot's mb() (const)
rbd::MultiBodyGraph& mc_rbdyn::Robot::mbg | ( | ) |
Access MultiBodyGraph that generated the robot's mb()
const rbd::MultiBodyGraph& mc_rbdyn::Robot::mbg | ( | ) | const |
Access MultiBodyGraph that generated the robot's mb() (const)
const RobotModule& mc_rbdyn::Robot::module | ( | ) | const |
Retrieve the associated RobotModule
const std::string& mc_rbdyn::Robot::name | ( | ) | const |
Returns the name of the robot
sva::ForceVecd mc_rbdyn::Robot::netWrench | ( | const std::vector< std::string > & | sensorNames | ) | const |
Computes net total wrench from a list of sensors.
sensorNames | Names of all sensors used to compute the net wrench |
const sva::PTransformd& mc_rbdyn::Robot::posW | ( | ) | const |
Return the robot's global pose
void mc_rbdyn::Robot::posW | ( | const sva::PTransformd & | pt | ) |
Set the robot's global pose. This is mostly meant for initialization purposes. In other scenarios there might be more things to do to properly move a robot (e.g. update contacts, set speed to zero).
pt | The new global pose |
If | joint(0) is neither free flyer nor fixed |
std::vector<std::vector<double> >& mc_rbdyn::Robot::q | ( | ) |
Equivalent to robot.mbc().q
const std::vector<std::vector<double> >& mc_rbdyn::Robot::q | ( | ) | const |
Equivalent to robot.mbc().q (const)
std::vector<std::vector<double> >& mc_rbdyn::Robot::ql | ( | ) |
Access the robot's angular lower limits
const std::vector<std::vector<double> >& mc_rbdyn::Robot::ql | ( | ) | const |
Access the robot's angular lower limits (const)
std::vector<std::vector<double> >& mc_rbdyn::Robot::qu | ( | ) |
Access the robot's angular upper limits
const std::vector<std::vector<double> >& mc_rbdyn::Robot::qu | ( | ) | const |
Access the robot's angular upper limits (const)
|
inline |
Return the reference joint order for this robot
void mc_rbdyn::Robot::removeConvex | ( | const std::string & | name | ) |
Remove a given convex
Using this function while the given convex is involved in a collision is not safe and will very likely result in a crash.
This has no effect if name
is not a convex of the robot.
name | Name of the convex |
unsigned int mc_rbdyn::Robot::robotIndex | ( | ) | const |
Access the robot's index in robots()
|
inlinenoexcept |
Access Robots instance this instance belongs to (const)
|
inlinenoexcept |
Access Robots instance this instance belongs to
|
inline |
Alias for
|
inline |
Alias for
std::map<std::string, std::vector<double> > mc_rbdyn::Robot::stance | ( | ) | const |
Return the robot's default stance (e.g. half-sitting for humanoid)
mc_rbdyn::Surface& mc_rbdyn::Robot::surface | ( | const std::string & | sName | ) |
Access a surface by its name sName
const mc_rbdyn::Surface& mc_rbdyn::Robot::surface | ( | const std::string & | sName | ) | const |
Access a surface by its name sName
(const)
const ForceSensor& mc_rbdyn::Robot::surfaceForceSensor | ( | const std::string & | surfaceName | ) | const |
Return a force sensor attached to the provided surface
surface | Name of the surface to which the sensor is attached |
If | no sensor is directly attached to this surface |
|
inline |
Checks if the surface has a force sensor directly attached to it.
surface | Name of the surface to which the sensor is directly attached |
If | surface does not exist in this robot |
|
inline |
Check if the surface has a force sensor attached to it (directly or indirectly)
surface | Name of the surface to which the sensor is directly attached |
sva::PTransformd mc_rbdyn::Robot::surfacePose | ( | const std::string & | sName | ) | const |
Get the pose of a surface frame with respect to the inertial frame.
sName | Name of surface frame. |
const std::map<std::string, mc_rbdyn::SurfacePtr>& mc_rbdyn::Robot::surfaces | ( | ) | const |
Returns all available surfaces
sva::ForceVecd mc_rbdyn::Robot::surfaceWrench | ( | const std::string & | surfaceName | ) | const |
Compute the gravity-free wrench in surface frame
surfaceName | A surface attached to a force sensor |
If | no sensor is attached to this surface |
std::vector<std::vector<double> >& mc_rbdyn::Robot::tdl | ( | ) |
Access the robot's angular lower torque-derivative limits
const std::vector<std::vector<double> >& mc_rbdyn::Robot::tdl | ( | ) | const |
Access the robot's angular lower torque-derivative limits (const)
std::vector<std::vector<double> >& mc_rbdyn::Robot::tdu | ( | ) |
Access the robot's angular upper torque-derivative limits
const std::vector<std::vector<double> >& mc_rbdyn::Robot::tdu | ( | ) | const |
Access the robot's angular upper torque-derivative limits (const)
std::vector<std::vector<double> >& mc_rbdyn::Robot::tl | ( | ) |
Access the robot's angular lower torque limits
const std::vector<std::vector<double> >& mc_rbdyn::Robot::tl | ( | ) | const |
Access the robot's angular lower torque limits (const)
std::vector<std::vector<double> >& mc_rbdyn::Robot::tu | ( | ) |
Access the robot's angular upper torque limits
const std::vector<std::vector<double> >& mc_rbdyn::Robot::tu | ( | ) | const |
Access the robot's angular upper torque limits (const)
mc_tvm::Convex& mc_rbdyn::Robot::tvmConvex | ( | const std::string & | name | ) | const |
Get the TVM convex associated to this robot convex
FIXME Returns a non-const reference from a const method because it is most often used to register dependencies between TVM nodes which require non-const objects
name | Name of the convex |
If | the convex does not exist |
mc_tvm::Robot& mc_rbdyn::Robot::tvmRobot | ( | ) | const |
Get the TVM robot associated to this robot
FIXME Returns a non-const reference from a const method because it is most often used to register dependencies between TVM nodes which require non-const objects
const sva::MotionVecd& mc_rbdyn::Robot::velW | ( | ) | const |
Return the robot's floating base velocity expressed in the inertial frame
void mc_rbdyn::Robot::velW | ( | const sva::MotionVecd & | vel | ) |
Update the robot's floating base velocity.
vel | New floating base velocity in the inertial frame. |
std::vector<std::vector<double> >& mc_rbdyn::Robot::vl | ( | ) |
Access the robot's angular lower velocity limits
const std::vector<std::vector<double> >& mc_rbdyn::Robot::vl | ( | ) | const |
Access the robot's angular lower velocity limits (const)
std::vector<std::vector<double> >& mc_rbdyn::Robot::vu | ( | ) |
Access the robot's angular upper velocity limits
const std::vector<std::vector<double> >& mc_rbdyn::Robot::vu | ( | ) | const |
Access the robot's angular upper velocity limits (const)
sva::PTransformd mc_rbdyn::Robot::X_b1_b2 | ( | const std::string & | b1, |
const std::string & | b2 | ||
) | const |
Relative transformation X_b1_b2 from body b1 to body b2
b1 | name of first body |
b2 | name of second body |
If | b1 or b2 does not exist within the robot |
Eigen::Vector3d mc_rbdyn::Robot::zmp | ( | const std::vector< std::string > & | sensorNames, |
const Eigen::Vector3d & | plane_p, | ||
const Eigen::Vector3d & | plane_n, | ||
double | minimalNetNormalForce = 1. |
||
) | const |
Computes the ZMP from sensor names and a plane
See zmpDoc
sensorNames | Names of all sensors attached to a link in contact with the environment |
Eigen::Vector3d mc_rbdyn::Robot::zmp | ( | const std::vector< std::string > & | sensorNames, |
const sva::PTransformd & | zmpFrame, | ||
double | minimalNetNormalForce = 1. |
||
) | const |
Computes the ZMP from sensor names and a frame.
See zmpDoc
sensorNames | Names of all sensors attached to a link in contact with the environment |
Eigen::Vector3d mc_rbdyn::Robot::zmp | ( | const sva::ForceVecd & | netTotalWrench, |
const Eigen::Vector3d & | plane_p, | ||
const Eigen::Vector3d & | plane_n, | ||
double | minimalNetNormalForce = 1. |
||
) | const |
Actual ZMP computation from net total wrench and the ZMP plane.
netTotalWrench | Total wrench for all links in contact |
plane_p | Arbitrary point on the ZMP plane |
plane_n | Normal to the ZMP plane (normalized) |
minimalNetNormalForce[N] | Mininal force above which the ZMP computation is considered valid. Must be >0 (prevents a divide by zero). |
To | prevent dividing by zero, throws if the projected force is below minimalNetNormalForce newton. This is highly unlikely to happen and would likely indicate indicate that you are computing a ZMP from invalid forces (such as with the robot in the air). |
Eigen::Vector3d mc_rbdyn::Robot::zmp | ( | const sva::ForceVecd & | netTotalWrench, |
const sva::PTransformd & | zmpFrame, | ||
double | minimalNetNormalForce = 1. |
||
) | const |
ZMP computation from net total wrench and a frame.
See zmpDoc
netTotalWrench | |
zmpFrame | Frame used for ZMP computation. The convention here is that the contact frame should have its z-axis pointing in the normal direction of the contact towards the robot. |
|
noexcept |
Computes the ZMP from sensor names and a plane
See zmpDoc
sensorNames | Names of all sensors attached to a link in contact with the environment |
|
noexcept |
Computes the ZMP from sensor names and a frame.
See zmpDoc
sensorNames | Names of all sensors attached to a link in contact with the environment |
|
noexcept |
Actual ZMP computation from net total wrench and the ZMP plane.
zmpOut | Output of the ZMP computation expressed in the requested frame |
netTotalWrench | Total wrench for all links in contact |
plane_p | Arbitrary point on the ZMP plane |
plane_n | Normal to the ZMP plane (normalized) |
minimalNetNormalForce[N] | Mininal force above which the ZMP computation is considered valid. Must be >0 (prevents a divide by zero). |
zmpOut
is untouched
|
noexcept |
ZMP computation from net total wrench and a frame.
See zmpDoc
zmpOut | Output of the ZMP computation expressed in the plane defined by the zmpFrame frame |
netTotalWrench | |
zmpFrame | Frame used for ZMP computation. The convention here is that the contact frame should have its z-axis pointing in the normal direction of the contact towards the robot. |
zmpOut
is untouched const Eigen::Vector3d& mc_rbdyn::Robot::zmpTarget | ( | ) | const |
Returns the target zmp
void mc_rbdyn::Robot::zmpTarget | ( | const Eigen::Vector3d & | zmp | ) |
Set the target zmp defined with respect to base-link. This target is intended to be used by an external stabilizer such as Kawada's
zmp | Note that usually the ZMP is a 2-vector assuming a perfectly flat ground. The convention here is that the ground is at (tz=0). Therefore the target zmp should be defined as (ZMPx, ZMPy, -zbaselink) |
|
friend |