Skip to content

Commit b7a1ab9

Browse files
committed
Change all instances of taking argument "const Eigen::VectorXd &" to "const ConstVectorRef&"
1 parent 8cddaa1 commit b7a1ab9

File tree

11 files changed

+40
-43
lines changed

11 files changed

+40
-43
lines changed

include/simple-mpc/centroidal-dynamics.hpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -87,14 +87,13 @@ namespace simple_mpc
8787

8888
// Getters and setters for contact forces
8989
void setReferenceForces(const std::size_t t, const std::map<std::string, Eigen::VectorXd> & force_refs) override;
90-
void
91-
setReferenceForce(const std::size_t t, const std::string & ee_name, const Eigen::VectorXd & force_ref) override;
90+
void setReferenceForce(const std::size_t t, const std::string & ee_name, const ConstVectorRef & force_ref) override;
9291
const Eigen::VectorXd getReferenceForce(const std::size_t t, const std::string & ee_name) override;
9392
void computeControlFromForces(const std::map<std::string, Eigen::VectorXd> & force_refs);
9493
const Eigen::VectorXd getVelocityBase(const std::size_t t) override;
95-
void setVelocityBase(const std::size_t t, const Eigen::VectorXd & velocity_base) override;
94+
void setVelocityBase(const std::size_t t, const ConstVectorRef & velocity_base) override;
9695
const Eigen::VectorXd getPoseBase(const std::size_t t) override;
97-
void setPoseBase(const std::size_t t, const Eigen::VectorXd & pose_base) override;
96+
void setPoseBase(const std::size_t t, const ConstVectorRef & pose_base) override;
9897
const Eigen::VectorXd getProblemState(const RobotDataHandler & data_handler) override;
9998
size_t getContactSupport(const std::size_t t) override;
10099

include/simple-mpc/fulldynamics.hpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -92,14 +92,13 @@ namespace simple_mpc
9292
void setReferencePoses(const std::size_t t, const std::map<std::string, pinocchio::SE3> & pose_refs) override;
9393
void setTerminalReferencePose(const std::string & ee_name, const pinocchio::SE3 & pose_ref) override;
9494
void setReferenceForces(const std::size_t t, const std::map<std::string, Eigen::VectorXd> & force_refs) override;
95-
void
96-
setReferenceForce(const std::size_t t, const std::string & ee_name, const Eigen::VectorXd & force_ref) override;
95+
void setReferenceForce(const std::size_t t, const std::string & ee_name, const ConstVectorRef & force_ref) override;
9796
const pinocchio::SE3 getReferencePose(const std::size_t t, const std::string & cost_name) override;
9897
const Eigen::VectorXd getReferenceForce(const std::size_t t, const std::string & cost_name) override;
9998
const Eigen::VectorXd getVelocityBase(const std::size_t t) override;
100-
void setVelocityBase(const std::size_t t, const Eigen::VectorXd & velocity_base) override;
99+
void setVelocityBase(const std::size_t t, const ConstVectorRef & velocity_base) override;
101100
const Eigen::VectorXd getPoseBase(const std::size_t t) override;
102-
void setPoseBase(const std::size_t t, const Eigen::VectorXd & pose_base) override;
101+
void setPoseBase(const std::size_t t, const ConstVectorRef & pose_base) override;
103102
const Eigen::VectorXd getProblemState(const RobotDataHandler & data_handler) override;
104103
size_t getContactSupport(const std::size_t t) override;
105104
FullDynamicsSettings getSettings()

