Skip to content

Commit 2732cd9

Browse files
committed
Merge branch 'devel' into topic/gar-optimizations
2 parents e3a8b38 + 168d0bf commit 2732cd9

21 files changed

+672
-31
lines changed

CHANGELOG.md

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,9 +27,11 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
2727
- Add `LqrProblemTpl::isApprox()`
2828
- Only link against needed pinocchio libraries ([#260](https://github.com/Simple-Robotics/aligator/pull/260))
2929
- Use Pinocchio instantiated functions ([#261](https://github.com/Simple-Robotics/aligator/pull/261))
30+
- CMake: Link to pinocchio::pinocchio_collision target
3031

3132
### Fixed
3233

34+
- Fixed copy of TrajOptProblem ([#265](https://github.com/Simple-Robotics/aligator/pull/265))
3335
- `LinesearchVariant::init()` should not be called unless the step accpetance strategy is a linesearch
3436
- Fixed compilation issues with C++20 (resolving [#246](https://github.com/Simple-Robotics/aligator/issues/246) and [#254](https://github.com/Simple-Robotics/aligator/discussions/254))
3537

@@ -39,6 +41,11 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
3941
- Remove subdirectory `aligator/helpers` from include dir
4042
- Remove function `allocate_shared_eigen_aligned()`
4143

44+
### Added
45+
46+
- Add a collision distance residual for collision pair
47+
- Add a relaxed log-barrier cost function
48+
4249
## [0.10.0] - 2024-12-09
4350

4451
### Added

CMakeLists.txt

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -61,10 +61,7 @@ else()
6161
endif()
6262
endif()
6363

64-
set(DOXYGEN_USE_MATHJAX NO)
65-
set(DOXYGEN_USE_TEMPLATE_CSS YES)
6664
set(DOXYGEN_HTML_HEADER "${PROJECT_SOURCE_DIR}/doc/header.html")
67-
set(DOXYGEN_HTML_STYLESHEET "")
6865

6966
# Use BoostConfig module distributed by boost library instead of using FindBoost module distributed
7067
# by CMake
@@ -394,7 +391,10 @@ function(create_library)
394391
)
395392

396393
if(BUILD_WITH_PINOCCHIO_SUPPORT)
397-
target_link_libraries(${PROJECT_NAME} PUBLIC pinocchio::pinocchio_default)
394+
target_link_libraries(
395+
${PROJECT_NAME}
396+
PUBLIC pinocchio::pinocchio_default pinocchio::pinocchio_collision
397+
)
398398
target_compile_definitions(${PROJECT_NAME} PUBLIC ALIGATOR_WITH_PINOCCHIO)
399399
if(PINOCCHIO_V3)
400400
target_compile_definitions(${PROJECT_NAME} PUBLIC ALIGATOR_PINOCCHIO_V3)
@@ -446,20 +446,20 @@ ADD_SOURCE_GROUP(LIB_SOURCES)
446446
install(
447447
TARGETS ${PROJECT_NAME}
448448
EXPORT ${TARGETS_EXPORT_NAME}
449-
INCLUDES DESTINATION ${CMAKE_INSTALL_FULL_INCLUDEDIR}
450-
LIBRARY DESTINATION ${CMAKE_INSTALL_FULL_LIBDIR}
449+
INCLUDES DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}
450+
LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR}
451451
)
452452

453453
if(DOWNLOAD_TRACY)
454454
install(
455455
TARGETS TracyClient
456456
EXPORT ${TARGETS_EXPORT_NAME}
457-
LIBRARY DESTINATION ${CMAKE_INSTALL_FULL_LIBDIR}/aligator
458-
ARCHIVE DESTINATION ${CMAKE_INSTALL_FULL_LIBDIR}/aligator
457+
LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR}/aligator
458+
ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR}/aligator
459459
)
460460
message(
461461
STATUS
462-
"Installing TracyClient target to ${CMAKE_INSTALL_FULL_LIBDIR}/aligator"
462+
"Installing TracyClient target to ${CMAKE_INSTALL_LIBDIR}/aligator"
463463
)
464464
endif()
465465

README.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -133,6 +133,7 @@ Please also consider citing the reference paper for the ProxDDP algorithm:
133133
* [Fabian Schramm](https://github.com/fabinsch) (Inria): core developer
134134
* [Ludovic De Matteïs](https://github.com/LudovicDeMatteis) (LAAS-CNRS/Inria): feature developer
135135
* [Ewen Dantec](https://edantec.github.io/) (Inria): feature developer
136+
* [Antoine Bussy](https://github.com/antoine-bussy) (Aldebaran)
136137

137138
## Acknowledgments
138139

bindings/python/src/modelling/expose-composite-costs.cpp

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33

44
#include "aligator/modelling/costs/quad-state-cost.hpp"
55
#include "aligator/modelling/costs/log-residual-cost.hpp"
6+
#include "aligator/modelling/costs/relaxed-log-barrier.hpp"
67
#include "aligator/python/polymorphic-convertible.hpp"
78

89
namespace aligator {
@@ -25,6 +26,7 @@ void exposeComposites() {
2526
using QuadStateCost = QuadraticStateCostTpl<Scalar>;
2627
using QuadControlCost = QuadraticControlCostTpl<Scalar>;
2728
using LogResCost = LogResidualCostTpl<Scalar>;
29+
using RelaxedLogCost = RelaxedLogBarrierCostTpl<Scalar>;
2830

2931
PolymorphicMultiBaseVisitor<CostAbstract> visitor;
3032
bp::class_<QuadResCost, bp::bases<CostAbstract>>(
@@ -47,6 +49,18 @@ void exposeComposites() {
4749
.def(CopyableVisitor<LogResCost>())
4850
.def(visitor);
4951

52+
bp::class_<RelaxedLogCost, bp::bases<CostAbstract>>(
53+
"RelaxedLogBarrierCost", "Relaxed log-barrier composite cost.",
54+
bp::init<PolyManifold, PolyFunction, const ConstVectorRef &,
55+
const Scalar>(
56+
bp::args("self", "space", "function", "weights", "threshold")))
57+
.def(bp::init<PolyManifold, PolyFunction, const Scalar, const Scalar>(
58+
bp::args("self", "space", "function", "weights", "threshold")))
59+
.def_readwrite("residual", &RelaxedLogCost::residual_)
60+
.def_readwrite("weights", &RelaxedLogCost::barrier_weights_)
61+
.def(CopyableVisitor<RelaxedLogCost>())
62+
.def(visitor);
63+
5064
bp::class_<CompositeData, bp::bases<CostData>>(
5165
"CompositeCostData",
5266
bp::init<int, int, shared_ptr<context::StageFunctionData>>(

bindings/python/src/modelling/expose-pinocchio-functions.cpp

Lines changed: 24 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77
#include "aligator/modelling/multibody/frame-placement.hpp"
88
#include "aligator/modelling/multibody/frame-velocity.hpp"
99
#include "aligator/modelling/multibody/frame-translation.hpp"
10+
#include "aligator/modelling/multibody/frame-collision.hpp"
1011
#include "aligator/python/polymorphic-convertible.hpp"
1112
#ifdef ALIGATOR_PINOCCHIO_V3
1213
#include "aligator/modelling/multibody/constrained-rnea.hpp"
@@ -52,6 +53,11 @@ void exposeFrameFunctions() {
5253
using FrameTranslation = FrameTranslationResidualTpl<Scalar>;
5354
using FrameTranslationData = FrameTranslationDataTpl<Scalar>;
5455

56+
using FrameCollision = FrameCollisionResidualTpl<Scalar>;
57+
using FrameCollisionData = FrameCollisionDataTpl<Scalar>;
58+
59+
using pinocchio::GeometryModel;
60+
5561
bp::register_ptr_to_python<shared_ptr<PinData>>();
5662

5763
PolymorphicMultiBaseVisitor<UnaryFunction, StageFunction> unary_visitor;
@@ -119,6 +125,24 @@ void exposeFrameFunctions() {
119125
.def_readonly("fJf", &FrameTranslationData::fJf_)
120126
.def_readonly("pin_data", &FrameTranslationData::pin_data_,
121127
"Pinocchio data struct.");
128+
129+
bp::class_<FrameCollision, bp::bases<UnaryFunction>>(
130+
"FrameCollisionResidual", "Frame collision residual function.",
131+
bp::init<int, int, const PinModel &, const GeometryModel &,
132+
pinocchio::PairIndex>(bp::args("self", "ndx", "nu", "model",
133+
"geom_model", "frame_pair_id")))
134+
.def(FrameAPIVisitor<FrameCollision>())
135+
.def(unary_visitor);
136+
137+
bp::register_ptr_to_python<shared_ptr<FrameCollisionData>>();
138+
139+
bp::class_<FrameCollisionData, bp::bases<context::StageFunctionData>>(
140+
"FrameCollisionData", "Data struct for FrameCollisionResidual.",
141+
bp::no_init)
142+
.def_readonly("pin_data", &FrameCollisionData::pin_data_,
143+
"Pinocchio data struct.")
144+
.def_readonly("geom_data", &FrameCollisionData::geometry_,
145+
"Geometry data struct.");
122146
}
123147

124148
#ifdef ALIGATOR_PINOCCHIO_V3

doc/Doxyfile.extra.in

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,8 @@ SHOW_FILES = YES
5454
SHOW_NAMESPACES = YES
5555

5656
USE_MATHJAX = YES
57-
MATHJAX_FORMAT = SVG
57+
MATHJAX_VERSION = MathJax_3
58+
MATHJAX_EXTENSIONS = ams,boldsymbol
5859

5960
SOURCE_BROWSER = YES
6061

examples/ur5_reach.py

Lines changed: 47 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88

99
from aligator import constraints, manifolds, dynamics # noqa
1010
from pinocchio.visualize import MeshcatVisualizer
11+
import hppfcl
1112

1213
from utils import ArgsBase, get_endpoint_traj
1314

@@ -16,6 +17,7 @@ class Args(ArgsBase):
1617
plot: bool = True
1718
fddp: bool = False
1819
bounds: bool = False
20+
collisions: bool = False
1921

2022

2123
args = Args().parse_args()
@@ -32,6 +34,30 @@ class Args(ArgsBase):
3234
vizer.initViewer(open=args.display, loadModel=True)
3335
vizer.setBackgroundColor()
3436

37+
fr_name = "universe"
38+
fr_id = rmodel.getFrameId(fr_name)
39+
joint_id = rmodel.frames[fr_id].parentJoint
40+
if args.collisions:
41+
obstacle_loc = pin.SE3.Identity()
42+
obstacle_loc.translation[0] = 0.3
43+
obstacle_loc.translation[1] = 0.5
44+
obstacle_loc.translation[2] = 0.3
45+
geom_object = pin.GeometryObject(
46+
"capsule", fr_id, joint_id, hppfcl.Capsule(0.05, 0.4), obstacle_loc
47+
)
48+
49+
fr_id2 = rmodel.getFrameId("wrist_3_joint")
50+
joint_id2 = rmodel.frames[fr_id2].parentJoint
51+
geom_object2 = pin.GeometryObject(
52+
"endeffector", fr_id2, joint_id2, hppfcl.Sphere(0.1), pin.SE3.Identity()
53+
)
54+
55+
geometry = pin.GeometryModel()
56+
ig_frame = geometry.addGeometryObject(geom_object)
57+
ig_frame2 = geometry.addGeometryObject(geom_object2)
58+
geometry.addCollisionPair(pin.CollisionPair(ig_frame, ig_frame2))
59+
60+
vizer.addGeometryObject(geom_object, [1.0, 1.0, 0.5, 1.0])
3561

3662
x0 = space.neutral()
3763

@@ -61,6 +87,12 @@ class Args(ArgsBase):
6187
tool_name = "tool0"
6288
tool_id = rmodel.getFrameId(tool_name)
6389
target_pos = np.array([0.15, 0.65, 0.5])
90+
target_place = pin.SE3.Identity()
91+
target_place.translation = target_pos
92+
target_object = pin.GeometryObject(
93+
"target", fr_id, joint_id, hppfcl.Sphere(0.05), target_place
94+
)
95+
vizer.addGeometryObject(target_object, [0.5, 0.5, 1.0, 1.0])
6496
print(target_pos)
6597

6698
frame_fn = aligator.FrameTranslationResidual(ndx, nu, rmodel, target_pos, tool_id)
@@ -71,14 +103,18 @@ class Args(ArgsBase):
71103
)
72104
wt_x_term = wt_x.copy()
73105
wt_x_term[:] = 1e-4
74-
wt_frame_pos = 10.0 * np.eye(frame_fn.nr)
106+
wt_frame_pos = 100.0 * np.eye(frame_fn.nr)
75107
wt_frame_vel = 100.0 * np.ones(frame_vel_fn.nr)
76108
wt_frame_vel = np.diag(wt_frame_vel)
77109

78110
term_cost = aligator.CostStack(space, nu)
79-
term_cost.addCost(aligator.QuadraticCost(wt_x_term, wt_u * 0))
80-
term_cost.addCost(aligator.QuadraticResidualCost(space, frame_fn, wt_frame_pos))
81-
term_cost.addCost(aligator.QuadraticResidualCost(space, frame_vel_fn, wt_frame_vel))
111+
term_cost.addCost("reg", aligator.QuadraticCost(wt_x_term, wt_u * 0))
112+
term_cost.addCost(
113+
"frame", aligator.QuadraticResidualCost(space, frame_fn, wt_frame_pos)
114+
)
115+
term_cost.addCost(
116+
"vel", aligator.QuadraticResidualCost(space, frame_vel_fn, wt_frame_vel)
117+
)
82118

83119
u_max = rmodel.effortLimit
84120
u_min = -u_max
@@ -103,12 +139,16 @@ def computeQuasistatic(model: pin.Model, x0, a):
103139

104140

105141
stages = []
106-
107142
for i in range(nsteps):
108143
rcost = aligator.CostStack(space, nu)
109-
rcost.addCost(aligator.QuadraticCost(wt_x * dt, wt_u * dt))
144+
rcost.addCost("reg", aligator.QuadraticCost(wt_x * dt, wt_u * dt))
110145

111146
stm = aligator.StageModel(rcost, discrete_dynamics)
147+
if args.collisions:
148+
# Distance to obstacle constrained between 0.1 and 100 m
149+
cstr_set = constraints.BoxConstraint(np.array([0.1]), np.array([100]))
150+
frame_col = aligator.FrameCollisionResidual(ndx, nu, rmodel, geometry, 0)
151+
stm.addConstraint(frame_col, cstr_set)
112152
if args.bounds:
113153
stm.addConstraint(*make_control_bounds())
114154
stages.append(stm)
@@ -119,7 +159,7 @@ def computeQuasistatic(model: pin.Model, x0, a):
119159

120160
mu_init = 1e-7
121161
verbose = aligator.VerboseLevel.VERBOSE
122-
max_iters = 40
162+
max_iters = 500
123163
solver = aligator.SolverProxDDP(tol, mu_init, max_iters=max_iters, verbose=verbose)
124164
solver.rollout_type = aligator.ROLLOUT_NONLINEAR
125165
solver.sa_strategy = aligator.SA_LINESEARCH_NONMONOTONE

include/aligator/core/traj-opt-problem.hpp

Lines changed: 11 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -129,7 +129,10 @@ template <typename _Scalar> struct TrajOptProblemTpl {
129129
xyz::polymorphic<CostAbstract> term_cost);
130130
/// @}
131131

132-
bool initCondIsStateError() const { return init_state_error_ != nullptr; }
132+
bool initCondIsStateError() const {
133+
assert(init_cond_is_state_error_ == checkInitCondIsStateError());
134+
return init_cond_is_state_error_;
135+
}
133136

134137
/// @brief Add a stage to the control problem.
135138
void addStage(const xyz::polymorphic<StageModel> &stage);
@@ -140,7 +143,7 @@ template <typename _Scalar> struct TrajOptProblemTpl {
140143
ALIGATOR_RUNTIME_ERROR(
141144
"Initial condition is not a StateErrorResidual.\n");
142145
}
143-
return init_state_error_->target_;
146+
return static_cast<StateErrorResidual const *>(&*init_constraint_)->target_;
144147
}
145148

146149
/// @brief Set initial state constraint.
@@ -149,7 +152,7 @@ template <typename _Scalar> struct TrajOptProblemTpl {
149152
ALIGATOR_RUNTIME_ERROR(
150153
"Initial condition is not a StateErrorResidual.\n");
151154
}
152-
init_state_error_->target_ = x0;
155+
static_cast<StateErrorResidual *>(&*init_constraint_)->target_ = x0;
153156
}
154157

155158
/// @brief Add a terminal constraint for the model.
@@ -189,9 +192,11 @@ template <typename _Scalar> struct TrajOptProblemTpl {
189192

190193
bool checkIntegrity() const;
191194

192-
private:
193-
/// Pointer to underlying state error residual
194-
StateErrorResidual *init_state_error_;
195+
protected:
196+
// Check if the initial state is a StateErrorResidual.
197+
// Since this is a costly operation (dynamic_cast), we cache the result.
198+
bool checkInitCondIsStateError() const;
199+
bool init_cond_is_state_error_ = false;
195200
};
196201

197202
namespace internal {

include/aligator/core/traj-opt-problem.hxx

Lines changed: 13 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -17,9 +17,9 @@ TrajOptProblemTpl<Scalar>::TrajOptProblemTpl(
1717
const std::vector<xyz::polymorphic<StageModel>> &stages,
1818
xyz::polymorphic<CostAbstract> term_cost)
1919
: init_constraint_(std::move(init_constraint)), stages_(stages),
20-
term_cost_(std::move(term_cost)), unone_(term_cost_->nu) {
20+
term_cost_(std::move(term_cost)), unone_(term_cost_->nu),
21+
init_cond_is_state_error_(checkInitCondIsStateError()) {
2122
unone_.setZero();
22-
init_state_error_ = dynamic_cast<StateErrorResidual *>(&*init_constraint_);
2323
}
2424

2525
template <typename Scalar>
@@ -29,9 +29,7 @@ TrajOptProblemTpl<Scalar>::TrajOptProblemTpl(
2929
xyz::polymorphic<CostAbstract> term_cost)
3030
: TrajOptProblemTpl(
3131
StateErrorResidual(stages[0]->xspace_, stages[0]->nu(), x0), stages,
32-
std::move(term_cost)) {
33-
init_state_error_ = static_cast<StateErrorResidual *>(&*init_constraint_);
34-
}
32+
std::move(term_cost)) {}
3533

3634
template <typename Scalar>
3735
TrajOptProblemTpl<Scalar>::TrajOptProblemTpl(
@@ -131,6 +129,9 @@ template <typename Scalar>
131129
bool TrajOptProblemTpl<Scalar>::checkIntegrity() const {
132130
bool ok = true;
133131

132+
if (init_cond_is_state_error_ != checkInitCondIsStateError())
133+
return false;
134+
134135
if (numSteps() == 0)
135136
return true;
136137

@@ -173,4 +174,11 @@ void TrajOptProblemTpl<Scalar>::replaceStageCircular(
173174
stages_.pop_back();
174175
}
175176

177+
template <typename Scalar>
178+
bool TrajOptProblemTpl<Scalar>::checkInitCondIsStateError() const {
179+
if (init_constraint_.valueless_after_move())
180+
return false;
181+
return dynamic_cast<StateErrorResidual const *>(&*init_constraint_);
182+
}
183+
176184
} // namespace aligator

0 commit comments

Comments
 (0)