src
tasks
src/tasks/task-actuation-equality.cpp
Go to the documentation of this file.
1
//
2
// Copyright (c) 2021 CNRS INRIA LORIA
3
//
4
// This file is part of tsid
5
// tsid is free software: you can redistribute it
6
// and/or modify it under the terms of the GNU Lesser General Public
7
// License as published by the Free Software Foundation, either version
8
// 3 of the License, or (at your option) any later version.
9
// tsid is distributed in the hope that it will be
10
// useful, but WITHOUT ANY WARRANTY; without even the implied warranty
11
// of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12
// General Lesser Public License for more details. You should have
13
// received a copy of the GNU Lesser General Public License along with
14
// tsid If not, see
15
// <http://www.gnu.org/licenses/>.
16
//
17
18
#include <
tsid/tasks/task-actuation-equality.hpp
>
19
#include "
tsid/robots/robot-wrapper.hpp
"
20
21
namespace
tsid
{
22
namespace
tasks {
23
using namespace
math;
24
using namespace
pinocchio
;
25
26
TaskActuationEquality::TaskActuationEquality
(
const
std::string&
name
,
27
RobotWrapper
&
robot
)
28
:
TaskActuation
(
name
,
robot
), m_constraint(
name
,
robot
.
na
(),
robot
.
na
()) {
29
m_ref
= Vector::Zero(
robot
.na());
30
m_weights
= Vector::Ones(
robot
.na());
31
Vector
m
= Vector::Ones(
robot
.na());
32
mask
(
m
);
33
}
34
35
const
Vector
&
TaskActuationEquality::mask
()
const
{
return
m_mask
; }
36
37
void
TaskActuationEquality::mask
(
const
Vector
&
m
) {
38
PINOCCHIO_CHECK_INPUT_ARGUMENT
(
m
.size() ==
m_robot
.
na
(),
39
"The size of the mask vector needs to equal "
+
40
std::to_string(
m_robot
.
na
()));
41
m_mask
=
m
;
42
43
const
Vector::Index
dim
=
static_cast<
Vector::Index
>
(
m
.sum());
44
Matrix
S
= Matrix::Zero(
dim
,
m_robot
.
na
());
45
m_activeAxes
.resize(
dim
);
46
unsigned
int
j = 0;
47
for
(
unsigned
int
i
= 0;
i
<
m
.size();
i
++)
48
if
(
m
(
i
) != 0.0) {
49
PINOCCHIO_CHECK_INPUT_ARGUMENT
(
50
m
(
i
) == 1.0,
51
"Entries in the mask vector need to be either 0.0 or 1.0"
);
52
S
(j,
i
) =
m_weights
(
i
);
53
m_activeAxes
(j) =
i
;
54
j++;
55
}
56
m_constraint
.
resize
((
unsigned
int
)
dim
,
m_robot
.
na
());
57
m_constraint
.
setMatrix
(
S
);
58
59
for
(
unsigned
int
i
= 0;
i
<
m_activeAxes
.size();
i
++)
60
m_constraint
.
vector
()(
i
) =
61
m_ref
(
m_activeAxes
(
i
)) *
m_weights
(
m_activeAxes
(
i
));
62
}
63
64
int
TaskActuationEquality::dim
()
const
{
return
(
int
)
m_mask
.sum(); }
65
66
// Reference should be the same size as robot.na(), even if a mask is used
67
// (masked dof values will just be ignored)
68
void
TaskActuationEquality::setReference
(
ConstRefVector
ref) {
69
PINOCCHIO_CHECK_INPUT_ARGUMENT
(
70
ref
.size() ==
m_robot
.
na
(),
71
"The size of the reference vector needs to equal "
+
72
std::to_string(
m_robot
.
na
()));
73
m_ref
=
ref
;
74
75
for
(
unsigned
int
i
= 0;
i
<
m_activeAxes
.size();
i
++)
76
m_constraint
.
vector
()(
i
) =
77
m_ref
(
m_activeAxes
(
i
)) *
m_weights
(
m_activeAxes
(
i
));
78
}
79
80
const
Vector
&
TaskActuationEquality::getReference
()
const
{
return
m_ref
; }
81
82
// Weighting vector should be the same size as robot.na(), even if a mask is
83
// used (masked dof values will just be ignored)
84
void
TaskActuationEquality::setWeightVector
(
ConstRefVector
weights) {
85
PINOCCHIO_CHECK_INPUT_ARGUMENT
(
86
weights
.size() ==
m_robot
.
na
(),
87
"The size of the weight vector needs to equal "
+
88
std::to_string(
m_robot
.
na
()));
89
m_weights
=
weights
;
90
91
for
(
unsigned
int
i
= 0;
i
<
m_activeAxes
.size();
i
++) {
92
m_constraint
.
matrix
()(
i
,
m_activeAxes
(
i
)) =
m_weights
(
m_activeAxes
(
i
));
93
m_constraint
.
vector
()(
i
) =
94
m_ref
(
m_activeAxes
(
i
)) *
m_weights
(
m_activeAxes
(
i
));
95
}
96
}
97
98
const
Vector
&
TaskActuationEquality::getWeightVector
()
const
{
99
return
m_weights
;
100
}
101
102
const
ConstraintBase
&
TaskActuationEquality::getConstraint
()
const
{
103
return
m_constraint
;
104
}
105
106
const
ConstraintBase
&
TaskActuationEquality::compute
(
const
double
,
107
ConstRefVector
,
108
ConstRefVector
,
Data
&) {
109
return
m_constraint
;
110
}
111
112
}
// namespace tasks
113
}
// namespace tsid
tsid::tasks::TaskActuationEquality::m_ref
Vector m_ref
Definition:
tasks/task-actuation-equality.hpp:57
tsid::tasks::TaskActuationEquality::dim
int dim() const override
Return the dimension of the task. \info should be overloaded in the child class.
Definition:
src/tasks/task-actuation-equality.cpp:64
tsid::tasks::TaskActuationEquality::getConstraint
const ConstraintBase & getConstraint() const override
Definition:
src/tasks/task-actuation-equality.cpp:102
pinocchio::DataTpl
PINOCCHIO_CHECK_INPUT_ARGUMENT
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
tsid::math::ConstraintEquality::vector
const Vector & vector() const override
Definition:
src/math/constraint-equality.cpp:55
task-actuation-equality.hpp
tsid::math::ConstraintBase
Abstract class representing a linear equality/inequality constraint. Equality constraints are represe...
Definition:
constraint-base.hpp:35
tsid::tasks::TaskActuationEquality::mask
const Vector & mask() const
Definition:
src/tasks/task-actuation-equality.cpp:35
i
int i
ref
list ref
demo_quadruped.robot
robot
Definition:
demo_quadruped.py:51
tsid::tasks::TaskActuationEquality::m_mask
Vector m_mask
Definition:
tasks/task-actuation-equality.hpp:55
tsid::tasks::TaskActuationEquality::setWeightVector
void setWeightVector(math::ConstRefVector weights)
Definition:
src/tasks/task-actuation-equality.cpp:84
tsid::math::ConstraintEquality::resize
void resize(unsigned int r, unsigned int c) override
Definition:
src/math/constraint-equality.cpp:46
Index
PINOCCHIO_COMPILER_DIAGNOSTIC_POP typedef std::size_t Index
S
S
tsid::math::ConstraintBase::matrix
virtual const Matrix & matrix() const
Definition:
constraint-base.cpp:35
robot-wrapper.hpp
tsid::tasks::TaskActuationEquality::m_weights
Vector m_weights
Definition:
tasks/task-actuation-equality.hpp:58
tsid::math::Matrix
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Matrix
Definition:
math/fwd.hpp:36
setup.name
name
Definition:
setup.in.py:179
tsid::tasks::TaskActuationEquality::m_constraint
ConstraintEquality m_constraint
Definition:
tasks/task-actuation-equality.hpp:59
weights
tuple weights
tsid::tasks::TaskActuationEquality::compute
const ConstraintBase & compute(double t, ConstRefVector q, ConstRefVector v, Data &data) override
Definition:
src/tasks/task-actuation-equality.cpp:106
tsid::tasks::TaskActuationEquality::getWeightVector
const Vector & getWeightVector() const
Definition:
src/tasks/task-actuation-equality.cpp:98
tsid
Definition:
bindings/python/constraint/constraint-bound.cpp:21
test_Constraint.m
int m
Definition:
test_Constraint.py:41
tsid::tasks::TaskActuation
Definition:
task-actuation.hpp:25
tsid::robots::RobotWrapper
Wrapper for a robot based on pinocchio.
Definition:
robots/robot-wrapper.hpp:37
test_Tasks.na
int na
Definition:
test_Tasks.py:95
tsid::tasks::TaskActuationEquality::TaskActuationEquality
TaskActuationEquality(const std::string &name, RobotWrapper &robot)
Definition:
src/tasks/task-actuation-equality.cpp:26
tsid::tasks::TaskBase::m_robot
RobotWrapper & m_robot
Reference on the robot model.
Definition:
task-base.hpp:64
tsid::tasks::TaskBase::ConstRefVector
math::ConstRefVector ConstRefVector
Definition:
task-base.hpp:39
tsid::tasks::TaskActuationEquality::Vector
math::Vector Vector
Definition:
tasks/task-actuation-equality.hpp:31
tsid::robots::RobotWrapper::na
virtual int na() const
Definition:
src/robots/robot-wrapper.cpp:98
tsid::tasks::TaskActuationEquality::m_activeAxes
VectorXi m_activeAxes
Definition:
tasks/task-actuation-equality.hpp:56
tsid::math::ConstraintBase::setMatrix
virtual bool setMatrix(ConstRefMatrix A)
Definition:
constraint-base.cpp:39
tsid::tasks::TaskActuationEquality::setReference
void setReference(math::ConstRefVector ref)
Definition:
src/tasks/task-actuation-equality.cpp:68
pinocchio
tsid::tasks::TaskActuationEquality::getReference
const Vector & getReference() const
Definition:
src/tasks/task-actuation-equality.cpp:80
tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sat May 3 2025 02:48:17