Skip to content

Commit 38cd655

Browse files
author
earlaud
committed
Use Eigen::Ref
1 parent 1e7d294 commit 38cd655

File tree

1 file changed

+9
-6
lines changed

1 file changed

+9
-6
lines changed

include/simple-mpc/inverse-dynamics.hpp

Lines changed: 9 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -141,11 +141,11 @@ namespace simple_mpc
141141
}
142142

143143
void setTarget(
144-
const Eigen::VectorXd & q_target,
145-
const Eigen::VectorXd & v_target,
146-
const Eigen::VectorXd & a_target,
144+
const Eigen::Ref<const Eigen::VectorXd> & q_target,
145+
const Eigen::Ref<const Eigen::VectorXd> & v_target,
146+
const Eigen::Ref<const Eigen::VectorXd> & a_target,
147147
const std::vector<bool> & contact_state_target,
148-
const Eigen::VectorXd & f_target)
148+
const Eigen::Ref<const Eigen::VectorXd> & f_target)
149149
{
150150
data_handler_.updateInternalData(q_target, v_target, false);
151151

@@ -186,8 +186,11 @@ namespace simple_mpc
186186
solver_->resize(formulation_.nVar(), formulation_.nEq(), formulation_.nIn());
187187
}
188188

189-
void
190-
solve(const double t, const Eigen::VectorXd & q_meas, const Eigen::VectorXd & v_meas, Eigen::VectorXd & tau_res)
189+
void solve(
190+
const double t,
191+
const Eigen::Ref<const Eigen::VectorXd> & q_meas,
192+
const Eigen::Ref<const Eigen::VectorXd> & v_meas,
193+
Eigen::Ref<Eigen::VectorXd> tau_res)
191194
{
192195
// Update contact position based on the real robot foot placement
193196
data_handler_.updateInternalData(q_meas, v_meas, false);

0 commit comments

Comments
 (0)