mc_rbdyn::Robot Struct Reference

#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 &&)
 
Robotoperator= (Robot &&)
 
 ~Robot ()
 
const std::string & name () const
 
const RobotModulemodule () const
 
bool jointHasJointSensor (const std::string &joint) const noexcept
 
const JointSensorjointJointSensor (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 RobotFrameframe (const std::string &name) const
 
RobotFrameframe (const std::string &name)
 
std::vector< std::string > frames () const
 
RobotFramemakeFrame (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::Surfacesurface (const std::string &sName)
 
const mc_rbdyn::Surfacesurface (const std::string &sName) const
 
sva::PTransformd surfacePose (const std::string &sName) const
 
mc_rbdyn::SurfacecopySurface (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_tconvex (const std::string &cName)
 
const convex_pair_tconvex (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::Robotsrobots () noexcept
 
const mc_rbdyn::Robotsrobots () 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::Grippergripper (const std::string &gripper)
 
const mc_control::Grippergripper (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::RobottvmRobot () const
 
mc_tvm::ConvextvmConvex (const std::string &name) const
 
 Robot (NewRobotToken, const std::string &name, Robots &robots, unsigned int robots_idx, bool loadFiles, const LoadRobotParameters &params={})
 
Body sensors

These functions are related to force sensors

const BodySensorbodySensor () const noexcept
 
void addBodySensor (const BodySensor &sensor)
 
bool hasBodySensor (const std::string &name) const noexcept
 
bool bodyHasBodySensor (const std::string &body) const noexcept
 
const BodySensorbodySensor (const std::string &name) const
 
const BodySensorbodyBodySensor (const std::string &name) const
 
const BodySensorVectorbodySensors () const noexcept
 

Returns the joint index of joint named

Exceptions
Ifthe joint does not exist within the robot.
unsigned int jointIndexByName (const std::string &name) const
 
int jointIndexInMBC (size_t jointIndex) const
 

Returns the body index of joint named

Exceptions
Ifthe body does not exist within the robot.
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 ForceSensorforceSensor (const std::string &name) const
 
const ForceSensorbodyForceSensor (const std::string &body) const
 
const ForceSensorfindBodyForceSensor (const std::string &body) const
 
const ForceSensorsurfaceForceSensor (const std::string &surfaceName) const
 
const ForceSensorindirectBodyForceSensor (const std::string &body) const
 Return a force sensor directly or indirectly attached to a body. More...
 
const ForceSensorindirectSurfaceForceSensor (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 DevicePtrVectordevices () 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
 

Member Typedef Documentation

◆ convex_pair_t

using mc_rbdyn::Robot::convex_pair_t = std::pair<std::string, S_ObjectPtr>

Constructor & Destructor Documentation

◆ Robot() [1/2]

mc_rbdyn::Robot::Robot ( Robot &&  )

◆ ~Robot()

mc_rbdyn::Robot::~Robot ( )

◆ Robot() [2/2]

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.

Member Function Documentation

◆ accW() [1/2]

const sva::MotionVecd mc_rbdyn::Robot::accW ( ) const

Return the robot's floating base acceleration expressed in the inertial frame

◆ accW() [2/2]

void mc_rbdyn::Robot::accW ( const sva::MotionVecd &  acc)

Update the robot's floating base acceleration.

Parameters
velNew floating base acceleration in the inertial frame.
Note
This function takes care of calling rbd::forwardAcceleration

◆ addBodySensor()

void mc_rbdyn::Robot::addBodySensor ( const BodySensor sensor)

Add BodySensor to the robot

Parameters
sensorBody to add

◆ addConvex()

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

Parameters
nameName of the convex
bodyName of the convex's parent body
convexsch::Object object representing the convex
X_b_cTransformation fro the convex's parent body to the convex

◆ addDevice()

void mc_rbdyn::Robot::addDevice ( DevicePtr  device)

Add a generic device to the robot

◆ addForceSensor()

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.

Parameters
sensorSensor to be added to the robot
Exceptions
Ifa sensor with the same name already exists within this robot

◆ addSensor()

void mc_rbdyn::Robot::addSensor ( SensorPtr  sensor)
inline

Alias for

See also
addDevice

◆ addSurface()

void mc_rbdyn::Robot::addSurface ( mc_rbdyn::SurfacePtr  surface,
bool  doNotReplace = true 
)

Adds a surface with a new name

◆ al() [1/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::al ( )

Access the robot's angular lower acceleration limits

◆ al() [2/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::al ( ) const

Access the robot's angular lower acceleration limits (const)

◆ alpha() [1/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::alpha ( )

Equivalent to robot.mbc().alpha

◆ alpha() [2/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::alpha ( ) const

Equivalent to robot.mbc().alpha (const)

◆ alphaD() [1/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::alphaD ( )

Equivalent to robot.mbc().alphaD

◆ alphaD() [2/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::alphaD ( ) const

Equivalent to robot.mbc().alphaD (const)

◆ au() [1/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::au ( )

Access the robot's angular upper acceleration limits

◆ au() [2/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::au ( ) const

Access the robot's angular upper acceleration limits (const)

◆ availableSurfaces()

std::vector<std::string> mc_rbdyn::Robot::availableSurfaces ( ) const

Returns a list of available surfaces

◆ bodyAccB() [1/3]

std::vector<sva::MotionVecd>& mc_rbdyn::Robot::bodyAccB ( )

Equivalent to robot.mbc().bodyAccB

◆ bodyAccB() [2/3]

const std::vector<sva::MotionVecd>& mc_rbdyn::Robot::bodyAccB ( ) const

Equivalent to robot.mbc().bodyAccB (const)

◆ bodyAccB() [3/3]

const sva::MotionVecd& mc_rbdyn::Robot::bodyAccB ( const std::string &  name) const

Access the acceleration of body name in body coordinates

Exceptions
Ifthe body doest not exist within the robot

◆ bodyBodySensor()

const BodySensor& mc_rbdyn::Robot::bodyBodySensor ( const std::string &  name) const

Return a specific BodySensor by body name

Parameters
nameName of the body
Exceptions
Ifthere is no sensor attached to the body

◆ bodyForceSensor()

const ForceSensor& mc_rbdyn::Robot::bodyForceSensor ( const std::string &  body) const

Return a force sensor attached to the provided body

Parameters
bodyName of the body to which the sensor is attached
Returns
The attached sensor
Exceptions
Ifno sensor is directly attached to this body
See also
ForceSensor & indirectBodyForceSensor(const std::string & body); To get a sensor directly or indirectly attached to the body.

◆ bodyHasBodySensor()

bool mc_rbdyn::Robot::bodyHasBodySensor ( const std::string &  body) const
inlinenoexcept

Return true if the specified body has a body sensor attached to it

Parameters
bodyBody to query

◆ bodyHasForceSensor()

bool mc_rbdyn::Robot::bodyHasForceSensor ( const std::string &  body) const
inlinenoexcept

Check if the body has a force sensor directly attached to it

Parameters
bodyName of the body to which the sensor is directly attached
See also
bodyHasIndirectForceSensor(const std::string &) if you wish to check whether a sensor is indirectly attached to a body
Returns
True if the body has a force sensor attached to it, false otherwise

◆ bodyHasIndirectForceSensor()

bool mc_rbdyn::Robot::bodyHasIndirectForceSensor ( const std::string &  body) const
inline

Check if the body has a force sensor attached to it (directly or indirectly)

Parameters
bodyName of the body to which the sensor is (directly or indirectly) attached
Returns
True if the body has a force sensor attached to it, false otherwise

◆ bodyIndexByName()

unsigned int mc_rbdyn::Robot::bodyIndexByName ( const std::string &  name) const

Access MultiBody representation of the robot

◆ bodyPosW() [1/3]

std::vector<sva::PTransformd>& mc_rbdyn::Robot::bodyPosW ( )

Equivalent to robot.mbc().bodyPosW

◆ bodyPosW() [2/3]

const std::vector<sva::PTransformd>& mc_rbdyn::Robot::bodyPosW ( ) const

Equivalent to robot.mbc().bodyPosW (const)

◆ bodyPosW() [3/3]

const sva::PTransformd& mc_rbdyn::Robot::bodyPosW ( const std::string &  name) const

Access the position of body name in world coordinates

Exceptions
Ifthe body does not exist within the robot

◆ bodySensor() [1/2]

const BodySensor& mc_rbdyn::Robot::bodySensor ( ) const
inlinenoexcept

Return the first BodySensor in the robot (const)

◆ bodySensor() [2/2]

const BodySensor& mc_rbdyn::Robot::bodySensor ( const std::string &  name) const

Return a specific BobySensor by name

Parameters
nameName of the sensor
Exceptions
Ifthe sensor does not exist

◆ bodySensors()

const BodySensorVector& mc_rbdyn::Robot::bodySensors ( ) const
inlinenoexcept

Return all body sensors (const)

◆ bodyTransform() [1/2]

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.

◆ bodyTransform() [2/2]

const sva::PTransformd& mc_rbdyn::Robot::bodyTransform ( int  bodyIndex) const

Access body transform by index

◆ bodyTransforms()

const std::vector<sva::PTransformd>& mc_rbdyn::Robot::bodyTransforms ( ) const

Access body transform vector

◆ bodyVelB() [1/3]

std::vector<sva::MotionVecd>& mc_rbdyn::Robot::bodyVelB ( )

Equivalent to robot.mbc().bodyVelB

◆ bodyVelB() [2/3]

const std::vector<sva::MotionVecd>& mc_rbdyn::Robot::bodyVelB ( ) const

Equivalent to robot.mbc().bodyVelB (const)

◆ bodyVelB() [3/3]

const sva::MotionVecd& mc_rbdyn::Robot::bodyVelB ( const std::string &  name) const

Access the velocity of body name in body coordinates

Exceptions
Ifthe body doest not exist within the robot

◆ bodyVelW() [1/3]

std::vector<sva::MotionVecd>& mc_rbdyn::Robot::bodyVelW ( )

Equivalent to robot.mbc().bodyVelW

◆ bodyVelW() [2/3]

const std::vector<sva::MotionVecd>& mc_rbdyn::Robot::bodyVelW ( ) const

Equivalent to robot.mbc().bodyVelW (const)

◆ bodyVelW() [3/3]

const sva::MotionVecd& mc_rbdyn::Robot::bodyVelW ( const std::string &  name) const

Access the velocity of body name in world coordinates

Exceptions
Ifthe body doest not exist within the robot

◆ bodyWrench()

sva::ForceVecd mc_rbdyn::Robot::bodyWrench ( const std::string &  bodyName) const

Compute the gravity-free wrench in body frame

Note
If the body is indirectly attached to the sensor (i.e there are joints in-between), then the kinematic transformation will be taken into account but the effect of bodies in-between is not accounted for in the returned wrench.
Parameters
bodyNameA body attached to a force sensor
Returns
Measured wrench in body frame
Exceptions
Ifno sensor is attached to this surface

◆ collisionTransform()

const sva::PTransformd& mc_rbdyn::Robot::collisionTransform ( const std::string &  cName) const

Access transformation between the collision mesh and the body

◆ com()

Eigen::Vector3d mc_rbdyn::Robot::com ( ) const

Compute and returns the current robot's CoM

◆ comAcceleration()

Eigen::Vector3d mc_rbdyn::Robot::comAcceleration ( ) const

Compute and returns the current robot's CoM acceleration

◆ comVelocity()

Eigen::Vector3d mc_rbdyn::Robot::comVelocity ( ) const

Compute and returns the current robot's CoM velocity

◆ controlTorque() [1/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::controlTorque ( ) const
inlinenoexcept

Access the desired control torque

◆ controlTorque() [2/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::controlTorque ( )
inlinenoexcept

Access the desired control torque

◆ convex() [1/2]

convex_pair_t& mc_rbdyn::Robot::convex ( const std::string &  cName)

Access a convex named cName

Returns
a pair giving the convex's parent body and the sch::Object object

◆ convex() [2/2]

const convex_pair_t& mc_rbdyn::Robot::convex ( const std::string &  cName) const

Access a convex named cName (const)

◆ convexes()

const std::map<std::string, convex_pair_t>& mc_rbdyn::Robot::convexes ( ) const

Access all convexes available in this robot

Returns
a map where keys are the convex name and values are those returned by convex

◆ cop()

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

Parameters
frameA frame attached to a force sensor
min_pressureMinimum pressure in N (default 0.5N).
Returns
Measured cop in provided frame
  • CoP if pressure >= min_pressure
  • Zero otherwise
Exceptions
Ifthe frame does not exist or no sensor is attached to this frame

◆ copW()

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

Parameters
frameA frame attached to a force sensor
min_pressureMinimum pressure in N (default 0.5N).
Returns
Measured cop in inertial frame
  • CoP if pressure >= min_pressure
  • Zero otherwise
Exceptions
Ifthe frame does not exist or no sensor is attached to this frame

◆ copyLoadedData()

void mc_rbdyn::Robot::copyLoadedData ( Robot destination) const
protected

Copy loaded data from this robot to a new robot

◆ copySurface()

mc_rbdyn::Surface& mc_rbdyn::Robot::copySurface ( const std::string &  sName,
const std::string &  name 
)

Copy an existing surface with a new name

◆ data()

const RobotDataPtr mc_rbdyn::Robot::data ( ) const
inlinenoexcept

Access the data associated to this object

◆ device() [1/2]

template<typename T >
T& mc_rbdyn::Robot::device ( const std::string &  name)
inline

Non-const variant

◆ device() [2/2]

template<typename T >
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

Parameters
nameName of the device
Template Parameters
Ttype of the device requested
Exceptions
Ifthe device does not exist or does not have the right type

◆ devices()

const DevicePtrVector& mc_rbdyn::Robot::devices ( ) const
inlinenoexcept

Get all devices attached to a robot

◆ encoderValues()

const std::vector<double>& mc_rbdyn::Robot::encoderValues ( ) const
inlinenoexcept

Return the encoder values

◆ encoderVelocities()

const std::vector<double>& mc_rbdyn::Robot::encoderVelocities ( ) const
inlinenoexcept

Return the encoder velocities

◆ eulerIntegration() [1/2]

void mc_rbdyn::Robot::eulerIntegration ( double  step)

Apply Euler integration to the robot using step timestep

◆ eulerIntegration() [2/2]

void mc_rbdyn::Robot::eulerIntegration ( rbd::MultiBodyConfig &  mbc,
double  step 
) const

Apply Euler integration to mbc using the robot's mb() and step timestep

◆ findBodyForceSensor()

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

◆ findIndirectForceSensorBodyName()

std::string mc_rbdyn::Robot::findIndirectForceSensorBodyName ( const std::string &  bodyName) const
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.

Parameters
bodyNameName of the body to which the sensor is attached
Returns
Body name to which the sensor is attached when found. Empty string otherwise

◆ fixCollisionTransforms()

void mc_rbdyn::Robot::fixCollisionTransforms ( )
protected

Used to set the collision transforms correctly

◆ fixSurface()

void mc_rbdyn::Robot::fixSurface ( Surface surface)
protected

Used to set the specified surface X_b_s correctly

This function should only be called once per surface.

Parameters
surfacesSurface that need to be modified

◆ fixSurfaces()

void mc_rbdyn::Robot::fixSurfaces ( )
protected

Used to set all robot surfaces' X_b_s correctly

This updates all surfaces in surfaces_ vector and should only be called once

◆ flexibility() [1/2]

std::vector<Flexibility>& mc_rbdyn::Robot::flexibility ( )

Return the flexibilities of the robot

◆ flexibility() [2/2]

const std::vector<Flexibility>& mc_rbdyn::Robot::flexibility ( ) const

Return the flexibilities of the robot (const)

◆ forceSensor()

const ForceSensor& mc_rbdyn::Robot::forceSensor ( const std::string &  name) const

Return a force sensor by name

Parameters
nameName of the sensor
Returns
The sensor named name
Exceptions
Ifno sensor with this name exists

◆ forceSensors()

const std::vector<ForceSensor>& mc_rbdyn::Robot::forceSensors ( ) const
inlinenoexcept

Returns all force sensors (const)

◆ forwardAcceleration() [1/2]

void mc_rbdyn::Robot::forwardAcceleration ( const sva::MotionVecd &  A_0 = sva::MotionVecd(Eigen::Vector6d::Zero()))

Apply forward acceleration to the robot

◆ forwardAcceleration() [2/2]

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()

◆ forwardKinematics() [1/2]

void mc_rbdyn::Robot::forwardKinematics ( )

Apply forward kinematics to the robot

◆ forwardKinematics() [2/2]

void mc_rbdyn::Robot::forwardKinematics ( rbd::MultiBodyConfig &  mbc) const

Apply forward kinematics to mbc using the robot's mb()

◆ forwardVelocity() [1/2]

void mc_rbdyn::Robot::forwardVelocity ( )

Apply forward velocity to the robot

◆ forwardVelocity() [2/2]

void mc_rbdyn::Robot::forwardVelocity ( rbd::MultiBodyConfig &  mbc) const

Apply forward velocity to mbc using the robot's mb()

◆ frame() [1/2]

RobotFrame& mc_rbdyn::Robot::frame ( const std::string &  name)
inline

Access the frame named name (non-const)

Exceptions
Ifthe frame does not exist

◆ frame() [2/2]

const RobotFrame& mc_rbdyn::Robot::frame ( const std::string &  name) const
inline

Access the frame named name

Exceptions
Ifthe frame does not exist

◆ frames()

std::vector<std::string> mc_rbdyn::Robot::frames ( ) const

Returns the list of available frames in this robot

◆ gripper() [1/2]

mc_control::Gripper& mc_rbdyn::Robot::gripper ( const std::string &  gripper)

Access a gripper by name

Parameters
gripperGripper name
Exceptions
Ifthe gripper does not exist within this robot

◆ gripper() [2/2]

const mc_control::Gripper& mc_rbdyn::Robot::gripper ( const std::string &  gripper) const

Access a gripper by name

Parameters
gripperGripper name
Exceptions
Ifthe gripper does not exist within this robot

◆ grippers()

const std::vector<mc_control::GripperRef>& mc_rbdyn::Robot::grippers ( ) const
inlinenoexcept

Access all grippers

◆ grippersByName()

const std::unordered_map<std::string, mc_control::GripperPtr>& mc_rbdyn::Robot::grippersByName ( ) const
inlinenoexcept

◆ hasBody()

bool mc_rbdyn::Robot::hasBody ( const std::string &  name) const

Returns true if the robot has a body named name

◆ hasBodySensor()

bool mc_rbdyn::Robot::hasBodySensor ( const std::string &  name) const
inlinenoexcept

Return true if the robot has a body sensor named name

Parameters
nameName of the body sensor

◆ hasConvex()

bool mc_rbdyn::Robot::hasConvex ( const std::string &  name) const

Check if a convex name exists

Returns
True if the convex exists, false otherwise

◆ hasDevice()

template<typename T >
bool mc_rbdyn::Robot::hasDevice ( const std::string &  name) const
noexcept

Returns true if a generic device of type T and named name exists in the robot

Parameters
nameName of the device
Template Parameters
TType of device requested

◆ hasForceSensor()

bool mc_rbdyn::Robot::hasForceSensor ( const std::string &  name) const
inlinenoexcept

Check if a force sensor exists

Parameters
nameName of the sensor
Returns
True if the sensor exists, false otherwise

◆ hasFrame()

bool mc_rbdyn::Robot::hasFrame ( const std::string &  name) const
inlinenoexcept

Returns true if the robot has a frame named name

◆ hasGripper()

bool mc_rbdyn::Robot::hasGripper ( const std::string &  gripper) const

Checks whether a gripper is part of this robot

◆ hasJoint()

bool mc_rbdyn::Robot::hasJoint ( const std::string &  name) const

Returns true if the robot has a joint named name

◆ hasSensor()

template<typename T >
bool mc_rbdyn::Robot::hasSensor ( const std::string &  name) const
inlinenoexcept

Alias for

See also
hasDevice

◆ hasSurface()

bool mc_rbdyn::Robot::hasSurface ( const std::string &  surface) const

Check if a surface surface exists

Returns
True if the surface exists, false otherwise

◆ indirectBodyForceSensor()

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.

Returns
The sensor to which the body is indirectly attached
Exceptions
Ifno sensor is found between the body and the root

◆ indirectSurfaceForceSensor()

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.

Parameters
surfaceName of surface indirectly attached to the sensor
Returns
The sensor to which the surface is indirectly attached
Exceptions
Ifno sensor is found between the surface and the root

◆ jl() [1/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::jl ( )

Access the robot's angular lower jerk limits

◆ jl() [2/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::jl ( ) const

Access the robot's angular lower jerk limits (const)

◆ jointHasJointSensor()

bool mc_rbdyn::Robot::jointHasJointSensor ( const std::string &  joint) const
inlinenoexcept

Return true if the specified joint has a joint sensor attached to it

Parameters
jointJoint to query

◆ jointIndexByName()

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

Note
Joint indices can be -1 for joints present in refJointOrder but not in the robot's mbc (such as filtered joints in some robot modules)
Parameters
jointIndexJoint index in refJointOrder
Returns
joint index in the mbc
Exceptions
IfjointIndex >= refJointOrder.size()

◆ jointIndexInMBC()

int mc_rbdyn::Robot::jointIndexInMBC ( size_t  jointIndex) const

Returns the joint index in the mbc of the joint with index jointIndex in refJointOrder

Note
Joint indices can be -1 for joints present in refJointOrder but not in the robot's mbc (such as filtered joints in some robot modules)
Parameters
jointIndexJoint index in refJointOrder
Returns
joint index in the mbc
Exceptions
IfjointIndex >= refJointOrder.size()

◆ jointJointSensor()

const JointSensor& mc_rbdyn::Robot::jointJointSensor ( const std::string &  joint) const

Return a specific JointSensor by joint name

Parameters
jointName of the joint
Exceptions
Ifthere is no sensor attached to the joint

◆ jointSensors()

const std::vector<JointSensor>& mc_rbdyn::Robot::jointSensors ( ) const
inlinenoexcept

Return all joint sensors (const)

◆ jointTorque() [1/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::jointTorque ( )

Equivalent to robot.mbc().jointTorque

◆ jointTorque() [2/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::jointTorque ( ) const

Equivalent to robot.mbc().jointTorque (const)

◆ jointTorques()

const std::vector<double>& mc_rbdyn::Robot::jointTorques ( ) const
inlinenoexcept

Return the joint torques from sensors

◆ ju() [1/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::ju ( )

Access the robot's angular upper jerk limits

◆ ju() [2/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::ju ( ) const

Access the robot's angular upper jerk limits (const)

◆ loadRSDFFromDir()

void mc_rbdyn::Robot::loadRSDFFromDir ( const std::string &  surfaceDir)

Load surfaces from the directory surfaceDir

◆ makeFrame()

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

Parameters
nameName of the frame
frameParent frame of this frame
X_p_fTransformation from the parent frame to the frame
bakedAttach the newly created frame to parent parent's body rather than parent if true
Returns
The newly created frame
Exceptions
Ifparent does not belong to this robot or if name already exists in this robot

◆ makeFrames()

void mc_rbdyn::Robot::makeFrames ( std::vector< mc_rbdyn::RobotModule::FrameDescription frames)

Create new frames attached to this robot

Parameters
framesDescription of the frames
Exceptions
Ifany of the frames' parent does not belong to this robot or if name already exists in this robot

◆ makeTemporaryFrame()

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

Parameters
nameName of the frame
frameParent frame of this frame
X_p_fTransformation from the parent frame to the frame
bakedAttach the newly created frame to parent parent's body rather than parent if true
Returns
The newly created frame
Exceptions
Ifparent does not belong to this robot

◆ mass()

double mc_rbdyn::Robot::mass ( ) const
inlinenoexcept

Compute and returns the mass of the robot

◆ mb() [1/2]

rbd::MultiBody& mc_rbdyn::Robot::mb ( )

Access MultiBody representation of the robot

◆ mb() [2/2]

const rbd::MultiBody& mc_rbdyn::Robot::mb ( ) const

Access MultiBody representation of the robot (const)

◆ mbc() [1/2]

rbd::MultiBodyConfig& mc_rbdyn::Robot::mbc ( )

Access MultiBodyConfig of the robot's mb()

◆ mbc() [2/2]

const rbd::MultiBodyConfig& mc_rbdyn::Robot::mbc ( ) const

Access MultiBodyConfig of the robot's mb() (const)

◆ mbg() [1/2]

rbd::MultiBodyGraph& mc_rbdyn::Robot::mbg ( )

Access MultiBodyGraph that generated the robot's mb()

◆ mbg() [2/2]

const rbd::MultiBodyGraph& mc_rbdyn::Robot::mbg ( ) const

Access MultiBodyGraph that generated the robot's mb() (const)

◆ module()

const RobotModule& mc_rbdyn::Robot::module ( ) const

Retrieve the associated RobotModule

◆ name()

const std::string& mc_rbdyn::Robot::name ( ) const

Returns the name of the robot

Note
To rename a robot, use Robots::rename(const std::string &, const std::string &)

◆ netWrench()

sva::ForceVecd mc_rbdyn::Robot::netWrench ( const std::vector< std::string > &  sensorNames) const

Computes net total wrench from a list of sensors.

Parameters
sensorNamesNames of all sensors used to compute the net wrench
Returns
Net total wrench (without gravity) in the inertial frame

◆ operator=()

Robot& mc_rbdyn::Robot::operator= ( Robot &&  )

◆ posW() [1/2]

const sva::PTransformd& mc_rbdyn::Robot::posW ( ) const

Return the robot's global pose

◆ posW() [2/2]

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).

Parameters
ptThe new global pose
Exceptions
Ifjoint(0) is neither free flyer nor fixed
Note
This function takes care of calling rbd::forwardKinematics

◆ q() [1/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::q ( )

Equivalent to robot.mbc().q

◆ q() [2/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::q ( ) const

Equivalent to robot.mbc().q (const)

◆ ql() [1/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::ql ( )

Access the robot's angular lower limits

◆ ql() [2/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::ql ( ) const

Access the robot's angular lower limits (const)

◆ qu() [1/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::qu ( )

Access the robot's angular upper limits

◆ qu() [2/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::qu ( ) const

Access the robot's angular upper limits (const)

◆ refJointOrder()

const std::vector<std::string>& mc_rbdyn::Robot::refJointOrder ( ) const
inline

Return the reference joint order for this robot

◆ removeConvex()

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.

Parameters
nameName of the convex

◆ robotIndex()

unsigned int mc_rbdyn::Robot::robotIndex ( ) const

Access the robot's index in robots()

◆ robots() [1/2]

const mc_rbdyn::Robots& mc_rbdyn::Robot::robots ( ) const
inlinenoexcept

Access Robots instance this instance belongs to (const)

◆ robots() [2/2]

mc_rbdyn::Robots& mc_rbdyn::Robot::robots ( )
inlinenoexcept

Access Robots instance this instance belongs to

◆ sensor() [1/2]

template<typename T >
T& mc_rbdyn::Robot::sensor ( const std::string &  name)
inline

Alias for

See also
device

◆ sensor() [2/2]

template<typename T >
const T& mc_rbdyn::Robot::sensor ( const std::string &  name) const
inline

Alias for

See also
device

◆ stance()

std::map<std::string, std::vector<double> > mc_rbdyn::Robot::stance ( ) const

Return the robot's default stance (e.g. half-sitting for humanoid)

◆ surface() [1/2]

mc_rbdyn::Surface& mc_rbdyn::Robot::surface ( const std::string &  sName)

Access a surface by its name sName

◆ surface() [2/2]

const mc_rbdyn::Surface& mc_rbdyn::Robot::surface ( const std::string &  sName) const

Access a surface by its name sName (const)

◆ surfaceForceSensor()

const ForceSensor& mc_rbdyn::Robot::surfaceForceSensor ( const std::string &  surfaceName) const

Return a force sensor attached to the provided surface

Parameters
surfaceName of the surface to which the sensor is attached
Returns
The attached sensor
Exceptions
Ifno sensor is directly attached to this surface
See also
ForceSensor & indirectBodyForceSensor(const std::string & surface); To get a sensor directly or indirectly attached to the surface.

◆ surfaceHasForceSensor()

bool mc_rbdyn::Robot::surfaceHasForceSensor ( const std::string &  surface) const
inline

Checks if the surface has a force sensor directly attached to it.

Parameters
surfaceName of the surface to which the sensor is directly attached
See also
surfaceHasIndirectForceSensor(const std::string &) if you wish to check whether a sensor is indirectly attached to a body
Exceptions
Ifsurface does not exist in this robot
Returns
True if the surface has a force sensor attached to it, false otherwise

◆ surfaceHasIndirectForceSensor()

bool mc_rbdyn::Robot::surfaceHasIndirectForceSensor ( const std::string &  surface) const
inline

Check if the surface has a force sensor attached to it (directly or indirectly)

Parameters
surfaceName of the surface to which the sensor is directly attached
Returns
True if the surface has a force sensor attached to it, false otherwise

◆ surfacePose()

sva::PTransformd mc_rbdyn::Robot::surfacePose ( const std::string &  sName) const

Get the pose of a surface frame with respect to the inertial frame.

Parameters
sNameName of surface frame.

◆ surfaces()

const std::map<std::string, mc_rbdyn::SurfacePtr>& mc_rbdyn::Robot::surfaces ( ) const

Returns all available surfaces

◆ surfaceWrench()

sva::ForceVecd mc_rbdyn::Robot::surfaceWrench ( const std::string &  surfaceName) const

Compute the gravity-free wrench in surface frame

Note
If the surface is indirectly attached to the sensor (i.e there are joints in-between), then the kinematic transformation will be taken into account but the effect of bodies in-between is not accounted for in the returned wrench.
Parameters
surfaceNameA surface attached to a force sensor
Returns
Measured wrench in surface frame
Exceptions
Ifno sensor is attached to this surface

◆ tdl() [1/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::tdl ( )

Access the robot's angular lower torque-derivative limits

◆ tdl() [2/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::tdl ( ) const

Access the robot's angular lower torque-derivative limits (const)

◆ tdu() [1/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::tdu ( )

Access the robot's angular upper torque-derivative limits

◆ tdu() [2/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::tdu ( ) const

Access the robot's angular upper torque-derivative limits (const)

◆ tl() [1/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::tl ( )

Access the robot's angular lower torque limits

◆ tl() [2/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::tl ( ) const

Access the robot's angular lower torque limits (const)

◆ tu() [1/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::tu ( )

Access the robot's angular upper torque limits

◆ tu() [2/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::tu ( ) const

Access the robot's angular upper torque limits (const)

◆ tvmConvex()

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

Parameters
nameName of the convex
Exceptions
Ifthe convex does not exist

◆ tvmRobot()

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

◆ velW() [1/2]

const sva::MotionVecd& mc_rbdyn::Robot::velW ( ) const

Return the robot's floating base velocity expressed in the inertial frame

◆ velW() [2/2]

void mc_rbdyn::Robot::velW ( const sva::MotionVecd &  vel)

Update the robot's floating base velocity.

Parameters
velNew floating base velocity in the inertial frame.
Note
This function takes care of calling rbd::forwardVelocity

◆ vl() [1/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::vl ( )

Access the robot's angular lower velocity limits

◆ vl() [2/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::vl ( ) const

Access the robot's angular lower velocity limits (const)

◆ vu() [1/2]

std::vector<std::vector<double> >& mc_rbdyn::Robot::vu ( )

Access the robot's angular upper velocity limits

◆ vu() [2/2]

const std::vector<std::vector<double> >& mc_rbdyn::Robot::vu ( ) const

Access the robot's angular upper velocity limits (const)

◆ X_b1_b2()

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

Parameters
b1name of first body
b2name of second body
Exceptions
Ifb1 or b2 does not exist within the robot

◆ zmp() [1/8]

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

Parameters
sensorNamesNames of all sensors attached to a link in contact with the environment

◆ zmp() [2/8]

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

Parameters
sensorNamesNames of all sensors attached to a link in contact with the environment

◆ zmp() [3/8]

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.

Parameters
netTotalWrenchTotal wrench for all links in contact
plane_pArbitrary point on the ZMP plane
plane_nNormal 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).
Returns
zmp expressed in the requested plane
Exceptions
Toprevent 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).

See also
Eigen::Vector3d mc_rbdyn::zmp(const sva::ForceVecd & netTotalWrench, const Eigen::Vector3d & plane_p, const Eigen::Vector3d & plane_n, double minimalNetNormalForce)

◆ zmp() [4/8]

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

See also
Eigen::Vector3d mc_rbdyn::zmp(const sva::ForceVecd & netTotalWrench, const sva::PTransformd & zmpFrame, double minimalNetNormalForce) const;
Parameters
netTotalWrench
zmpFrameFrame 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.
Returns
ZMP expressed in the plane defined by the zmpFrame frame.

◆ zmp() [5/8]

bool mc_rbdyn::Robot::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

Computes the ZMP from sensor names and a plane

See zmpDoc

Parameters
sensorNamesNames of all sensors attached to a link in contact with the environment

◆ zmp() [6/8]

bool mc_rbdyn::Robot::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.

See zmpDoc

Parameters
sensorNamesNames of all sensors attached to a link in contact with the environment

◆ zmp() [7/8]

bool mc_rbdyn::Robot::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.

Parameters
zmpOutOutput of the ZMP computation expressed in the requested frame
netTotalWrenchTotal wrench for all links in contact
plane_pArbitrary point on the ZMP plane
plane_nNormal 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).
Returns
True if the computation was successful, false otherwise and zmpOut is untouched
See also
bool mc_rbdyn::zmp(Eigen::Vector3d & zmpOut, const sva::ForceVecd & netTotalWrench, const Eigen::Vector3d & plane_p, const Eigen::Vector3d & plane_n, double minimalNetNormalForce)

◆ zmp() [8/8]

bool mc_rbdyn::Robot::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.

See zmpDoc

See also
Eigen::Vector3d mc_rbdyn::zmp(Eigen::Vector3d & zmpOut, const sva::ForceVecd & netTotalWrench, const sva::PTransformd & zmpFrame, double minimalNetNormalForce)
Parameters
zmpOutOutput of the ZMP computation expressed in the plane defined by the zmpFrame frame
netTotalWrench
zmpFrameFrame 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.
Returns
True if the computation was successful, false otherwise and zmpOut is untouched

◆ zmpTarget() [1/2]

const Eigen::Vector3d& mc_rbdyn::Robot::zmpTarget ( ) const

Returns the target zmp

Returns
Target ZMP. See zmpTarget(Eigen::Vector3d) for details.

◆ zmpTarget() [2/2]

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

Parameters
zmpNote 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)

Friends And Related Function Documentation

◆ Robots

friend struct Robots
friend

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