We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent d336215 commit 3aaf197Copy full SHA for 3aaf197
cartesian_controller_base/src/ForwardDynamicsSolver.cpp
@@ -216,11 +216,11 @@ bool ForwardDynamicsSolver::buildGenericModel() {
216
217
// Only give the last segment a generic mass and inertia.
218
// See https://arxiv.org/pdf/1908.06252.pdf for a motivation for this setting.
219
- // double m = 1;
220
- // double ip = 1;
221
- // m_chain.segments[m_chain.segments.size() - 1].setInertia(
222
- // KDL::RigidBodyInertia(m, KDL::Vector::Zero(),
223
- // KDL::RotationalInertia(ip, ip, ip)));
+ double m = 1;
+ double ip = 1;
+ m_chain.segments[m_chain.segments.size() - 1].setInertia(
+ KDL::RigidBodyInertia(m, KDL::Vector::Zero(),
+ KDL::RotationalInertia(ip, ip, ip)));
224
225
return true;
226
}
0 commit comments