include/simple-mpc/kinodynamics.hpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -80,14 +80,13 @@ namespace simple_mpc
8080
void setReferencePoses(const std::size_t i, const std::map<std::string, pinocchio::SE3> & pose_refs) override;
8181
void setTerminalReferencePose(const std::string & ee_name, const pinocchio::SE3 & pose_ref) override;
8282
void setReferenceForces(const std::size_t i, const std::map<std::string, Eigen::VectorXd> & force_refs) override;
83-
void
84-
setReferenceForce(const std::size_t i, const std::string & ee_name, const Eigen::VectorXd & force_ref) override;
83+
void setReferenceForce(const std::size_t i, const std::string & ee_name, const ConstVectorRef & force_ref) override;
8584
const Eigen::VectorXd getReferenceForce(const std::size_t i, const std::string & cost_name) override;
8685
const pinocchio::SE3 getReferencePose(const std::size_t i, const std::string & cost_name) override;
8786
const Eigen::VectorXd getVelocityBase(const std::size_t t) override;
8887
const Eigen::VectorXd getPoseBase(const std::size_t t) override;
89-
void setPoseBase(const std::size_t t, const Eigen::VectorXd & pose_base) override;
90-
void setVelocityBase(const std::size_t t, const Eigen::VectorXd & velocity_base) override;
88+
void setPoseBase(const std::size_t t, const ConstVectorRef & pose_base) override;
89+
void setVelocityBase(const std::size_t t, const ConstVectorRef & velocity_base) override;
9190
const Eigen::VectorXd getProblemState(const RobotDataHandler & data_handler) override;
9291
size_t getContactSupport(const std::size_t t) override;
9392

include/simple-mpc/ocp-handler.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -82,16 +82,16 @@ namespace simple_mpc
8282

8383
// Setter and getter for base velocity
8484
virtual const Eigen::VectorXd getVelocityBase(const std::size_t t) = 0;
85-
virtual void setVelocityBase(const std::size_t t, const Eigen::VectorXd & velocity_base) = 0;
85+
virtual void setVelocityBase(const std::size_t t, const ConstVectorRef & velocity_base) = 0;
8686

8787
// Setter and getter for base pose
8888
virtual const Eigen::VectorXd getPoseBase(const std::size_t t) = 0;
89-
virtual void setPoseBase(const std::size_t t, const Eigen::VectorXd & pose_base) = 0;
89+
virtual void setPoseBase(const std::size_t t, const ConstVectorRef & pose_base) = 0;
9090

9191
// Setter and getter for forces reference
9292
virtual void setReferenceForces(const std::size_t t, const std::map<std::string, Eigen::VectorXd> & force_refs) = 0;
9393
virtual void
94-
setReferenceForce(const std::size_t t, const std::string & ee_name, const Eigen::VectorXd & force_ref) = 0;
94+
setReferenceForce(const std::size_t t, const std::string & ee_name, const ConstVectorRef & force_ref) = 0;
9595
virtual const Eigen::VectorXd getReferenceForce(const std::size_t t, const std::string & ee_name) = 0;
9696
virtual const Eigen::VectorXd getProblemState(const RobotDataHandler & data_handler) = 0;
9797
virtual size_t getContactSupport(const std::size_t t) = 0;
@@ -100,14 +100,14 @@ namespace simple_mpc
100100

101101
// Create one TrajOptProblem from contact sequence
102102
void createProblem(
103-
const Eigen::VectorXd & x0,
103+
const ConstVectorRef & x0,
104104
const size_t horizon,
105105
const int force_size,
106106
const double gravity,
107107
const bool terminal_constraint);
108108

109109
// Setter and getter for control reference
110-
void setReferenceControl(const std::size_t t, const Eigen::VectorXd & u_ref);
110+
void setReferenceControl(const std::size_t t, const ConstVectorRef & u_ref);
111111
ConstVectorRef getReferenceControl(const std::size_t t);
112112

113113
// Getter for various objects and quantities

include/simple-mpc/python/py-ocp-handler.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -125,7 +125,7 @@ namespace simple_mpc
125125
}
126126

127127
void
128-
setReferenceForce(const std::size_t t, const std::string & ee_name, const Eigen::VectorXd & force_ref) override
128+
setReferenceForce(const std::size_t t, const std::string & ee_name, const ConstVectorRef & force_ref) override
129129
{
130130
SIMPLE_MPC_PYTHON_OVERRIDE_PURE(void, "setReferenceForce", t, ee_name, force_ref);
131131
}
@@ -135,7 +135,7 @@ namespace simple_mpc
135135
SIMPLE_MPC_PYTHON_OVERRIDE_PURE(Eigen::VectorXd, "getReferenceForce", t, ee_name);
136136
}
137137

