Go to the documentation of this file.
32 using namespace trajectories;
37 double dt,
bool verbose)
82 m_ub = Vector::Constant(4, 1, 1e10);
83 m_lb = Vector::Constant(4, 1, -1e10);
103 for (
int i = 0;
i <
m_na;
i++) {
119 "The size of the mask vector needs to equal " +
126 for (
unsigned int i = 0;
i <
m.size();
i++)
129 m(
i) == 1.0,
"Mask entries need to be either 0.0 or 1.0");
166 lower.size() ==
m_na,
167 "The size of the lower position bounds vector needs to equal " +
168 std::to_string(
m_na));
170 upper.size() ==
m_na,
171 "The size of the upper position bounds vector needs to equal " +
172 std::to_string(
m_na));
181 upper.size() ==
m_na,
182 "The size of the (absolute) velocity bounds vector needs to equal " +
183 std::to_string(
m_na));
190 upper.size() ==
m_na,
191 "The size of the (absolute) acceleration bounds vector needs to equal " +
192 std::to_string(
m_na));
217 bool impose_position_bounds,
bool impose_velocity_bounds,
218 bool impose_viability_bounds,
bool impose_acceleration_bounds) {
228 for (
int i = 0;
i <
m_na;
i++) {
231 std::cout <<
"State of joint " <<
i
232 <<
" is not viable because q[i]< qMin[i] : " << qa[
i] <<
"<"
239 std::cout <<
"State of joint " <<
i
240 <<
" is not viable because qa[i]>m_qMax[i] : " << qa[
i] <<
">"
247 std::cout <<
"State (q,dq) :(" << qa[
i] <<
"," << dqa[
i]
248 <<
") of joint " <<
i
249 <<
" is not viable because |dq|>dqMax : " << std::abs(dqa[
i])
256 if (dqa[
i] > (dqMaxViab +
m_eps)) {
258 std::cout <<
"State (q,dq,dqMaxViab) :(" << qa[
i] <<
"," << dqa[
i]
259 <<
"," << dqMaxViab <<
") of joint " <<
i
260 <<
" is not viable because dq>dqMaxViab : " << dqa[
i] <<
">"
261 << dqMaxViab << std::endl;
267 if (dqa[
i] < (dqMinViab +
m_eps)) {
269 std::cout <<
"State (q,dq,dqMinViab) :(" << qa[
i] <<
"," << dqa[
i]
270 <<
"," << dqMinViab <<
") of joint " <<
i
271 <<
" is not viable because dq<dqMinViab : " << dqa[
i] <<
"<"
272 << dqMinViab << std::endl;
289 for (
int i = 0;
i <
m_na;
i++) {
299 std::cout <<
"WARNING qa[i]==m_qMin[i] for joint" <<
i << std::endl;
300 std::cout <<
"You are going to violate the position bound " <<
i
314 std::cout <<
"WARNING qa[i]==m_qMax[i] for joint" <<
i << std::endl;
315 std::cout <<
"You are going to violate the position bound " <<
i
343 for (
int i = 0;
i <
m_na;
i++) {
349 std::cout <<
"Error: state (" << qa[
i] <<
"," << dqa[
i] <<
") of joint "
350 <<
i <<
"not viable because delta is negative: " <<
m_delta_1
359 std::cout <<
"Error: state (" << qa[
i] <<
"," << dqa[
i] <<
") of joint "
360 <<
i <<
"not viable because delta is negative: " <<
m_delta_2
376 for (
int i = 0;
i <
m_na;
i++) {
378 std::cout <<
"WARNING: specified state ( < " <<
m_qa[
i] <<
" , "
411 m_ub.setConstant(4, 1, 1e10);
412 m_lb.setConstant(4, 1, -1e10);
415 for (
int i = 0;
i <
m_na;
i++) {
431 std::cout <<
"Conflict between pos/vel/acc bound ddqMin " <<
m_ddqLB[
i]
432 <<
" ddqMax " <<
m_ddqUB[
i] << std::endl;
433 std::cout <<
"ub " <<
m_ub.transpose() << std::endl;
434 std::cout <<
"lb " <<
m_lb.transpose() << std::endl;
442 std::cout <<
"New bounds are ddqMin " <<
m_ddqLB[
i] <<
" ddqMax "
void setTimeStep(double dt)
const ConstraintBase & getConstraint() const override
int dim() const override
Return the dimension of the task. \info should be overloaded in the child class.
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
void computeAccLimitsFromPosLimits(ConstRefVector q, ConstRefVector dq, bool verbose=true)
bool m_impose_velocity_bounds
Abstract class representing a linear equality/inequality constraint. Equality constraints are represe...
TaskJointPosVelAccBounds(const std::string &name, RobotWrapper &robot, double dt, bool verbose=true)
const Vector & lowerBound() const override
const TSID_DEPRECATED Vector & mask() const
bool m_impose_viability_bounds
Vector m_minus_dq_over_dt
void setPositionBounds(ConstRefVector lower, ConstRefVector upper)
void setVerbose(bool verbose)
void setAccelerationBounds(ConstRefVector upper)
PINOCCHIO_COMPILER_DIAGNOSTIC_POP typedef std::size_t Index
const Vector & getAccelerationBounds() const
void computeAccLimitsFromViability(ConstRefVector q, ConstRefVector dq, bool verbose=true)
bool m_impose_acceleration_bounds
void resize(unsigned int r, unsigned int c) override
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Matrix
bool m_impose_position_bounds
void setImposeBounds(bool impose_position_bounds, bool impose_velocity_bounds, bool impose_viability_bounds, bool impose_acceleration_bounds)
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Wrapper for a robot based on pinocchio.
const Vector & getPositionUpperBounds() const
virtual void setMask(math::ConstRefVector mask) override
void computeAccLimits(ConstRefVector q, ConstRefVector dq, bool verbose=true)
void setVelocityBounds(ConstRefVector upper)
const Vector & upperBound() const override
void isStateViable(ConstRefVector q, ConstRefVector dq, bool verbose=true)
const ConstraintBase & compute(double t, ConstRefVector q, ConstRefVector v, Data &data) override
RobotWrapper & m_robot
Reference on the robot model.
const Vector & getPositionLowerBounds() const
ConstraintInequality m_constraint
math::ConstRefVector ConstRefVector
virtual bool setMatrix(ConstRefMatrix A)
const Vector & getVelocityBounds() const
tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sat May 3 2025 02:48:17