Line |
Branch |
Exec |
Source |
1 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
2 |
|
|
// BSD 3-Clause License |
3 |
|
|
// |
4 |
|
|
// Copyright (C) 2019-2023, University of Edinburgh, LAAS-CNRS, |
5 |
|
|
// Heriot-Watt University |
6 |
|
|
// Copyright note valid unless otherwise stated in individual files. |
7 |
|
|
// All rights reserved. |
8 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
9 |
|
|
|
10 |
|
|
#ifndef CROCODDYL_LEGGED_ROBOTS_FACTORY_HPP_ |
11 |
|
|
#define CROCODDYL_LEGGED_ROBOTS_FACTORY_HPP_ |
12 |
|
|
|
13 |
|
|
#include <example-robot-data/path.hpp> |
14 |
|
|
#include <pinocchio/algorithm/model.hpp> |
15 |
|
|
#include <pinocchio/parsers/srdf.hpp> |
16 |
|
|
#include <pinocchio/parsers/urdf.hpp> |
17 |
|
|
|
18 |
|
|
#include "crocoddyl/core/costs/cost-sum.hpp" |
19 |
|
|
#include "crocoddyl/core/costs/residual.hpp" |
20 |
|
|
#include "crocoddyl/core/integrator/euler.hpp" |
21 |
|
|
#include "crocoddyl/core/mathbase.hpp" |
22 |
|
|
#include "crocoddyl/core/residuals/control.hpp" |
23 |
|
|
#include "crocoddyl/multibody/actions/contact-fwddyn.hpp" |
24 |
|
|
#include "crocoddyl/multibody/actuations/floating-base.hpp" |
25 |
|
|
#include "crocoddyl/multibody/contacts/contact-3d.hpp" |
26 |
|
|
#include "crocoddyl/multibody/contacts/contact-6d.hpp" |
27 |
|
|
#include "crocoddyl/multibody/contacts/multiple-contacts.hpp" |
28 |
|
|
#include "crocoddyl/multibody/residuals/com-position.hpp" |
29 |
|
|
#include "crocoddyl/multibody/residuals/frame-placement.hpp" |
30 |
|
|
#include "crocoddyl/multibody/residuals/frame-translation.hpp" |
31 |
|
|
#include "crocoddyl/multibody/residuals/state.hpp" |
32 |
|
|
#include "crocoddyl/multibody/states/multibody.hpp" |
33 |
|
|
#include "robot-ee-names.hpp" |
34 |
|
|
|
35 |
|
|
namespace crocoddyl { |
36 |
|
|
namespace benchmark { |
37 |
|
|
|
38 |
|
|
template <typename Scalar> |
39 |
|
✗ |
void build_contact_action_models( |
40 |
|
|
RobotEENames robotNames, |
41 |
|
|
std::shared_ptr<crocoddyl::ActionModelAbstractTpl<Scalar> >& runningModel, |
42 |
|
|
std::shared_ptr<crocoddyl::ActionModelAbstractTpl<Scalar> >& |
43 |
|
|
terminalModel) { |
44 |
|
|
typedef |
45 |
|
|
typename crocoddyl::DifferentialActionModelContactFwdDynamicsTpl<Scalar> |
46 |
|
|
DifferentialActionModelContactFwdDynamics; |
47 |
|
|
typedef typename crocoddyl::IntegratedActionModelEulerTpl<Scalar> |
48 |
|
|
IntegratedActionModelEuler; |
49 |
|
|
typedef typename crocoddyl::ActuationModelFloatingBaseTpl<Scalar> |
50 |
|
|
ActuationModelFloatingBase; |
51 |
|
|
typedef typename crocoddyl::CostModelSumTpl<Scalar> CostModelSum; |
52 |
|
|
typedef typename crocoddyl::ContactModelMultipleTpl<Scalar> |
53 |
|
|
ContactModelMultiple; |
54 |
|
|
typedef typename crocoddyl::CostModelAbstractTpl<Scalar> CostModelAbstract; |
55 |
|
|
typedef typename crocoddyl::ContactModelAbstractTpl<Scalar> |
56 |
|
|
ContactModelAbstract; |
57 |
|
|
typedef typename crocoddyl::CostModelResidualTpl<Scalar> CostModelResidual; |
58 |
|
|
typedef typename crocoddyl::ResidualModelFramePlacementTpl<Scalar> |
59 |
|
|
ResidualModelFramePlacement; |
60 |
|
|
typedef typename crocoddyl::ResidualModelCoMPositionTpl<Scalar> |
61 |
|
|
ResidualModelCoMPosition; |
62 |
|
|
typedef typename crocoddyl::ResidualModelStateTpl<Scalar> ResidualModelState; |
63 |
|
|
typedef typename crocoddyl::ResidualModelControlTpl<Scalar> |
64 |
|
|
ResidualModelControl; |
65 |
|
|
typedef typename crocoddyl::ContactModel6DTpl<Scalar> ContactModel6D; |
66 |
|
|
typedef typename crocoddyl::ContactModel3DTpl<Scalar> ContactModel3D; |
67 |
|
|
typedef typename crocoddyl::MathBaseTpl<Scalar>::Vector2s Vector2s; |
68 |
|
|
typedef typename crocoddyl::MathBaseTpl<Scalar>::Vector3s Vector3s; |
69 |
|
|
typedef typename crocoddyl::MathBaseTpl<Scalar>::VectorXs VectorXs; |
70 |
|
|
typedef typename crocoddyl::MathBaseTpl<Scalar>::Matrix3s Matrix3s; |
71 |
|
|
|
72 |
|
✗ |
pinocchio::ModelTpl<double> modeld; |
73 |
|
✗ |
pinocchio::urdf::buildModel(robotNames.urdf_path, |
74 |
|
✗ |
pinocchio::JointModelFreeFlyer(), modeld); |
75 |
|
✗ |
modeld.lowerPositionLimit.head<7>().array() = -1; |
76 |
|
✗ |
modeld.upperPositionLimit.head<7>().array() = 1.; |
77 |
|
✗ |
pinocchio::srdf::loadReferenceConfigurations(modeld, robotNames.srdf_path, |
78 |
|
|
false); |
79 |
|
|
|
80 |
|
✗ |
pinocchio::ModelTpl<Scalar> model(modeld.cast<Scalar>()); |
81 |
|
✗ |
std::shared_ptr<crocoddyl::StateMultibodyTpl<Scalar> > state = |
82 |
|
|
std::make_shared<crocoddyl::StateMultibodyTpl<Scalar> >( |
83 |
|
|
std::make_shared<pinocchio::ModelTpl<Scalar> >(model)); |
84 |
|
|
|
85 |
|
✗ |
VectorXs default_state(model.nq + model.nv); |
86 |
|
✗ |
default_state << model.referenceConfigurations[robotNames.reference_conf], |
87 |
|
✗ |
VectorXs::Zero(model.nv); |
88 |
|
|
|
89 |
|
✗ |
std::shared_ptr<ActuationModelFloatingBase> actuation = |
90 |
|
|
std::make_shared<ActuationModelFloatingBase>(state); |
91 |
|
|
|
92 |
|
✗ |
std::shared_ptr<CostModelAbstract> comCost = |
93 |
|
|
std::make_shared<CostModelResidual>( |
94 |
|
|
state, std::make_shared<ResidualModelCoMPosition>( |
95 |
|
✗ |
state, Vector3s::Zero(), actuation->get_nu())); |
96 |
|
✗ |
std::shared_ptr<CostModelAbstract> goalTrackingCost = |
97 |
|
|
std::make_shared<CostModelResidual>( |
98 |
|
|
state, std::make_shared<ResidualModelFramePlacement>( |
99 |
|
✗ |
state, model.getFrameId(robotNames.ee_name), |
100 |
|
✗ |
pinocchio::SE3Tpl<Scalar>( |
101 |
|
|
Matrix3s::Identity(), |
102 |
|
✗ |
Vector3s(Scalar(.0), Scalar(.0), Scalar(.4))), |
103 |
|
✗ |
actuation->get_nu())); |
104 |
|
✗ |
std::shared_ptr<CostModelAbstract> xRegCost = |
105 |
|
|
std::make_shared<CostModelResidual>( |
106 |
|
|
state, std::make_shared<ResidualModelState>(state, default_state, |
107 |
|
✗ |
actuation->get_nu())); |
108 |
|
✗ |
std::shared_ptr<CostModelAbstract> uRegCost = |
109 |
|
|
std::make_shared<CostModelResidual>( |
110 |
|
|
state, |
111 |
|
✗ |
std::make_shared<ResidualModelControl>(state, actuation->get_nu())); |
112 |
|
|
|
113 |
|
|
// Create a cost model per the running and terminal action model. |
114 |
|
✗ |
std::shared_ptr<CostModelSum> runningCostModel = |
115 |
|
✗ |
std::make_shared<CostModelSum>(state, actuation->get_nu()); |
116 |
|
✗ |
std::shared_ptr<CostModelSum> terminalCostModel = |
117 |
|
✗ |
std::make_shared<CostModelSum>(state, actuation->get_nu()); |
118 |
|
|
|
119 |
|
|
// Then let's added the running and terminal cost functions |
120 |
|
✗ |
runningCostModel->addCost("gripperPose", goalTrackingCost, Scalar(1)); |
121 |
|
|
// runningCostModel->addCost("comPos", comCost, Scalar(1e-7)); |
122 |
|
✗ |
runningCostModel->addCost("xReg", xRegCost, Scalar(1e-4)); |
123 |
|
✗ |
runningCostModel->addCost("uReg", uRegCost, Scalar(1e-4)); |
124 |
|
✗ |
terminalCostModel->addCost("gripperPose", goalTrackingCost, Scalar(1)); |
125 |
|
|
|
126 |
|
✗ |
std::shared_ptr<ContactModelMultiple> contact_models = |
127 |
|
✗ |
std::make_shared<ContactModelMultiple>(state, actuation->get_nu()); |
128 |
|
|
|
129 |
|
✗ |
for (std::size_t i = 0; i < robotNames.contact_names.size(); ++i) { |
130 |
|
✗ |
switch (robotNames.contact_types[i]) { |
131 |
|
✗ |
case Contact3D: { |
132 |
|
✗ |
std::shared_ptr<ContactModelAbstract> support_contact = |
133 |
|
|
std::make_shared<ContactModel3D>( |
134 |
|
✗ |
state, model.getFrameId(robotNames.contact_names[i]), |
135 |
|
✗ |
Eigen::Vector3d::Zero(), pinocchio::LOCAL_WORLD_ALIGNED, |
136 |
|
✗ |
actuation->get_nu(), Vector2s(Scalar(0.), Scalar(50.))); |
137 |
|
✗ |
contact_models->addContact( |
138 |
|
✗ |
model.frames[model.getFrameId(robotNames.contact_names[i])].name, |
139 |
|
|
support_contact); |
140 |
|
✗ |
break; |
141 |
|
|
} |
142 |
|
✗ |
case Contact6D: { |
143 |
|
✗ |
std::shared_ptr<ContactModelAbstract> support_contact = |
144 |
|
|
std::make_shared<ContactModel6D>( |
145 |
|
✗ |
state, model.getFrameId(robotNames.contact_names[i]), |
146 |
|
|
pinocchio::SE3Tpl<Scalar>::Identity(), |
147 |
|
✗ |
pinocchio::LOCAL_WORLD_ALIGNED, actuation->get_nu(), |
148 |
|
✗ |
Vector2s(Scalar(0.), Scalar(50.))); |
149 |
|
✗ |
contact_models->addContact( |
150 |
|
✗ |
model.frames[model.getFrameId(robotNames.contact_names[i])].name, |
151 |
|
|
support_contact); |
152 |
|
✗ |
break; |
153 |
|
|
} |
154 |
|
✗ |
default: { |
155 |
|
✗ |
break; |
156 |
|
|
} |
157 |
|
|
} |
158 |
|
|
} |
159 |
|
|
|
160 |
|
|
// Next, we need to create an action model for running and terminal nodes |
161 |
|
✗ |
std::shared_ptr<DifferentialActionModelContactFwdDynamics> runningDAM = |
162 |
|
|
std::make_shared<DifferentialActionModelContactFwdDynamics>( |
163 |
|
|
state, actuation, contact_models, runningCostModel); |
164 |
|
✗ |
std::shared_ptr<DifferentialActionModelContactFwdDynamics> terminalDAM = |
165 |
|
|
std::make_shared<DifferentialActionModelContactFwdDynamics>( |
166 |
|
|
state, actuation, contact_models, terminalCostModel); |
167 |
|
|
|
168 |
|
✗ |
runningModel = |
169 |
|
✗ |
std::make_shared<IntegratedActionModelEuler>(runningDAM, Scalar(5e-3)); |
170 |
|
✗ |
terminalModel = |
171 |
|
✗ |
std::make_shared<IntegratedActionModelEuler>(terminalDAM, Scalar(5e-3)); |
172 |
|
|
} |
173 |
|
|
|
174 |
|
|
} // namespace benchmark |
175 |
|
|
} // namespace crocoddyl |
176 |
|
|
|
177 |
|
|
#endif // CROCODDYL_BIPED_FACTORY_HPP_ |
178 |
|
|
|