138-
void setVelocityBase(const std::size_t t, const Eigen::VectorXd & velocity_base) override
138+
void setVelocityBase(const std::size_t t, const ConstVectorRef & velocity_base) override
139139
{
140140
SIMPLE_MPC_PYTHON_OVERRIDE_PURE(void, "setVelocityBase", t, velocity_base);
141141
}
@@ -145,7 +145,7 @@ namespace simple_mpc
145145
SIMPLE_MPC_PYTHON_OVERRIDE_PURE(Eigen::VectorXd, "getVelocityBase", t);
146146
}
147147

148-
void setPoseBase(const std::size_t t, const Eigen::VectorXd & pose_base) override
148+
void setPoseBase(const std::size_t t, const ConstVectorRef & pose_base) override
149149
{
150150
SIMPLE_MPC_PYTHON_OVERRIDE_PURE(void, "setPoseBase", t, pose_base);
151151
}
@@ -165,7 +165,7 @@ namespace simple_mpc
165165
SIMPLE_MPC_PYTHON_OVERRIDE_PURE(std::size_t, "getContactSupport", t);
166166
}
167167

168-
void setReferenceControl(const std::size_t t, const Eigen::VectorXd & u_ref)
168+
void setReferenceControl(const std::size_t t, const ConstVectorRef & u_ref)
169169
{
170170
SIMPLE_MPC_PYTHON_OVERRIDE(void, OCPHandler, setReferenceControl, t, u_ref);
171171
}

include/simple-mpc/robot-handler.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -111,7 +111,7 @@ namespace simple_mpc
111111
* @return Eigen::VectorXd The vector that must be integrated during a unit of
112112
* time to go from x1 to x2.
113113
*/
114-
Eigen::VectorXd difference(const Eigen::VectorXd & x1, const Eigen::VectorXd & x2) const;
114+
Eigen::VectorXd difference(const ConstVectorRef & x1, const ConstVectorRef & x2) const;
115115

116116
/**
117117
* @brief Compute reduced state from measures by concatenating q,v of the
@@ -121,10 +121,10 @@ namespace simple_mpc
121121
* @param v Velocity vector of the full model
122122
* @return const Eigen::VectorXd State vector of the reduced model.
123123
*/
124-
Eigen::VectorXd shapeState(const Eigen::VectorXd & q, const Eigen::VectorXd & v) const;
124+
Eigen::VectorXd shapeState(const ConstVectorRef & q, const ConstVectorRef & v) const;
125125

126126
// Const getters
127-
const Eigen::VectorXd & getReferenceState() const
127+
const ConstVectorRef & getReferenceState() const
128128
{
129129
return reference_state_;
130130
}
@@ -195,8 +195,8 @@ namespace simple_mpc
195195
RobotDataHandler(const RobotModelHandler & model_handler);
196196

197197
// Set new robot state
198-
void updateInternalData(const Eigen::VectorXd & x, const bool updateJacobians);
199-
void updateJacobiansMassMatrix(const Eigen::VectorXd & x);
198+
void updateInternalData(const ConstVectorRef & x, const bool updateJacobians);
199+
void updateJacobiansMassMatrix(const ConstVectorRef & x);
200200

201201
// Const getters
202202
const SE3 & getRefFootPose(const std::string & foot_name) const

src/centroidal-dynamics.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -189,7 +189,7 @@ namespace simple_mpc
189189
}
190190

191191
void
192-
CentroidalOCP::setReferenceForce(const std::size_t t, const std::string & ee_name, const Eigen::VectorXd & force_ref)
192+
CentroidalOCP::setReferenceForce(const std::size_t t, const std::string & ee_name, const ConstVectorRef & force_ref)
193193
{
194194
std::vector<std::string> hname = model_handler_.getFeetNames();
195195
std::vector<std::string>::iterator it = std::find(hname.begin(), hname.end(), ee_name);
@@ -223,7 +223,7 @@ namespace simple_mpc
223223
return v;
224224
}
225225

226-
void CentroidalOCP::setVelocityBase(const std::size_t t, const Eigen::VectorXd & velocity_base)
226+
void CentroidalOCP::setVelocityBase(const std::size_t t, const ConstVectorRef & velocity_base)
227227
{
228228
CostStack * cs = getCostStack(t);
229229
QuadraticResidualCost * qcm = cs->getComponent<QuadraticResidualCost>("linear_mom_cost");
@@ -244,7 +244,7 @@ namespace simple_mpc
244244
return cfr->getReference();
245245
}
246246

