Class TorqueLimits
Defined in File TorqueLimits.h
Inheritance Relationships
Base Type
public OpenSoT::Constraint< Eigen::MatrixXd, Eigen::VectorXd >
(Template Class Constraint)
Class Documentation
-
class TorqueLimits : public OpenSoT::Constraint<Eigen::MatrixXd, Eigen::VectorXd>
The TorqueLimits class implements torque limits in inverse dynamics:
NOTE: torque limits contains as well limits on floating base torque (that should be zeros)-tau_lims - h <= Mqddot - Jc'Fc <= tau_lims + h
Public Types
-
typedef std::shared_ptr<TorqueLimits> Ptr
Public Functions
-
TorqueLimits(const XBot::ModelInterface &robot, const AffineHelper &qddot, const std::vector<AffineHelper> &wrenches, const std::vector<std::string> &contact_links, const Eigen::VectorXd &torque_limits)
-
- Parameters
robot –
qddot –
wrenches –
contact_links –
torque_limits –
-
virtual void update()
Updates the A, b, Aeq, beq, Aineq, b*Bound matrices.
-
void setTorqueLimits(const Eigen::VectorXd &torque_limits)
setTorqueLimits to set new torque limits
- Parameters
torque_limits –
-
bool enableContact(const std::string &contact_link)
enableContact for task computation
- Parameters
contact_link –
- Returns
false if the contact is not in the contacts vector
-
bool disableContact(const std::string &contact_link)
disableContact for task computation
- Parameters
contact_link –
- Returns
false if the contact is not in the contacts vector
-
const std::vector<bool> &getEnabledContacts() const
getEnabledContacts
- Returns
vector of booleans indicating active contact (in the same order as in contact_links)
-
typedef std::shared_ptr<TorqueLimits> Ptr