247-
void CentroidalOCP::setPoseBase(const std::size_t t, const Eigen::VectorXd & pose_base)
247+
void CentroidalOCP::setPoseBase(const std::size_t t, const ConstVectorRef & pose_base)
248248
{
249249
if (pose_base.size() != 7)
250250
{

src/fulldynamics.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -287,8 +287,8 @@ namespace simple_mpc
287287
}
288288
}
289289

290-
void FullDynamicsOCP::setReferenceForce(
291-
const std::size_t i, const std::string & ee_name, const Eigen::VectorXd & force_ref)
290+
void
291+
FullDynamicsOCP::setReferenceForce(const std::size_t i, const std::string & ee_name, const ConstVectorRef & force_ref)
292292
{
293293
CostStack * cs = getCostStack(i);
294294
QuadraticResidualCost * qrc = cs->getComponent<QuadraticResidualCost>(ee_name + "_force_cost");
@@ -329,7 +329,7 @@ namespace simple_mpc
329329
return qc->getTarget().segment(nq_, 6);
330330
}
331331

332-
void FullDynamicsOCP::setVelocityBase(const std::size_t t, const Eigen::VectorXd & velocity_base)
332+
void FullDynamicsOCP::setVelocityBase(const std::size_t t, const ConstVectorRef & velocity_base)
333333
{
334334
if (velocity_base.size() != 6)
335335
{
@@ -348,7 +348,7 @@ namespace simple_mpc
348348
return qc->getTarget().head(7);
349349
};
350350

351-
void FullDynamicsOCP::setPoseBase(const std::size_t t, const Eigen::VectorXd & pose_base)
351+
void FullDynamicsOCP::setPoseBase(const std::size_t t, const ConstVectorRef & pose_base)
352352
{
353353
if (pose_base.size() != 7)
354354
{

src/kinodynamics.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -244,8 +244,8 @@ namespace simple_mpc
244244
setReferenceControl(i, control_ref_);
245245
}
246246

247-
void KinodynamicsOCP::setReferenceForce(
248-
const std::size_t i, const std::string & ee_name, const Eigen::VectorXd & force_ref)
247+
void
248+
KinodynamicsOCP::setReferenceForce(const std::size_t i, const std::string & ee_name, const ConstVectorRef & force_ref)
249249
{
250250
std::vector<std::string> hname = model_handler_.getFeetNames();
251251
std::vector<std::string>::iterator it = std::find(hname.begin(), hname.end(), ee_name);
@@ -270,7 +270,7 @@ namespace simple_mpc
270270
return qc->getTarget().segment(nq_, 6);
271271
}
272272

273-
void KinodynamicsOCP::setVelocityBase(const std::size_t t, const Eigen::VectorXd & velocity_base)
273+
void KinodynamicsOCP::setVelocityBase(const std::size_t t, const ConstVectorRef & velocity_base)
274274
{
275275
if (velocity_base.size() != 6)
276276
{
@@ -289,7 +289,7 @@ namespace simple_mpc
289289
return qc->getTarget().head(7);
290290
};
291291

292-
void KinodynamicsOCP::setPoseBase(const std::size_t t, const Eigen::VectorXd & pose_base)
292+
void KinodynamicsOCP::setPoseBase(const std::size_t t, const ConstVectorRef & pose_base)
293293
{
294294
if (pose_base.size() != 7)
295295
{

src/ocp-handler.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ namespace simple_mpc
5555
return stage_models;
5656
}
5757

58-
void OCPHandler::setReferenceControl(const std::size_t t, const Eigen::VectorXd & u_ref)
58+
void OCPHandler::setReferenceControl(const std::size_t t, const ConstVectorRef & u_ref)
5959
{
6060
CostStack * cs = getCostStack(t);
6161
QuadraticControlCost * qc = cs->getComponent<QuadraticControlCost>("control_cost");
@@ -94,7 +94,7 @@ namespace simple_mpc
9494
}
9595

9696
void OCPHandler::createProblem(
97-
const Eigen::VectorXd & x0,
97+
const ConstVectorRef & x0,
9898
const size_t horizon,
9999
const int force_size,
100100
const double gravity,

0 commit comments

Comments
 (0)