diff --git a/CHANGELOG.md b/CHANGELOG.md index 415553996..2df1ae195 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -12,11 +12,17 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0 - Add a multibody friction cone cost ([#234](https://github.com/Simple-Robotics/aligator/pull/234)) - Add a `GravityCompensationResidual`, modelling $r(x,u) = Bu - G(q)$ ([#235](https://github.com/Simple-Robotics/aligator/pull/235)) - Add Pixi support ([#240](https://github.com/Simple-Robotics/aligator/pull/240)) +- Added a nonmonotone linesearch procedure ([#244](https://github.com/Simple-Robotics/aligator/pull/244)) +- Add enum value `StepAcceptanceStrategy::LINESEARCH_NONMONOTONE` ([#244](https://github.com/Simple-Robotics/aligator/pull/244)) ### Changed +- **API BREAKING:** Change enum value `StepAcceptanceStrategy::LINESEARCH` to `LINESEARCH_NONMONOTONE` ([#244](https://github.com/Simple-Robotics/aligator/pull/244)) + - Add constructor argument `StepAcceptanceStrategy sa_strategy`, defaults to nonmonotone +- The minimum required version of proxsuite-nlp is now 0.10.0 ([#244](https://github.com/Simple-Robotics/aligator/pull/244)) - `SolverProxDDP`: add temporary vectors for linesearch - `SolverProxDDP`: remove exceptions from `computeMultipliers()`, return a bool flag +- HistoryCallback: take solver instance as argument - `gar`: rework and move sparse matrix utilities to `gar/utils.hpp` - `SolverProxDDP`: Rename `maxRefinementSteps_` and `refinementThreshold_` to snake-case - `SolverProxDDP`: make `linesearch_` public diff --git a/CMakeLists.txt b/CMakeLists.txt index dce8ac665..accbc6d39 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -216,7 +216,7 @@ set(BOOST_REQUIRED_COMPONENTS filesystem) set_boost_default_options() export_boost_default_options() add_project_dependency(Boost REQUIRED COMPONENTS ${BOOST_REQUIRED_COMPONENTS}) -add_project_dependency(proxsuite-nlp 0.8.0 REQUIRED PKG_CONFIG_REQUIRES "proxsuite-nlp >= 0.8.0") +add_project_dependency(proxsuite-nlp 0.10.0 REQUIRED PKG_CONFIG_REQUIRES "proxsuite-nlp >= 0.10.0") if(BUILD_WITH_PINOCCHIO_SUPPORT) message(STATUS "Building aligator with Pinocchio support.") diff --git a/bindings/python/aligator/utils/plotting.py b/bindings/python/aligator/utils/plotting.py index f29a02b76..4b2dc4891 100644 --- a/bindings/python/aligator/utils/plotting.py +++ b/bindings/python/aligator/utils/plotting.py @@ -4,7 +4,14 @@ from aligator import HistoryCallback, Results -def plot_convergence(cb: HistoryCallback, ax: plt.Axes, res: Results = None): +def plot_convergence( + cb: HistoryCallback, + ax: plt.Axes, + res: Results = None, + *, + show_al_iters=False, + legend_kwargs={}, +): from proxsuite_nlp.utils import plot_pd_errs prim_infeas = cb.prim_infeas.tolist() @@ -14,7 +21,28 @@ def plot_convergence(cb: HistoryCallback, ax: plt.Axes, res: Results = None): dual_infeas.append(res.dual_infeas) plot_pd_errs(ax, prim_infeas, dual_infeas) ax.grid(axis="y", which="major") - return + handles, labels = ax.get_legend_handles_labels() + labels += [ + "Prim. err $p$", + "Dual err $d$", + ] + if show_al_iters: + prim_tols = np.array(cb.prim_tols) + al_iters = np.array(cb.al_index) + labels.append("$\\eta_k$") + + itrange = np.arange(len(al_iters)) + if itrange.size > 0: + if al_iters.max() > 0: + labels.append("AL iters") + ax.step(itrange, prim_tols, c="green", alpha=0.9, lw=1.1) + al_change = al_iters[1:] - al_iters[:-1] + al_change_idx = itrange[:-1][al_change > 0] + + ax.vlines(al_change_idx, *ax.get_ylim(), colors="gray", lw=4.0, alpha=0.5) + + ax.legend(labels=labels, **legend_kwargs) + return labels def plot_se2_pose( @@ -50,6 +78,7 @@ def plot_controls_traj( joint_names=None, rmodel=None, figsize=(6.4, 6.4), + xlabel="Time (s)", ) -> tuple[plt.Figure, list[plt.Axes]]: t0 = times[0] tf = times[-1] @@ -57,7 +86,9 @@ def plot_controls_traj( nu = us.shape[1] nrows, r = divmod(nu, ncols) nrows += int(r > 0) - if axes is None: + + make_new_plot = axes is None + if make_new_plot: fig, axes = plt.subplots(nrows, ncols, sharex="col", figsize=figsize) else: fig = axes.flat[0].get_figure() @@ -77,9 +108,13 @@ def plot_controls_traj( ax.set_ylim(*ylim) if joint_names is not None: joint_name = joint_names[i].lower() - ax.set_ylabel(joint_name) - fig.supxlabel("Time $t$") - fig.suptitle("Control trajectories") + ax.set_title(joint_name, fontsize=8) + if nu > 1: + fig.supxlabel(xlabel) + fig.suptitle("Control trajectories") + else: + axes[0].set_xlabel(xlabel) + axes[0].set_title("Control trajectories") fig.tight_layout() return fig, axes @@ -92,6 +127,7 @@ def plot_velocity_traj( ncols=2, vel_limit=None, figsize=(6.4, 6.4), + xlabel="Time (s)", ) -> tuple[plt.Figure, list[plt.Axes]]: vs = np.asarray(vs) nv = rmodel.nv @@ -111,7 +147,7 @@ def plot_velocity_traj( tf = times[-1] if axes is None: - fig, axes = plt.subplots(nrows, ncols, figsize=figsize) + fig, axes = plt.subplots(nrows, ncols, sharex=True, figsize=figsize) fig: plt.Figure else: fig = axes.flat[0].get_figure() @@ -127,9 +163,9 @@ def plot_velocity_traj( ax.hlines(-vel_limit[i], t0, tf, colors="k", linestyles="--") ax.hlines(+vel_limit[i], t0, tf, colors="r", linestyles="dashdot") ax.set_ylim(*ylim) - ax.set_ylabel(joint_name) + ax.set_title(joint_name, fontsize=8) - fig.supxlabel("Time $t$") + fig.supxlabel(xlabel) fig.suptitle("Velocity trajectories") fig.tight_layout() return fig, axes diff --git a/bindings/python/src/expose-callbacks.cpp b/bindings/python/src/expose-callbacks.cpp index 49016bfbf..d65561b6e 100644 --- a/bindings/python/src/expose-callbacks.cpp +++ b/bindings/python/src/expose-callbacks.cpp @@ -2,21 +2,29 @@ #include "aligator/python/callbacks.hpp" #include "aligator/helpers/history-callback.hpp" +#include "aligator/solvers/proxddp/solver-proxddp.hpp" +#include "aligator/solvers/fddp/solver-fddp.hpp" + namespace aligator { namespace python { using context::Scalar; +using context::SolverFDDP; +using context::SolverProxDDP; +using HistoryCallback = HistoryCallbackTpl; + +#define ctor(Solver) \ + bp::init( \ + ("self"_a, "solver", "store_pd_vars"_a = true, "store_values"_a = true)) void exposeHistoryCallback() { - using HistoryCallback = HistoryCallbackTpl; bp::scope in_history = bp::class_>( "HistoryCallback", "Store the history of solver's variables.", - bp::init((bp::arg("self"), - bp::arg("store_pd_vars") = true, - bp::arg("store_values") = true, - bp::arg("store_residuals") = true))) + bp::no_init) + .def(ctor(SolverProxDDP)) + .def(ctor(SolverFDDP)) #define _c(name) def_readonly(#name, &HistoryCallback::name) ._c(xs) ._c(us) @@ -36,9 +44,8 @@ void exposeHistoryCallback() { void exposeCallbacks() { bp::register_ptr_to_python>(); - bp::class_("BaseCallback", - "Base callback for solvers.", - bp::init<>(bp::args("self"))) + bp::class_( + "BaseCallback", "Base callback for solvers.", bp::init<>(("self"_a))) .def("call", bp::pure_virtual(&CallbackWrapper::call), bp::args("self", "workspace", "results")); diff --git a/bindings/python/src/expose-solver-prox.cpp b/bindings/python/src/expose-solver-prox.cpp index 750892589..d05c9dfd4 100644 --- a/bindings/python/src/expose-solver-prox.cpp +++ b/bindings/python/src/expose-solver-prox.cpp @@ -7,6 +7,7 @@ #include "aligator/solvers/proxddp/solver-proxddp.hpp" #include +#include namespace aligator { namespace python { @@ -19,8 +20,8 @@ void exposeProxDDP() { using context::VectorRef; using context::Workspace; - eigenpy::register_symbolic_link_to_registered_type< - Linesearch::Options>(); + using LsOptions = Linesearch::Options; + eigenpy::register_symbolic_link_to_registered_type(); eigenpy::register_symbolic_link_to_registered_type(); eigenpy::register_symbolic_link_to_registered_type< proxsuite::nlp::LSInterpolation>(); @@ -74,6 +75,7 @@ void exposeProxDDP() { .def(PrintableVisitor()); using SolverType = SolverProxDDPTpl; + using ls_variant_t = SolverType::LinesearchVariant::variant_t; auto cls = bp::class_( @@ -84,9 +86,10 @@ void exposeProxDDP() { " The solver instance initializes both a Workspace and a Results " "struct.", bp::init( + StepAcceptanceStrategy, HessianApprox>( ("self"_a, "tol", "mu_init"_a = 1e-2, "max_iters"_a = 1000, "verbose"_a = VerboseLevel::QUIET, + "sa_strategy"_a = StepAcceptanceStrategy::LINESEARCH_NONMONOTONE, "hess_approx"_a = HessianApprox::GAUSS_NEWTON))) .def("cycleProblem", &SolverType::cycleProblem, ("self"_a, "problem", "data"), @@ -110,7 +113,7 @@ void exposeProxDDP() { .def_readwrite("max_al_iters", &SolverType::max_al_iters, "Maximum number of AL iterations.") .def_readwrite("ls_mode", &SolverType::ls_mode, "Linesearch mode.") - .def_readwrite("sa_strategy", &SolverType::sa_strategy, + .def_readwrite("sa_strategy", &SolverType::sa_strategy_, "StepAcceptance strategy.") .def_readwrite("rollout_type", &SolverType::rollout_type_, "Rollout type.") @@ -120,7 +123,6 @@ void exposeProxDDP() { "Minimum regularization value.") .def_readwrite("reg_max", &SolverType::reg_max, "Maximum regularization value.") - .def_readwrite("lq_print_detailed", &SolverType::lq_print_detailed) .def("updateLQSubproblem", &SolverType::updateLQSubproblem, "self"_a) .def("computeCriterion", &SolverType::computeCriterion, "self"_a, "Compute problem stationarity.") @@ -143,6 +145,12 @@ void exposeProxDDP() { "(target_tol) will not be synced when the latter changes and " "`solver.run()` is called.") .def(SolverVisitor()) + .add_property("linesearch", + bp::make_function( + +[](const SolverType &s) -> const ls_variant_t & { + return s.linesearch_; + }, + eigenpy::ReturnInternalVariant{})) .def("run", &SolverType::run, ("self"_a, "problem", "xs_init"_a = bp::list(), "us_init"_a = bp::list(), "vs_init"_a = bp::list(), @@ -150,6 +158,12 @@ void exposeProxDDP() { "Run the algorithm. Can receive initial guess for " "multiplier trajectory."); + bp::class_, bp::bases>>( + "NonmonotoneLinesearch", bp::no_init) + .def(bp::init(("self"_a, "options"))) + .def_readwrite("avg_eta", &NonmonotoneLinesearch::avg_eta) + .def_readwrite("beta_dec", &NonmonotoneLinesearch::beta_dec); + { using AlmParams = SolverType::AlmParams; bp::scope scope{cls}; diff --git a/bindings/python/src/module.cpp b/bindings/python/src/module.cpp index 113ee87e3..4800d09d1 100644 --- a/bindings/python/src/module.cpp +++ b/bindings/python/src/module.cpp @@ -42,7 +42,9 @@ static void exposeEnums() { bp::enum_("StepAcceptanceStrategy", "Step acceptance strategy.") - .value("SA_LINESEARCH", StepAcceptanceStrategy::LINESEARCH) + .value("SA_LINESEARCH_ARMIJO", StepAcceptanceStrategy::LINESEARCH_ARMIJO) + .value("SA_LINESEARCH_NONMONOTONE", + StepAcceptanceStrategy::LINESEARCH_NONMONOTONE) .value("SA_FILTER", StepAcceptanceStrategy::FILTER) .export_values(); } diff --git a/examples/acrobot.py b/examples/acrobot.py index fe8ce0aec..84e520700 100644 --- a/examples/acrobot.py +++ b/examples/acrobot.py @@ -70,10 +70,10 @@ class Args(ArgsBase): ) tol = 1e-3 -mu_init = 10.0 +mu_init = 1e-2 solver = aligator.SolverProxDDP(tol, mu_init=mu_init, verbose=aligator.VERBOSE) solver.max_iters = 200 -solver.rollout_type = aligator.ROLLOUT_LINEAR +solver.rollout_type = aligator.ROLLOUT_NONLINEAR solver.linear_solver_choice = aligator.LQ_SOLVER_STAGEDENSE solver.setup(problem) @@ -96,7 +96,10 @@ class Args(ArgsBase): from aligator.utils.plotting import plot_controls_traj times = np.linspace(0, Tf, nsteps + 1) - fig1 = plot_controls_traj(times, res.us, ncols=1, rmodel=rmodel, figsize=(6.4, 3.2)) + fig1, axes = plot_controls_traj( + times, res.us, ncols=1, rmodel=rmodel, figsize=(6.4, 3.2) + ) + plt.title("Controls (N/m)") fig1.tight_layout() xs = np.stack(res.xs) vs = xs[:, nq:] @@ -104,15 +107,17 @@ class Args(ArgsBase): theta_s = np.zeros((nsteps + 1, 2)) theta_s0 = space.difference(space.neutral(), x0)[:2] theta_s = theta_s0 + np.cumsum(vs * timestep, axis=0) - fig2 = plt.figure(figsize=(6.4, 6.4)) - plt.subplot(211) + fig2 = plt.figure(figsize=(6.4, 3.2)) + plt.subplot(1, 2, 1) plt.plot(times, theta_s, label=("$\\theta_0$", "$\\theta_1$")) - plt.title("Joint angles") + plt.title("Joint angles (rad)") + plt.xlabel("Time (s)") plt.legend() - plt.subplot(212) + plt.subplot(1, 2, 2) plt.plot(times, xs[:, nq:], label=("$\\dot\\theta_0$", "$\\dot\\theta_1$")) plt.legend() - plt.title("Joint velocities") + plt.title("Joint velocities (rad/s)") + plt.xlabel("Time (s)") fig2.tight_layout() _fig_dict = {"controls": fig1, "velocities": fig2} diff --git a/examples/cartpole.py b/examples/cartpole.py index 0dc18757e..9a9bf039e 100644 --- a/examples/cartpole.py +++ b/examples/cartpole.py @@ -45,28 +45,27 @@ class Args(ArgsBase): # running cost regularizes the control input rcost = aligator.CostStack(space, nu) -wu = np.ones(nu) * 1e-2 -rcost.addCost(aligator.QuadraticControlCost(space, np.zeros(nu), np.diag(wu) * dt)) -frame_place_target = pin.SE3.Identity() -frame_place_target.translation[:] = target_pos -frame_err = aligator.FramePlacementResidual( +wu = np.ones(nu) * 1e-3 +wx_reg = np.eye(ndx) * 1e-3 +rcost.addCost( + "ureg", aligator.QuadraticControlCost(space, np.zeros(nu), np.diag(wu) * dt) +) +rcost.addCost( + "xreg", aligator.QuadraticStateCost(space, nu, space.neutral(), wx_reg * dt) +) +frame_err = aligator.FrameTranslationResidual( ndx, nu, model, - frame_place_target, + target_pos, frame_id, ) -weights_frame_place = np.zeros(6) -weights_frame_place[:3] = 1.0 -weights_frame_place = np.diag(weights_frame_place) -rcost.addCost( - aligator.QuadraticResidualCost(space, frame_err, weights_frame_place * dt) -) term_cost = aligator.CostStack(space, nu) +term_cost.addCost("xreg", aligator.QuadraticStateCost(space, nu, x0, wx_reg)) # box constraint on control -u_min = -6.0 * np.ones(nu) -u_max = +6.0 * np.ones(nu) +u_min = -2.0 * np.ones(nu) +u_max = +2.0 * np.ones(nu) def get_box_cstr(): @@ -76,6 +75,7 @@ def get_box_cstr(): nsteps = 500 Tf = nsteps * dt +print(f"Tf = {Tf}") problem = aligator.TrajOptProblem(x0, nu, space, term_cost) for i in range(nsteps): @@ -84,23 +84,25 @@ def get_box_cstr(): stage.addConstraint(*get_box_cstr()) problem.addStage(stage) -term_fun = aligator.FrameTranslationResidual(ndx, nu, model, target_pos, frame_id) +term_fun = frame_err if args.term_cstr: problem.addTerminalConstraint(term_fun, constraints.EqualityConstraintSet()) else: + weights_frame_place = 5 * np.ones(3) + weights_frame_place = np.diag(weights_frame_place) term_cost.addCost( aligator.QuadraticResidualCost(space, frame_err, weights_frame_place) ) -mu_init = 1e-2 +mu_init = 1e-8 verbose = aligator.VerboseLevel.VERBOSE -TOL = 1e-4 +TOL = 1e-6 MAX_ITER = 300 solver = aligator.SolverProxDDP(TOL, mu_init, max_iters=MAX_ITER, verbose=verbose) -solver.rollout_type = aligator.ROLLOUT_LINEAR -callback = aligator.HistoryCallback() +solver.bcl_params.mu_lower_bound = 1e-11 +callback = aligator.HistoryCallback(solver) solver.registerCallback("his", callback) u0 = np.zeros(nu) @@ -126,23 +128,25 @@ def get_box_cstr(): ax1 = fig1.add_subplot(gs0[0]) ax2 = fig1.add_subplot(gs0[1]) lstyle = {"lw": 0.9} - ax1.plot(trange, xs_opt[:, 0], ls="-", **lstyle) - ax1.plot(trange, xs_opt[:, 2], ls="-", label="$\\dot{x}$", **lstyle) - ax1.set_ylabel("$q(t)$") + ax1.plot(trange, xs_opt[:, 0], ls="-", label="$x$ (m)", **lstyle) + ax1.plot(trange, xs_opt[:, 2], ls="-", label="$\\dot{x}$ (m/s)", **lstyle) + ax1.set_title("Cartpole position $x$") if args.term_cstr: pass ax1.legend() - ax2.plot(trange, xs_opt[:, 1], ls="-", **lstyle) - ax2.plot(trange, xs_opt[:, 3], ls="-", label="$\\dot{\\theta}$", **lstyle) - ax2.set_ylabel("Angle $\\theta(t)$") + ax2.plot(trange, xs_opt[:, 1], ls="-", label="$\\theta$ (rad)", **lstyle) + ax2.plot(trange, xs_opt[:, 3], ls="-", label="$\\dot{\\theta}$ (rad/s)", **lstyle) + ax2.set_title("Angle $\\theta(t)$") ax2.legend() - plt.xlabel("Time $t$") + plt.xlabel("Time (s)") gs1 = gs[1].subgridspec(1, 2, width_ratios=[1, 2]) ax3 = plt.subplot(gs1[0]) plt.plot(*_pts.T, ls=":") plt.scatter(*target_pos[1:], c="r", marker="^", zorder=2, label="EE target") + plt.xlabel("$x$ (m)") + plt.ylabel("$z$ (m)") plt.legend() ax3.set_aspect("equal") plt.title("Endpoint trajectory") @@ -157,46 +161,17 @@ def get_box_cstr(): colors="k", lw=2.5, alpha=0.4, - label=r"$\bar{u}$", + label=r"bound $\overline{u}$", ) - plt.title("Controls $u(t)$") + plt.title(r"Controls $u$ (N/m)") plt.legend() fig1.tight_layout() - fig2 = plt.figure(figsize=(6.4, 4.8)) + fig2 = plt.figure(figsize=(7.2, 4)) ax: plt.Axes = plt.subplot(111) ax.hlines(TOL, 0, res.num_iters, lw=2.2, alpha=0.8, colors="k") - plot_convergence(callback, ax, res) - prim_tols = np.array(callback.prim_tols) - al_iters = np.array(callback.al_index) - - itrange = np.arange(len(al_iters)) - legends_ = [ - "$\\epsilon_\\mathrm{tol}$", - "Prim. err $p$", - "Dual err $d$", - ] - if len(itrange) > 0: - ax.step(itrange, prim_tols, c="green", alpha=0.9, lw=1.1) - al_change = al_iters[1:] - al_iters[:-1] - al_change_idx = itrange[:-1][al_change > 0] - legends_.extend( - [ - "Prim tol $\\eta_k$", - "AL iters", - ] - ) + plot_convergence(callback, ax, res, show_al_iters=True) - ax.vlines(al_change_idx, *ax.get_ylim(), colors="gray", lw=4.0, alpha=0.5) - ax.legend( - [ - "$\\epsilon_\\mathrm{tol}$", - "Prim. err $p$", - "Dual err $d$", - "Prim tol $\\eta_k$", - "AL iters", - ] - ) fig2.tight_layout() fig_dict = {"traj": fig1, "conv": fig2} @@ -222,7 +197,9 @@ def get_box_cstr(): qs = [x[:nq] for x in res.xs.tolist()] vs = [x[nq:] for x in res.xs.tolist()] - obj = pin.GeometryObject("objective", 0, hppfcl.Sphere(0.05), frame_place_target) + obj = pin.GeometryObject( + "objective", 0, hppfcl.Sphere(0.05), pin.SE3(np.eye(3), target_pos) + ) color = [255, 20, 83, 255] obj.meshColor[:] = color obj.meshColor /= 255 diff --git a/examples/lqr.py b/examples/lqr.py index e17318fb5..5ad279acb 100644 --- a/examples/lqr.py +++ b/examples/lqr.py @@ -23,6 +23,12 @@ class Args(tap.Tap): args = Args().parse_args() np.random.seed(42) +TAG = "LQR" +if args.bounds: + TAG += "_bounded" +if args.term_cstr: + TAG += "_cstr" + nx = 3 # dimension of the state manifold nu = 3 # dimension of the input space = manifolds.VectorSpace(nx) @@ -78,7 +84,7 @@ class Args(tap.Tap): tol = 1e-8 solver = aligator.SolverProxDDP(tol, mu_init, verbose=verbose) -his_cb = aligator.HistoryCallback() +his_cb = aligator.HistoryCallback(solver) solver.registerCallback("his", his_cb) print("Registered callbacks:", solver.getCallbackNames().tolist()) solver.max_iters = 20 @@ -98,6 +104,8 @@ class Args(tap.Tap): plt.subplot(121) fig1: plt.Figure = plt.gcf() +fig1.set_figwidth(6.4) +fig1.set_figheight(3.6) lstyle = {"lw": 0.9, "marker": ".", "markersize": 5} trange = np.arange(nsteps + 1) @@ -144,7 +152,7 @@ class Args(tap.Tap): plt.tight_layout() -fig2: plt.Figure = plt.figure() +fig2: plt.Figure = plt.figure(figsize=(6.4, 3.6)) ax: plt.Axes = fig2.add_subplot() niter = res.num_iters ax.hlines( @@ -155,15 +163,13 @@ class Args(tap.Tap): linestyles="-", linewidth=2.0, ) -plot_convergence(his_cb, ax, res) +plot_convergence(his_cb, ax, res, show_al_iters=True) ax.set_title("Convergence (constrained LQR)") -ax.legend( - [ - "Tolerance $\\epsilon_\\mathrm{tol}$", - "Primal error $p$", - "Dual error $d$", - ] -) fig2.tight_layout() +fig_dicts = {"traj": fig1, "conv": fig2} + +for name, _fig in fig_dicts.items(): + _fig: plt.Figure + _fig.savefig(f"assets/{TAG}_{name}.pdf") plt.show() diff --git a/examples/quadrotor_obstacles.py b/examples/quadrotor_obstacles.py index 57a6082bd..e2a71e41c 100644 --- a/examples/quadrotor_obstacles.py +++ b/examples/quadrotor_obstacles.py @@ -322,15 +322,22 @@ def setup() -> aligator.TrajOptProblem: vizer = None tol = 1e-4 - mu_init = 1.0 + if args.bounds: + mu_init = 1e1 + if args.obstacles: + mu_init = 1.0 + # elif args.obstacles: + # mu_init = 1e-2 + else: + mu_init = 1e-6 verbose = aligator.VerboseLevel.VERBOSE - history_cb = aligator.HistoryCallback() solver = aligator.SolverProxDDP(tol, mu_init, verbose=verbose) + history_cb = aligator.HistoryCallback(solver) if args.fddp: solver = aligator.SolverFDDP(tol, verbose=verbose) solver.max_iters = 400 + solver.reg_min = 1e-5 solver.registerCallback("his", history_cb) - solver.bcl_params.dyn_al_scale = 1e-6 solver.setup(problem) solver.run(problem, xs_init, us_init) @@ -351,42 +358,49 @@ def plot_costate_value() -> plt.Figure: plt.vlines(idx_switch, *plt.ylim(), colors="r", label="switch") plt.legend() - plt.xlabel("Time $t$") + plt.xlabel("Time $t$ (s)") plt.ylabel("Dimension") plt.title("Multipliers") plt.colorbar() plt.tight_layout() return plt.gcf() + TAG = "quadrotor" if args.obstacles: - TAG = "quadrotor_obstacles" - else: - TAG = "quadrotor" + TAG += "_obstacles" + if args.bounds: + TAG += "_bounds" + if args.term_cstr: + TAG += "_termcstr" root_pt_opt = np.stack(xs_opt)[:, :3] if args.plot: + from aligator.utils import plotting + if len(results.lams) > 0: plot_costate_value() nplot = 3 - fig: plt.Figure = plt.figure(figsize=(9.6, 5.4)) + fig: plt.Figure = plt.figure(figsize=(7.2, 3.2)) ax0: plt.Axes = fig.add_subplot(1, nplot, 1) ax0.plot(times[:-1], us_opt) ax0.hlines((u_min[0], u_max[0]), *times[[0, -1]], colors="k", alpha=0.3, lw=1.4) - ax0.set_title("Controls") - ax0.set_xlabel("Time") + ax0.set_title("Controls (N/m)") + ax0.set_xlabel("Time (s)") ax1: plt.Axes = fig.add_subplot(1, nplot, 2) ax1.plot(times, root_pt_opt) + ax1.set_xlabel("Time (s)") + ax1.set_title("Quadrotor position (m)") plt.legend(["$x$", "$y$", "$z$"]) ax1.scatter([times_wp[-1]] * 3, x_term[:3], marker=".", c=["C0", "C1", "C2"]) ax2: plt.Axes = fig.add_subplot(1, nplot, 3) - n_iter = np.arange(len(history_cb.prim_infeas.tolist())) - ax2.semilogy( - n_iter[1:], history_cb.prim_infeas.tolist()[1:], label="Primal err." + plotting.plot_convergence( + history_cb, + ax2, + res=results, + show_al_iters=True, + legend_kwargs=dict(fontsize=8), ) - ax2.semilogy(n_iter, history_cb.dual_infeas.tolist(), label="Dual err.") - ax2.set_xlabel("Iterations") - ax2.legend() fig.tight_layout() for ext in ["png", "pdf"]: diff --git a/examples/se2-car.cpp b/examples/se2-car.cpp index 3e651874d..051e15321 100644 --- a/examples/se2-car.cpp +++ b/examples/se2-car.cpp @@ -9,7 +9,7 @@ int main() { const T mu_init = 1e-2; SolverProxDDPTpl solver(1e-4, mu_init); solver.verbose_ = VERBOSE; - solver.sa_strategy = StepAcceptanceStrategy::FILTER; + solver.sa_strategy_ = StepAcceptanceStrategy::FILTER; solver.linear_solver_choice = LQSolverChoice::PARALLEL; solver.setNumThreads(4); solver.rollout_type_ = RolloutType::LINEAR; diff --git a/examples/solo_jump.py b/examples/solo_jump.py index e2b441aae..4045db448 100644 --- a/examples/solo_jump.py +++ b/examples/solo_jump.py @@ -30,6 +30,7 @@ class Args(ArgsBase): args = Args().parse_args() +q0[2] += 0.02 pin.framesForwardKinematics(rmodel, rdata, q0) @@ -42,7 +43,7 @@ class Args(ArgsBase): effort_limit = rmodel.effortLimit[6:] print(f"Effort limit: {effort_limit}") -constraint_models = create_ground_contact_model(rmodel, (0, 0, 100), 50) +constraint_models = create_ground_contact_model(rmodel, (0, 0, 100), 60) prox_settings = pin.ProximalSettings(1e-9, 1e-10, 10) ode1 = dynamics.MultibodyConstraintFwdDynamics( space, act_matrix, constraint_models, prox_settings @@ -64,34 +65,29 @@ def test(): test() -dt = 20e-3 # 20 ms +dt = 5e-3 # 20 ms tf = 1.2 # in seconds nsteps = int(tf / dt) print("Num steps: {:d}".format(nsteps)) switch_t0 = 0.4 -switch_t1 = 0.9 # landing time +switch_t1 = 1.0 # landing time k0 = int(switch_t0 / dt) k1 = int(switch_t1 / dt) times = np.linspace(0, tf, nsteps + 1) mask = (switch_t0 <= times) & (times < switch_t1) -x0_ref = np.concatenate((q0, np.zeros(nv))) -x_ref_flight = x0_ref.copy() +q1 = q0.copy() +# q1[3:7] = pin.exp3_quat(np.array([0.0, 0.0, np.pi / 3])) +v0 = np.zeros(nv) +x0_ref = np.concatenate((q0, v0)) w_x = np.ones(space.ndx) * 1e-2 -w_x[:6] = 0.0 +w_x[:nv] = 1.0 +w_x[3:6] = 0.1 w_x[nv : nv + 6] = 0.0 w_x = np.diag(w_x) -w_u = np.eye(nu) * 1e-4 - - -def add_fly_high_cost(costs: aligator.CostStack, slope): - fly_high_w = 1.0 - for fname, fid in FOOT_FRAME_IDS.items(): - fn = aligator.FlyHighResidual(space.ndx, rmodel, fid, slope, nu) - fl_cost = aligator.QuadraticResidualCost(space, fn, np.eye(2) * dt) - costs.addCost(fl_cost, fly_high_w / len(FOOT_FRAME_IDS)) +w_u = np.eye(nu) * 1e-1 def create_land_fns(): @@ -99,7 +95,7 @@ def create_land_fns(): for fname, fid in FOOT_FRAME_IDS.items(): p_ref = rdata.oMf[fid].translation fn = aligator.FrameTranslationResidual(space.ndx, nu, rmodel, p_ref, fid) - out[fid] = fn[2] + out[fid] = fn[2] # [2] return out @@ -122,21 +118,18 @@ def create_land_cost(costs, w): costs.addCost(land_cost, w / len(FOOT_FRAME_IDS)) -x_ref_flight[2] = 1.2 stages = [] for k in range(nsteps): vf = ode1 - wxlocal_k = w_x * dt if mask[k]: vf = ode2 - xref = x0_ref + xref = x0_ref.copy() - xreg_cost = aligator.QuadraticStateCost(space, nu, xref, weights=wxlocal_k) + xreg_cost = aligator.QuadraticStateCost(space, nu, xref, weights=w_x * dt) ureg_cost = aligator.QuadraticControlCost(space, nu, weights=w_u * dt) cost = aligator.CostStack(space, nu) cost.addCost(xreg_cost) cost.addCost(ureg_cost) - add_fly_high_cost(cost, slope=50) dyn_model = dynamics.IntegratorSemiImplEuler(vf, dt) stm = aligator.StageModel(cost, dyn_model) @@ -147,8 +140,8 @@ def create_land_cost(costs, w): constraints.BoxConstraint(-effort_limit, effort_limit), ) if k == k1: - fns = create_land_fns() - for fid, fn in fns.items(): + pin.framesForwardKinematics(rmodel, rdata, q1) + for fid, fn in create_land_fns().items(): stm.addConstraint(fn, constraints.EqualityConstraintSet()) for fid, fn in create_land_vel_fns().items(): stm.addConstraint(fn, constraints.EqualityConstraintSet()) @@ -156,19 +149,20 @@ def create_land_cost(costs, w): stages.append(stm) -w_xterm = w_x.copy() -term_cost = aligator.QuadraticStateCost(space, nu, x0_ref, weights=w_x) +w_xterm = w_x * 1 +xterm = np.concatenate((q1, v0)) +print("x0 :", x0_ref) +print("xterm:", xterm) +term_cost = aligator.QuadraticStateCost(space, nu, xterm, weights=w_xterm) problem = aligator.TrajOptProblem(x0_ref, stages, term_cost) mu_init = 1e-5 -tol = 1e-4 -solver = aligator.SolverProxDDP(tol, mu_init, verbose=aligator.VERBOSE, max_iters=100) +tol = 1e-5 +solver = aligator.SolverProxDDP(tol, mu_init, verbose=aligator.VERBOSE, max_iters=300) solver.rollout_type = aligator.ROLLOUT_LINEAR -solver.linear_solver_choice = aligator.LQ_SOLVER_PARALLEL -# solver.sa_strategy = aligator.SA_FILTER solver.setNumThreads(args.num_threads) -cb_ = aligator.HistoryCallback() +cb_ = aligator.HistoryCallback(solver) solver.registerCallback("his", cb_) solver.setup(problem) @@ -207,7 +201,8 @@ def make_plots(res: aligator.Results): fig4 = plt.figure() ax = fig4.add_subplot(111) - plot_convergence(cb_, ax, res=res) + ax.hlines(tol, 0, res.num_iters, lw=2.2, alpha=0.8, colors="k") + plot_convergence(cb_, ax, res, show_al_iters=True) fig4.tight_layout() _fig_dict = {"controls": fig1, "velocities": fig2, "foot_traj": fig3, "conv": fig4} @@ -228,7 +223,9 @@ def make_plots(res: aligator.Results): visual_model=robot.visual_model, data=rdata, ) - vizer.initViewer(loadModel=True, zmq_url=args.zmq_url) + vizer.initViewer( + open=args.zmq_url is None, loadModel=True, zmq_url=args.zmq_url + ) # custom_color = np.asarray((53, 144, 243)) / 255.0 # vizer.setBackgroundColor(col_bot=list(custom_color), col_top=(1, 1, 1, 1)) manage_lights(vizer) @@ -249,7 +246,8 @@ def make_plots(res: aligator.Results): qs = xs[:, :nq] vs = xs[:, nq:] - FPS = min(30, 1.0 / dt) + # FPS = min(30, 1.0 / dt) + FPS = 1.0 / dt if args.display: import contextlib diff --git a/examples/talos-walk.cpp b/examples/talos-walk.cpp index 315395152..98c9143d4 100644 --- a/examples/talos-walk.cpp +++ b/examples/talos-walk.cpp @@ -29,7 +29,7 @@ int main(int, char **) { us_i.assign(nsteps, u0); solver.rollout_type_ = aligator::RolloutType::LINEAR; - solver.sa_strategy = aligator::StepAcceptanceStrategy::FILTER; + solver.sa_strategy_ = aligator::StepAcceptanceStrategy::FILTER; solver.filter_.beta_ = 1e-5; solver.force_initial_condition_ = true; solver.reg_min = 1e-6; diff --git a/examples/talos_arms.py b/examples/talos_arms.py index 54dd055c1..2a217c95e 100644 --- a/examples/talos_arms.py +++ b/examples/talos_arms.py @@ -90,7 +90,9 @@ class Args(ArgsBase): solver.rollout_type = aligator.ROLLOUT_NONLINEAR # solver = aligator.SolverFDDP(TOL, verbose=verbose) solver.max_iters = max_iters -solver.sa_strategy = aligator.SA_LINESEARCH # FILTER or LINESEARCH +solver.sa_strategy = ( + aligator.SA_LINESEARCH_NONMONOTONE +) # FILTER or LINESEARCH_ARMIJO or LINESEARCH_NONMONOTONE solver.setup(problem) u0 = compute_quasistatic(rmodel, rdata, x0, acc=np.zeros(nv)) diff --git a/examples/ur10_ballistic.py b/examples/ur10_ballistic.py index 2a4e4dea7..47f612c8d 100644 --- a/examples/ur10_ballistic.py +++ b/examples/ur10_ballistic.py @@ -9,7 +9,11 @@ from pathlib import Path from typing import Tuple from pinocchio.visualize import MeshcatVisualizer -from aligator.utils.plotting import plot_controls_traj, plot_velocity_traj +from aligator.utils.plotting import ( + plot_controls_traj, + plot_convergence, + plot_velocity_traj, +) from utils import ( add_namespace_prefix_to_models, ArgsBase, @@ -31,14 +35,16 @@ class Args(ArgsBase): print(f"Velocity limit (before): {robot.model.velocityLimit}") -def load_projectile_model(): +def load_projectile_model(free_flyer: bool = True): ball_urdf = Path(__file__).parent / "mug.urdf" packages_dirs = [str(Path(__file__).parent)] ball_scale = 1.0 model, cmodel, vmodel = pin.buildModelsFromUrdf( str(ball_urdf), package_dirs=packages_dirs, - root_joint=pin.JointModelFreeFlyer(), + root_joint=pin.JointModelFreeFlyer() + if free_flyer + else pin.JointModelTranslation(), ) print("Projectile model:\n", model) for geom in cmodel.geometryObjects: @@ -76,21 +82,23 @@ def append_ball_to_robot_model( return rmodel, cmodel, vmodel, ref_q0 +nq_o = robot.model.nq +nv_o = robot.model.nv rmodel, cmodel, vmodel, ref_q0 = append_ball_to_robot_model(robot) print(f"New model velocity lims: {rmodel.velocityLimit}") space = manifolds.MultibodyPhaseSpace(rmodel) rdata: pin.Data = rmodel.createData() -nq = rmodel.nq -nv = rmodel.nv -nu = nv - 6 +nq_b = rmodel.nq +nv_b = rmodel.nv +nu = nv_b - 6 ndx = space.ndx x0 = space.neutral() -x0[:nq] = ref_q0 +x0[:nq_b] = ref_q0 print("X0 = {}".format(x0)) -MUG_VEL_IDX = slice(robot.nv, nv) +MUG_VEL_IDX = slice(robot.nv, nv_b) -def create_rcm(): +def create_rcm(contact_type=pin.ContactType.CONTACT_6D): # create rigid constraint between ball & tool0 tool_fid = rmodel.getFrameId("tool0") frame: pin.Frame = rmodel.frames[tool_fid] @@ -100,7 +108,7 @@ def create_rcm(): pl1 = rmodel.frames[tool_fid].placement pl2 = rdata.oMf[tool_fid] rcm = pin.RigidConstraintModel( - pin.ContactType.CONTACT_6D, + contact_type, rmodel, joint1_id, pl1, @@ -133,16 +141,10 @@ def configure_viz(target_pos): target_pos = np.array([2.4, -0.2, 0.0]) -if args.display: - viz = configure_viz(target_pos=target_pos) - viz.display(ref_q0) -else: - viz = None - dt = 0.01 tf = 2.0 # seconds nsteps = int(tf / dt) -actuation_matrix = np.eye(nv, nu) +actuation_matrix = np.eye(nv_b, nu) prox_settings = pin.ProximalSettings(accuracy=1e-8, mu=1e-6, max_iter=20) rcm = create_rcm() @@ -153,8 +155,8 @@ def configure_viz(target_pos): dyn_model1 = dynamics.IntegratorSemiImplEuler(ode1, dt) dyn_model2 = dynamics.IntegratorSemiImplEuler(ode2, dt) -q0 = x0[:nq] -v0 = x0[nq:] +q0 = x0[:nq_b] +v0 = x0[nq_b:] u0_free = pin.rnea(robot.model, robot.data, robot.q0, robot.v0, robot.v0) u0, lam_c = aligator.underactuatedConstrainedInverseDynamics( rmodel, rdata, q0, v0, actuation_matrix, [rcm], [rcm.createData()] @@ -178,16 +180,19 @@ def testu0(u0): dms = [dyn_model1] * nsteps us_i = [u0] * len(dms) xs_i = aligator.rollout(dms, x0, us_i) -qs_i = [x[:nq] for x in xs_i] +qs_i = [x[:nq_b] for x in xs_i] if args.display: + viz = configure_viz(target_pos=target_pos) viz.play(qs_i, dt=dt) +else: + viz = None def create_running_cost(): costs = aligator.CostStack(space, nu) - w_x = np.array([1e-3] * nv + [0.1] * nv) - w_v = w_x[nv:] + w_x = np.array([1e-3] * nv_b + [0.1] * nv_b) + w_v = w_x[nv_b:] # no costs on mug w_x[MUG_VEL_IDX] = 0.0 w_v[MUG_VEL_IDX] = 0.0 @@ -203,7 +208,7 @@ def create_running_cost(): def create_term_cost(has_frame_cost=False, w_ball=1.0): w_xf = np.zeros(ndx) w_xf[: robot.nv] = 1e-4 - w_xf[nv + 6 :] = 1e-6 + w_xf[nv_b + 6 :] = 1e-6 costs = aligator.CostStack(space, nu) xreg = aligator.QuadraticStateCost(space, nu, x0, np.diag(w_xf)) costs.addCost(xreg) @@ -234,11 +239,16 @@ def get_position_limit_constraint(): return (pos_fn, box_cstr) +JOINT_VEL_LIM_IDX = [0, 1, 3, 4, 5, 6] +print("Joint vel. limits enforced for:") +for i in JOINT_VEL_LIM_IDX: + print(robot.model.names[i]) + + def get_velocity_limit_constraint(): state_fn = aligator.StateErrorResidual(space, nu, space.neutral()) - idx = [1, 3, 4, 5] - vel_fn = state_fn[[nv + i for i in idx]] - vlim = rmodel.velocityLimit[idx] + vel_fn = state_fn[[nv_b + i for i in JOINT_VEL_LIM_IDX]] + vlim = rmodel.velocityLimit[JOINT_VEL_LIM_IDX] assert vel_fn.nr == vlim.shape[0] box_cstr = constraints.BoxConstraint(-vlim, vlim) return (vel_fn, box_cstr) @@ -272,12 +282,11 @@ def create_stage(contact: bool): problem.addTerminalConstraint(*create_term_constraint(target_pos)) problem.addTerminalConstraint(*get_velocity_limit_constraint()) tol = 1e-4 -mu_init = 1e-1 +mu_init = 2e-1 solver = aligator.SolverProxDDP(tol, mu_init, max_iters=300, verbose=aligator.VERBOSE) # solver.linear_solver_choice = aligator.LQ_SOLVER_PARALLEL # solver.rollout_type = aligator.ROLLOUT_LINEAR -# solver.sa_strategy = aligator.SA_FILTER -his_cb = aligator.HistoryCallback() +his_cb = aligator.HistoryCallback(solver) solver.setNumThreads(4) solver.registerCallback("his", his_cb) solver.setup(problem) @@ -290,8 +299,8 @@ def create_stage(contact: bool): xs = solver.results.xs us = solver.results.us -qs = [x[:nq] for x in xs] -vs = [x[nq:] for x in xs] +qs = [x[:nq_b] for x in xs] +vs = [x[nq_b:] for x in xs] vs = np.asarray(vs) proj_frame_id = rmodel.getFrameId("ball/root_joint") @@ -311,7 +320,7 @@ def get_frame_vel(k: int): if args.display: def viz_callback(i: int): - pin.forwardKinematics(rmodel, rdata, qs[i], xs[i][nq:]) + pin.forwardKinematics(rmodel, rdata, qs[i], xs[i][nq_b:]) viz.drawFrameVelocities(proj_frame_id, v_scale=0.06) fid = rmodel.getFrameId("ball/root_joint") ctar: pin.SE3 = rdata.oMf[fid] @@ -336,18 +345,19 @@ def viz_callback(i: int): _joint_names = robot.model.names _efflims = robot.model.effortLimit _vlims = robot.model.velocityLimit + for i in range(nv_o): + if i not in JOINT_VEL_LIM_IDX: + _vlims[i] = np.inf + figsize = (6.4, 4.0) fig1, _ = plot_controls_traj( - times, us, joint_names=_joint_names, effort_limit=_efflims + times, us, rmodel=rmodel, effort_limit=_efflims, figsize=figsize ) + fig1.suptitle("Controls (N/m)") fig2, _ = plot_velocity_traj( - times, vs[:, :-6], rmodel=robot.model, vel_limit=_vlims + times, vs[:, :-6], rmodel=robot.model, vel_limit=_vlims, figsize=figsize ) - for fig, name in [(fig1, "controls"), (fig2, "velocity")]: - PLOTDIR = Path("assets") - for ext in [".png", ".pdf"]: - figpath: Path = PLOTDIR / f"{EXPERIMENT_NAME}_{name}" - fig.savefig(figpath.with_suffix(ext)) + PLOTDIR = Path("assets") fig3 = plt.figure() ax: plt.Axes = fig3.add_subplot(111) @@ -355,4 +365,22 @@ def viz_callback(i: int): ax.set_yscale("log") ax.set_title("Dynamic slack errors $\\|s\\|_\\infty$") + fig4 = plt.figure(figsize=(6.4, 3.6)) + ax = fig4.add_subplot(111) + plot_convergence( + his_cb, + ax, + res=solver.results, + show_al_iters=True, + legend_kwargs=dict(fontsize=8), + ) + ax.set_title("Convergence") + fig4.tight_layout() + + _fig_dict = {"controls": fig1, "velocity": fig2, "conv": fig4} + for name, fig in _fig_dict.items(): + for ext in [".png", ".pdf"]: + figpath: Path = PLOTDIR / f"{EXPERIMENT_NAME}_{name}" + fig.savefig(figpath.with_suffix(ext)) + plt.show() diff --git a/examples/ur5_reach.py b/examples/ur5_reach.py index 4272c2442..a0ae7620a 100644 --- a/examples/ur5_reach.py +++ b/examples/ur5_reach.py @@ -122,10 +122,10 @@ def computeQuasistatic(model: pin.Model, x0, a): max_iters = 40 solver = aligator.SolverProxDDP(tol, mu_init, max_iters=max_iters, verbose=verbose) solver.rollout_type = aligator.ROLLOUT_NONLINEAR -solver.sa_strategy = aligator.SA_LINESEARCH +solver.sa_strategy = aligator.SA_LINESEARCH_NONMONOTONE if args.fddp: solver = aligator.SolverFDDP(tol, verbose, max_iters=max_iters) -cb = aligator.HistoryCallback() +cb = aligator.HistoryCallback(solver) solver.registerCallback("his", cb) solver.setup(problem) solver.run(problem, init_xs, init_us) diff --git a/examples/utils/solo.py b/examples/utils/solo.py index 55de49ed7..30cd1bead 100644 --- a/examples/utils/solo.py +++ b/examples/utils/solo.py @@ -7,7 +7,7 @@ rmodel: pin.Model = robot.model rdata: pin.Data = robot.data stance_name = "straight_standing" -q0 = rmodel.referenceConfigurations[stance_name] +q0 = rmodel.referenceConfigurations[stance_name].copy() FOOT_FRAME_IDS = { fname: rmodel.getFrameId(fname) diff --git a/include/aligator/core/enums.hpp b/include/aligator/core/enums.hpp index 3fc9afe02..5d7c783d7 100644 --- a/include/aligator/core/enums.hpp +++ b/include/aligator/core/enums.hpp @@ -26,6 +26,10 @@ enum struct MultiplierUpdateMode { NEWTON, PRIMAL, PRIMAL_DUAL }; enum struct LinesearchMode { PRIMAL = 0, PRIMAL_DUAL = 1 }; /// Whether to use linesearch or filter during step acceptance phase -enum struct StepAcceptanceStrategy { LINESEARCH = 0, FILTER = 1 }; +enum struct StepAcceptanceStrategy { + LINESEARCH_ARMIJO, + LINESEARCH_NONMONOTONE, + FILTER, +}; } // namespace aligator diff --git a/include/aligator/core/linesearch-nonmonotone.hpp b/include/aligator/core/linesearch-nonmonotone.hpp new file mode 100644 index 000000000..57b9224b4 --- /dev/null +++ b/include/aligator/core/linesearch-nonmonotone.hpp @@ -0,0 +1,63 @@ +#pragma once + +#include +#include + +namespace aligator { +using proxsuite::nlp::Linesearch; +using proxsuite::nlp::LinesearchStrategy; + +/// @brief Nonmonotone Linesearch algorithm. Modifies the Armijo condition with +/// a moving average of function values. +/// @details This is the algorithm from Zhang and Hager, SiOpt 2004. +template struct NonmonotoneLinesearch : Linesearch { + using typename Linesearch::FunctionSample; + using typename Linesearch::Options; + using fun_t = std::function; + + Scalar run(fun_t f, Scalar phi0, Scalar dphi0, Scalar &a_opt); + NonmonotoneLinesearch(const Options &options); + + void reset() { + mov_avg = Scalar(0.); + avg_weight = Scalar(0.); + } + + /// Weight for moving average + Scalar avg_eta = 0.85; + Scalar beta_dec = 0.5; + +private: + Scalar mov_avg; + Scalar avg_weight; +}; + +template +NonmonotoneLinesearch::NonmonotoneLinesearch(const Options &options) + : Linesearch(options), mov_avg(0.), avg_weight(0.) {} + +template +Scalar NonmonotoneLinesearch::run(fun_t f, Scalar phi0, Scalar dphi0, + Scalar &a_opt) { + const Options &opts = this->options_; + mov_avg = avg_eta * avg_weight * mov_avg + phi0; + avg_weight = avg_eta * avg_weight + 1; + mov_avg /= avg_weight; + + while (a_opt > opts.alpha_min) { + try { + const Scalar phia = f(a_opt); + bool suff_decrease = phia <= mov_avg + opts.armijo_c1 * a_opt * dphi0; + if (suff_decrease) + return phia; + } catch (const std::runtime_error &) { + } + a_opt *= beta_dec; + } + + // then, a_opt <= opts.alpha_min + a_opt = std::max(a_opt, opts.alpha_min); + return f(a_opt); +} + +} // namespace aligator diff --git a/include/aligator/helpers/history-callback.hpp b/include/aligator/helpers/history-callback.hpp index 87e20e04e..135060bc8 100644 --- a/include/aligator/helpers/history-callback.hpp +++ b/include/aligator/helpers/history-callback.hpp @@ -5,7 +5,8 @@ #include "aligator/core/workspace-base.hpp" #include "aligator/core/results-base.hpp" -#include "aligator/solvers/proxddp/results.hpp" +#include +#include namespace aligator { @@ -13,10 +14,11 @@ namespace aligator { template struct HistoryCallbackTpl : CallbackBaseTpl { using Workspace = WorkspaceBaseTpl; using Results = ResultsBaseTpl; - HistoryCallbackTpl(bool store_pd_vars = false, bool store_values = true, - bool store_residuals = true) + template + HistoryCallbackTpl(Solver *solver, bool store_pd_vars = false, + bool store_values = true) : store_primal_dual_vars_(store_pd_vars), store_values_(store_values), - store_residuals_(store_residuals) {} + rtti_(typeid(*solver)), solver_(solver) {} ALIGATOR_DYNAMIC_TYPEDEFS(Scalar); @@ -32,31 +34,14 @@ template struct HistoryCallbackTpl : CallbackBaseTpl { std::vector prim_tols; std::vector dual_tols; - void call(const Workspace & /*workspace*/, const Results &results) { - if (store_primal_dual_vars_) { - xs.push_back(results.xs); - us.push_back(results.us); - // lams.push_back(results.lams); - } - if (store_values_) { - values.push_back(results.traj_cost_); - merit_values.push_back(results.merit_value_); - } - if (store_residuals_) { - prim_infeas.push_back(results.prim_infeas); - dual_infeas.push_back(results.dual_infeas); - } - // if (auto w = dynamic_cast *>(&workspace)) { - // inner_crits.push_back(w->inner_criterion); - // } - if (auto r = dynamic_cast *>(&results)) { - al_index.push_back(r->al_iter); - } - } + void call(const Workspace & /*workspace*/, const Results &results); bool store_primal_dual_vars_; bool store_values_; - bool store_residuals_; + +private: + std::type_index rtti_; + std::any solver_; }; } // namespace aligator diff --git a/include/aligator/helpers/history-callback.hxx b/include/aligator/helpers/history-callback.hxx new file mode 100644 index 000000000..4e0dc1658 --- /dev/null +++ b/include/aligator/helpers/history-callback.hxx @@ -0,0 +1,35 @@ +#include "history-callback.hpp" + +#include "aligator/solvers/proxddp/solver-proxddp.hpp" + +namespace aligator { + +template +void HistoryCallbackTpl::call(const Workspace & /*workspace*/, + const Results &results) { + if (store_primal_dual_vars_) { + xs.push_back(results.xs); + us.push_back(results.us); + // lams.push_back(results.lams); + } + if (store_values_) { + values.push_back(results.traj_cost_); + merit_values.push_back(results.merit_value_); + } + prim_infeas.push_back(results.prim_infeas); + dual_infeas.push_back(results.dual_infeas); + // if (auto w = dynamic_cast *>(&workspace)) { + // inner_crits.push_back(w->inner_criterion); + // } + if (auto r = dynamic_cast *>(&results)) { + al_index.push_back(r->al_iter); + } + + if (rtti_ == typeid(SolverProxDDPTpl)) { + auto *s = std::any_cast *>(solver_); + prim_tols.push_back(s->prim_tol_); + dual_tols.push_back(s->inner_tol_); + } +} + +} // namespace aligator diff --git a/include/aligator/overloads.hpp b/include/aligator/overloads.hpp new file mode 100644 index 000000000..0a830e524 --- /dev/null +++ b/include/aligator/overloads.hpp @@ -0,0 +1,11 @@ +#pragma once + +namespace aligator { + +/// @brief Utility helper struct for creating visitors from lambdas. +template struct overloads : Ts... { + using Ts::operator()...; +}; +template overloads(Ts...) -> overloads; + +} // namespace aligator diff --git a/include/aligator/solvers/proxddp/solver-proxddp.hpp b/include/aligator/solvers/proxddp/solver-proxddp.hpp index bc2c3583f..274b04b2e 100644 --- a/include/aligator/solvers/proxddp/solver-proxddp.hpp +++ b/include/aligator/solvers/proxddp/solver-proxddp.hpp @@ -3,7 +3,9 @@ /// @copyright Copyright (C) 2022-2024 LAAS-CNRS, INRIA #pragma once +#include "aligator/overloads.hpp" #include "aligator/core/linesearch.hpp" +#include "aligator/core/linesearch-nonmonotone.hpp" #include "aligator/core/filter.hpp" #include "aligator/core/callback-base.hpp" #include "aligator/core/enums.hpp" @@ -14,6 +16,7 @@ #include "results.hpp" #include +#include namespace aligator { namespace gar { @@ -32,8 +35,6 @@ enum class LQSolverChoice { SERIAL, PARALLEL, STAGEDENSE }; /// implementation. template struct SolverProxDDPTpl { public: - // typedefs - using Scalar = _Scalar; ALIGATOR_DYNAMIC_TYPEDEFS(Scalar); using Problem = TrajOptProblemTpl; @@ -50,8 +51,53 @@ template struct SolverProxDDPTpl { using CstrSet = ConstraintSetTpl; using TrajOptData = TrajOptDataTpl; using LinesearchOptions = typename Linesearch::Options; - using LinesearchType = proxsuite::nlp::ArmijoLinesearch; - using Filter = FilterTpl; + + struct LinesearchVariant { + using fun_t = std::function; + using variant_t = std::variant, + NonmonotoneLinesearch>; + + Scalar run(const fun_t &fun, const Scalar phi0, const Scalar dphi0, + Scalar &alpha_try) { + return std::visit( + overloads{[](std::monostate &) { + return std::numeric_limits::quiet_NaN(); + }, + [&](auto &&method) { + return method.run(fun, phi0, dphi0, alpha_try); + }}, + impl_); + } + + void reset() { + std::visit(overloads{[](std::monostate &) {}, + [&](auto &&method) { method.reset(); }}, + impl_); + } + + Scalar isValid() const { return impl_.index() > 0ul; } + + operator const variant_t &() const { return impl_; } + + private: + explicit LinesearchVariant() {} + void init(StepAcceptanceStrategy strat, const LinesearchOptions &options) { + switch (strat) { + case StepAcceptanceStrategy::LINESEARCH_ARMIJO: + impl_ = ArmijoLinesearch(options); + break; + case StepAcceptanceStrategy::LINESEARCH_NONMONOTONE: + impl_ = NonmonotoneLinesearch(options); + break; + default: + ALIGATOR_WARNING("LinesearchVariant::", + "provided StepAcceptanceStrategy is invalid."); + break; + } + } + friend SolverProxDDPTpl; + variant_t impl_; + }; struct AlmParams { /// Log-factor \f$\alpha_\eta\f$ for primal tolerance (failure) @@ -113,13 +159,10 @@ template struct SolverProxDDPTpl { VerboseLevel verbose_; /// Choice of linear solver LQSolverChoice linear_solver_choice = LQSolverChoice::SERIAL; - bool lq_print_detailed = false; /// Type of Hessian approximation. Default is Gauss-Newton. HessianApprox hess_approx_ = HessianApprox::GAUSS_NEWTON; /// Linesearch options, as in proxsuite-nlp. LinesearchOptions ls_params; - /// Type of linesearch strategy. Default is Armijo. - LinesearchStrategy ls_strat = LinesearchStrategy::ARMIJO; /// Type of Lagrange multiplier update. MultiplierUpdateMode multiplier_update_mode = MultiplierUpdateMode::NEWTON; /// Linesearch mode. @@ -131,7 +174,7 @@ template struct SolverProxDDPTpl { /// Parameters for the BCL outer loop of the augmented Lagrangian algorithm. AlmParams bcl_params; /// Step acceptance mode. - StepAcceptanceStrategy sa_strategy = StepAcceptanceStrategy::LINESEARCH; + StepAcceptanceStrategy sa_strategy_; /// Force the initial state @f$ x_0 @f$ to be fixed to the problem initial /// condition. @@ -148,9 +191,9 @@ template struct SolverProxDDPTpl { Results results_; /// LQR subproblem solver std::unique_ptr> linearSolver_; - Filter filter_; + FilterTpl filter_; /// Linesearch function - LinesearchType linesearch_; + LinesearchVariant linesearch_; private: /// Callbacks @@ -167,6 +210,8 @@ template struct SolverProxDDPTpl { SolverProxDDPTpl(const Scalar tol = 1e-6, const Scalar mu_init = 0.01, const std::size_t max_iters = 1000, VerboseLevel verbose = VerboseLevel::QUIET, + StepAcceptanceStrategy sa_strategy = + StepAcceptanceStrategy::LINESEARCH_NONMONOTONE, HessianApprox hess_approx = HessianApprox::GAUSS_NEWTON); inline std::size_t getNumThreads() const { return num_threads_; } diff --git a/include/aligator/solvers/proxddp/solver-proxddp.hxx b/include/aligator/solvers/proxddp/solver-proxddp.hxx index 512df57cd..4191b2043 100644 --- a/include/aligator/solvers/proxddp/solver-proxddp.hxx +++ b/include/aligator/solvers/proxddp/solver-proxddp.hxx @@ -71,12 +71,13 @@ SolverProxDDPTpl::SolverProxDDPTpl(const Scalar tol, const Scalar mu_init, const std::size_t max_iters, VerboseLevel verbose, + StepAcceptanceStrategy sa_strategy, HessianApprox hess_approx) : target_tol_(tol), target_dual_tol_(tol), sync_dual_tol(true), mu_init(mu_init), verbose_(verbose), hess_approx_(hess_approx), - max_iters(max_iters), rollout_max_iters(1), + sa_strategy_(sa_strategy), max_iters(max_iters), rollout_max_iters(1), filter_(0.0, ls_params.alpha_min, ls_params.max_num_steps), - linesearch_(ls_params) { + linesearch_() { ls_params.interp_type = proxsuite::nlp::LSInterpolation::CUBIC; } @@ -146,11 +147,12 @@ void SolverProxDDPTpl::setup(const Problem &problem) { if (!problem.checkIntegrity()) ALIGATOR_RUNTIME_ERROR("Problem failed integrity check."); + linesearch_.init(sa_strategy_, ls_params); + results_.~Results(); workspace_.~Workspace(); new (&results_) Results(problem); new (&workspace_) Workspace(problem); - linesearch_.setOptions(ls_params); switch (linear_solver_choice) { case LQSolverChoice::SERIAL: { @@ -512,6 +514,7 @@ bool SolverProxDDPTpl::run(const Problem &problem, al_iter++; break; } + linesearch_.reset(); // accept primal updates workspace_.prev_xs = results_.xs; @@ -670,8 +673,10 @@ bool SolverProxDDPTpl::innerLoop(const Problem &problem) { Scalar alpha_opt = 1; Scalar phi_new; - switch (sa_strategy) { - case StepAcceptanceStrategy::LINESEARCH: + switch (sa_strategy_) { + case StepAcceptanceStrategy::LINESEARCH_ARMIJO: + case StepAcceptanceStrategy::LINESEARCH_NONMONOTONE: + assert(linesearch_.isValid()); phi_new = linesearch_.run(merit_eval_fun, phi0, dphi0, alpha_opt); break; case StepAcceptanceStrategy::FILTER: diff --git a/pixi.lock b/pixi.lock index 3a3e30bbd..668103210 100644 --- a/pixi.lock +++ b/pixi.lock @@ -41,7 +41,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/fmt-11.0.2-h434a139_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.54.1-py312h178313f_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.55.0-py312h178313f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.12.1-h267a509_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-hfea6d02_1.conda @@ -132,7 +132,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.4.0-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.4-hb346dea_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.5-hb346dea_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lz4-c-1.9.4-hcb278e6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lzo-2.10-hd590300_1001.conda @@ -185,7 +185,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/simde-0.8.2-h84d6215_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.16.0-pyh6c4a22f_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/suitesparse-7.8.3-hb42a789_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/suitesparse-7.8.3-hb42a789_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h4a8ded7_18.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tbb-2022.0.0-hceb3a55_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h59595ed_0.conda @@ -208,7 +208,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxdmcp-1.1.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.2.6-h166bdaf_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_6.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.6-ha6fb4c9_0.conda osx-64: @@ -252,7 +252,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/fmt-11.0.2-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.54.1-py312hbe3f5e4_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.55.0-py312h3520af0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.12.1-h60636b9_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/gdbm-1.18-h8a0c380_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/gettext-0.22.5-hdfe23c8_3.conda @@ -321,7 +321,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.49.2-hd79239c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.4.0-h10d778d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.4-h12808cf_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.5-h495214b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-19.1.3-hf78d878_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-17.0.6-hbedff68_1.conda @@ -373,7 +373,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/simde-0.8.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.16.0-pyh6c4a22f_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/suitesparse-7.8.3-h51aacc0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/suitesparse-7.8.3-h440b1d8_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tbb-2022.0.0-h0ec6371_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h73e2aa4_0.conda @@ -396,7 +396,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxdmcp-1.1.5-h00291cd_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xz-5.2.6-h775f41a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/yaml-0.2.5-h0d85af4_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-he4ceba3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-h7130eaa_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zstd-1.5.6-h915ae27_0.conda osx-arm64: @@ -440,7 +440,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fmt-11.0.2-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.54.1-py312ha0ccf2a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.55.0-py312h998013c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.12.1-hadb7bae_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-0.22.5-h8414b35_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-tools-0.22.5-h8414b35_3.conda @@ -509,7 +509,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.49.2-h7ab814d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.4.0-h93a5062_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.4-h8424949_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.5-hbbdcc80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-19.1.3-hb52a8e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-17.0.6-h5090b49_2.conda @@ -562,7 +562,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/simde-0.8.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.16.0-pyh6c4a22f_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/suitesparse-7.8.3-hcefb574_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/suitesparse-7.8.3-h12cb078_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tbb-2022.0.0-h0cbf7ec_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-hebf3989_0.conda @@ -585,7 +585,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxdmcp-1.1.5-hd74edd7_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xz-5.2.6-h57fd34a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/yaml-0.2.5-h3422bc3_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-h9f5b81c_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-hc1bb282_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zstd-1.5.6-hb46c0d2_0.conda all-py39: @@ -629,7 +629,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/fmt-11.0.2-h434a139_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.54.1-py39h9399b63_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.55.0-py39h9399b63_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.12.1-h267a509_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-hfea6d02_1.conda @@ -722,7 +722,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.4.0-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.4-hb346dea_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.5-hb346dea_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lz4-c-1.9.4-hcb278e6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lzo-2.10-hd590300_1001.conda @@ -775,7 +775,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/simde-0.8.2-h84d6215_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.16.0-pyh6c4a22f_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/suitesparse-7.8.3-hb42a789_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/suitesparse-7.8.3-hb42a789_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h4a8ded7_18.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tbb-2022.0.0-hceb3a55_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h59595ed_0.conda @@ -798,7 +798,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxdmcp-1.1.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.2.6-h166bdaf_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_6.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda - conda: https://conda.anaconda.org/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.6-ha6fb4c9_0.conda @@ -843,7 +843,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/fmt-11.0.2-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.54.1-py39h20cc651_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.55.0-py39hd18e689_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.12.1-h60636b9_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/gdbm-1.18-h8a0c380_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/gettext-0.22.5-hdfe23c8_3.conda @@ -914,7 +914,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.49.2-hd79239c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.4.0-h10d778d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.4-h12808cf_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.5-h495214b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-19.1.3-hf78d878_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-17.0.6-hbedff68_1.conda @@ -966,7 +966,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/simde-0.8.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.16.0-pyh6c4a22f_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/suitesparse-7.8.3-h51aacc0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/suitesparse-7.8.3-h440b1d8_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tbb-2022.0.0-h0ec6371_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h73e2aa4_0.conda @@ -989,7 +989,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxdmcp-1.1.5-h00291cd_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xz-5.2.6-h775f41a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/yaml-0.2.5-h0d85af4_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-he4ceba3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-h7130eaa_7.conda - conda: https://conda.anaconda.org/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zstd-1.5.6-h915ae27_0.conda @@ -1034,7 +1034,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fmt-11.0.2-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.54.1-py39h66d85bf_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.55.0-py39hefdd603_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.12.1-hadb7bae_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-0.22.5-h8414b35_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-tools-0.22.5-h8414b35_3.conda @@ -1105,7 +1105,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.49.2-h7ab814d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.4.0-h93a5062_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.4-h8424949_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.5-hbbdcc80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-19.1.3-hb52a8e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-17.0.6-h5090b49_2.conda @@ -1158,7 +1158,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/simde-0.8.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.16.0-pyh6c4a22f_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/suitesparse-7.8.3-hcefb574_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/suitesparse-7.8.3-h12cb078_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tbb-2022.0.0-h0cbf7ec_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-hebf3989_0.conda @@ -1181,7 +1181,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxdmcp-1.1.5-hd74edd7_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xz-5.2.6-h57fd34a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/yaml-0.2.5-h3422bc3_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-h9f5b81c_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-hc1bb282_7.conda - conda: https://conda.anaconda.org/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zstd-1.5.6-hb46c0d2_0.conda @@ -1224,7 +1224,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/fmt-11.0.2-h434a139_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.54.1-py312h178313f_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.55.0-py312h178313f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.12.1-h267a509_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-hfea6d02_1.conda @@ -1315,7 +1315,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.4.0-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.4-hb346dea_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.5-hb346dea_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lz4-c-1.9.4-hcb278e6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lzo-2.10-hd590300_1001.conda @@ -1368,7 +1368,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/simde-0.8.2-h84d6215_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.16.0-pyh6c4a22f_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/suitesparse-7.8.3-hb42a789_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/suitesparse-7.8.3-hb42a789_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h4a8ded7_18.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tbb-2022.0.0-hceb3a55_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h59595ed_0.conda @@ -1391,7 +1391,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxdmcp-1.1.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.2.6-h166bdaf_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_6.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.6-ha6fb4c9_0.conda osx-64: @@ -1433,7 +1433,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/fmt-11.0.2-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.54.1-py312hbe3f5e4_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.55.0-py312h3520af0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.12.1-h60636b9_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/gdbm-1.18-h8a0c380_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/gettext-0.22.5-hdfe23c8_3.conda @@ -1502,7 +1502,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.49.2-hd79239c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.4.0-h10d778d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.4-h12808cf_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.5-h495214b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-19.1.3-hf78d878_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-17.0.6-hbedff68_1.conda @@ -1554,7 +1554,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/simde-0.8.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.16.0-pyh6c4a22f_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/suitesparse-7.8.3-h51aacc0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/suitesparse-7.8.3-h440b1d8_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tbb-2022.0.0-h0ec6371_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h73e2aa4_0.conda @@ -1577,7 +1577,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxdmcp-1.1.5-h00291cd_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xz-5.2.6-h775f41a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/yaml-0.2.5-h0d85af4_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-he4ceba3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-h7130eaa_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zstd-1.5.6-h915ae27_0.conda osx-arm64: @@ -1619,7 +1619,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fmt-11.0.2-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.54.1-py312ha0ccf2a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.55.0-py312h998013c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.12.1-hadb7bae_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-0.22.5-h8414b35_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-tools-0.22.5-h8414b35_3.conda @@ -1688,7 +1688,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.49.2-h7ab814d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.4.0-h93a5062_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.4-h8424949_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.5-hbbdcc80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-19.1.3-hb52a8e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-17.0.6-h5090b49_2.conda @@ -1741,7 +1741,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/simde-0.8.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.16.0-pyh6c4a22f_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/suitesparse-7.8.3-hcefb574_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/suitesparse-7.8.3-h12cb078_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tbb-2022.0.0-h0cbf7ec_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-hebf3989_0.conda @@ -1764,7 +1764,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxdmcp-1.1.5-hd74edd7_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xz-5.2.6-h57fd34a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/yaml-0.2.5-h3422bc3_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-h9f5b81c_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-hc1bb282_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zstd-1.5.6-hb46c0d2_0.conda clang: @@ -1809,7 +1809,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/fmt-11.0.2-h434a139_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.54.1-py312h178313f_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.55.0-py312h178313f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.12.1-h267a509_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-hfea6d02_1.conda @@ -1902,7 +1902,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.4.0-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.4-hb346dea_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.5-hb346dea_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lz4-c-1.9.4-hcb278e6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lzo-2.10-hd590300_1001.conda @@ -1975,7 +1975,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxdmcp-1.1.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.2.6-h166bdaf_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_6.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.6-ha6fb4c9_0.conda crocoddyl: @@ -2019,7 +2019,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/fmt-11.0.2-h434a139_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.54.1-py312h178313f_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.55.0-py312h178313f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.12.1-h267a509_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-hfea6d02_1.conda @@ -2110,7 +2110,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.4.0-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.4-hb346dea_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.5-hb346dea_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lz4-c-1.9.4-hcb278e6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lzo-2.10-hd590300_1001.conda @@ -2183,7 +2183,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxdmcp-1.1.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.2.6-h166bdaf_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_6.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.6-ha6fb4c9_0.conda osx-64: @@ -2227,7 +2227,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/fmt-11.0.2-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.54.1-py312hbe3f5e4_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.55.0-py312h3520af0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.12.1-h60636b9_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/gdbm-1.18-h8a0c380_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/gettext-0.22.5-hdfe23c8_3.conda @@ -2295,7 +2295,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.49.2-hd79239c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.4.0-h10d778d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.4-h12808cf_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.5-h495214b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-19.1.3-hf78d878_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-17.0.6-hbedff68_1.conda @@ -2367,7 +2367,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxdmcp-1.1.5-h00291cd_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xz-5.2.6-h775f41a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/yaml-0.2.5-h0d85af4_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-he4ceba3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-h7130eaa_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zstd-1.5.6-h915ae27_0.conda osx-arm64: @@ -2411,7 +2411,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fmt-11.0.2-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.54.1-py312ha0ccf2a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.55.0-py312h998013c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.12.1-hadb7bae_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-0.22.5-h8414b35_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-tools-0.22.5-h8414b35_3.conda @@ -2479,7 +2479,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.49.2-h7ab814d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.4.0-h93a5062_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.4-h8424949_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.5-hbbdcc80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-19.1.3-hb52a8e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-17.0.6-h5090b49_2.conda @@ -2552,7 +2552,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxdmcp-1.1.5-hd74edd7_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xz-5.2.6-h57fd34a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/yaml-0.2.5-h3422bc3_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-h9f5b81c_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-hc1bb282_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zstd-1.5.6-hb46c0d2_0.conda default: @@ -2594,7 +2594,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/fmt-11.0.2-h434a139_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.54.1-py312h178313f_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.55.0-py312h178313f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.12.1-h267a509_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-hfea6d02_1.conda @@ -2685,7 +2685,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.4.0-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.4-hb346dea_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.5-hb346dea_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lz4-c-1.9.4-hcb278e6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lzo-2.10-hd590300_1001.conda @@ -2758,7 +2758,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxdmcp-1.1.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.2.6-h166bdaf_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_6.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.6-ha6fb4c9_0.conda osx-64: @@ -2800,7 +2800,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/fmt-11.0.2-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.54.1-py312hbe3f5e4_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.55.0-py312h3520af0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.12.1-h60636b9_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/gdbm-1.18-h8a0c380_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/gettext-0.22.5-hdfe23c8_3.conda @@ -2868,7 +2868,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.49.2-hd79239c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.4.0-h10d778d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.4-h12808cf_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.5-h495214b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-19.1.3-hf78d878_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-17.0.6-hbedff68_1.conda @@ -2940,7 +2940,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxdmcp-1.1.5-h00291cd_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xz-5.2.6-h775f41a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/yaml-0.2.5-h0d85af4_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-he4ceba3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-h7130eaa_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zstd-1.5.6-h915ae27_0.conda osx-arm64: @@ -2982,7 +2982,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fmt-11.0.2-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.54.1-py312ha0ccf2a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.55.0-py312h998013c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.12.1-hadb7bae_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-0.22.5-h8414b35_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-tools-0.22.5-h8414b35_3.conda @@ -3050,7 +3050,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.49.2-h7ab814d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.4.0-h93a5062_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.4-h8424949_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.5-hbbdcc80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-19.1.3-hb52a8e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-17.0.6-h5090b49_2.conda @@ -3123,7 +3123,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxdmcp-1.1.5-hd74edd7_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xz-5.2.6-h57fd34a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/yaml-0.2.5-h3422bc3_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-h9f5b81c_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-hc1bb282_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zstd-1.5.6-hb46c0d2_0.conda lint: @@ -3169,7 +3169,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/filelock-3.16.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/fmt-11.0.2-h434a139_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.54.1-py312h178313f_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.55.0-py312h178313f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.12.1-h267a509_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-hfea6d02_1.conda @@ -3261,7 +3261,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.4.0-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.4-hb346dea_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.5-hb346dea_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lz4-c-1.9.4-hcb278e6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lzo-2.10-hd590300_1001.conda @@ -3341,7 +3341,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxdmcp-1.1.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.2.6-h166bdaf_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_6.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.6-ha6fb4c9_0.conda osx-64: @@ -3387,7 +3387,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/filelock-3.16.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/fmt-11.0.2-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.54.1-py312hbe3f5e4_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.55.0-py312h3520af0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.12.1-h60636b9_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/gdbm-1.18-h8a0c380_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/gettext-0.22.5-hdfe23c8_3.conda @@ -3456,7 +3456,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.49.2-hd79239c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.4.0-h10d778d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.4-h12808cf_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.5-h495214b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-19.1.3-hf78d878_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-17.0.6-hbedff68_1.conda @@ -3535,7 +3535,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxdmcp-1.1.5-h00291cd_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xz-5.2.6-h775f41a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/yaml-0.2.5-h0d85af4_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-he4ceba3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-h7130eaa_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zstd-1.5.6-h915ae27_0.conda osx-arm64: @@ -3581,7 +3581,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/filelock-3.16.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fmt-11.0.2-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.54.1-py312ha0ccf2a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.55.0-py312h998013c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.12.1-hadb7bae_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-0.22.5-h8414b35_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-tools-0.22.5-h8414b35_3.conda @@ -3650,7 +3650,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.49.2-h7ab814d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.4.0-h93a5062_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.4-h8424949_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.5-hbbdcc80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-19.1.3-hb52a8e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-17.0.6-h5090b49_2.conda @@ -3730,7 +3730,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxdmcp-1.1.5-hd74edd7_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xz-5.2.6-h57fd34a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/yaml-0.2.5-h3422bc3_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-h9f5b81c_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-hc1bb282_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zstd-1.5.6-hb46c0d2_0.conda openmp: @@ -3772,7 +3772,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/fmt-11.0.2-h434a139_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.54.1-py312h178313f_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.55.0-py312h178313f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.12.1-h267a509_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-hfea6d02_1.conda @@ -3863,7 +3863,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.4.0-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.4-hb346dea_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.5-hb346dea_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lz4-c-1.9.4-hcb278e6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lzo-2.10-hd590300_1001.conda @@ -3936,7 +3936,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxdmcp-1.1.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.2.6-h166bdaf_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_6.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.6-ha6fb4c9_0.conda osx-64: @@ -3978,7 +3978,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/fmt-11.0.2-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.54.1-py312hbe3f5e4_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.55.0-py312h3520af0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.12.1-h60636b9_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/gdbm-1.18-h8a0c380_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/gettext-0.22.5-hdfe23c8_3.conda @@ -4046,7 +4046,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.49.2-hd79239c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.4.0-h10d778d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.4-h12808cf_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.5-h495214b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-19.1.3-hf78d878_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-17.0.6-hbedff68_1.conda @@ -4118,7 +4118,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxdmcp-1.1.5-h00291cd_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xz-5.2.6-h775f41a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/yaml-0.2.5-h0d85af4_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-he4ceba3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-h7130eaa_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zstd-1.5.6-h915ae27_0.conda osx-arm64: @@ -4160,7 +4160,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fmt-11.0.2-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.54.1-py312ha0ccf2a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.55.0-py312h998013c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.12.1-hadb7bae_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-0.22.5-h8414b35_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-tools-0.22.5-h8414b35_3.conda @@ -4228,7 +4228,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.49.2-h7ab814d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.4.0-h93a5062_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.4-h8424949_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.5-hbbdcc80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-19.1.3-hb52a8e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-17.0.6-h5090b49_2.conda @@ -4301,7 +4301,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxdmcp-1.1.5-hd74edd7_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xz-5.2.6-h57fd34a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/yaml-0.2.5-h3422bc3_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-h9f5b81c_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-hc1bb282_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zstd-1.5.6-hb46c0d2_0.conda pinocchio: @@ -4344,7 +4344,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/fmt-11.0.2-h434a139_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.54.1-py312h178313f_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.55.0-py312h178313f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.12.1-h267a509_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-hfea6d02_1.conda @@ -4435,7 +4435,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.4.0-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.4-hb346dea_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.5-hb346dea_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lz4-c-1.9.4-hcb278e6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lzo-2.10-hd590300_1001.conda @@ -4508,7 +4508,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxdmcp-1.1.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.2.6-h166bdaf_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_6.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.6-ha6fb4c9_0.conda osx-64: @@ -4551,7 +4551,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/fmt-11.0.2-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.54.1-py312hbe3f5e4_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.55.0-py312h3520af0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.12.1-h60636b9_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/gdbm-1.18-h8a0c380_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/gettext-0.22.5-hdfe23c8_3.conda @@ -4619,7 +4619,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.49.2-hd79239c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.4.0-h10d778d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.4-h12808cf_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.5-h495214b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-19.1.3-hf78d878_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-17.0.6-hbedff68_1.conda @@ -4691,7 +4691,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxdmcp-1.1.5-h00291cd_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xz-5.2.6-h775f41a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/yaml-0.2.5-h0d85af4_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-he4ceba3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-h7130eaa_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zstd-1.5.6-h915ae27_0.conda osx-arm64: @@ -4734,7 +4734,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fmt-11.0.2-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.54.1-py312ha0ccf2a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.55.0-py312h998013c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.12.1-hadb7bae_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-0.22.5-h8414b35_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-tools-0.22.5-h8414b35_3.conda @@ -4802,7 +4802,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.49.2-h7ab814d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.4.0-h93a5062_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.4-h8424949_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.5-hbbdcc80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-19.1.3-hb52a8e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-17.0.6-h5090b49_2.conda @@ -4875,7 +4875,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxdmcp-1.1.5-hd74edd7_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xz-5.2.6-h57fd34a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/yaml-0.2.5-h3422bc3_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-h9f5b81c_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-hc1bb282_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zstd-1.5.6-hb46c0d2_0.conda py39: @@ -4917,7 +4917,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/fmt-11.0.2-h434a139_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.54.1-py39h9399b63_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.55.0-py39h9399b63_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.12.1-h267a509_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-hfea6d02_1.conda @@ -5010,7 +5010,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.4.0-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.4-hb346dea_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.5-hb346dea_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lz4-c-1.9.4-hcb278e6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lzo-2.10-hd590300_1001.conda @@ -5083,7 +5083,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxdmcp-1.1.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.2.6-h166bdaf_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_6.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda - conda: https://conda.anaconda.org/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.6-ha6fb4c9_0.conda @@ -5126,7 +5126,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/fmt-11.0.2-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.54.1-py39h20cc651_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.55.0-py39hd18e689_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.12.1-h60636b9_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/gdbm-1.18-h8a0c380_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/gettext-0.22.5-hdfe23c8_3.conda @@ -5196,7 +5196,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.49.2-hd79239c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.4.0-h10d778d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.4-h12808cf_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.5-h495214b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-19.1.3-hf78d878_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-17.0.6-hbedff68_1.conda @@ -5268,7 +5268,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxdmcp-1.1.5-h00291cd_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xz-5.2.6-h775f41a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/yaml-0.2.5-h0d85af4_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-he4ceba3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-h7130eaa_7.conda - conda: https://conda.anaconda.org/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zstd-1.5.6-h915ae27_0.conda @@ -5311,7 +5311,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fmt-11.0.2-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.54.1-py39h66d85bf_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.55.0-py39hefdd603_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.12.1-hadb7bae_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-0.22.5-h8414b35_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-tools-0.22.5-h8414b35_3.conda @@ -5381,7 +5381,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.49.2-h7ab814d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.4.0-h93a5062_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.4-h8424949_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.5-hbbdcc80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-19.1.3-hb52a8e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-17.0.6-h5090b49_2.conda @@ -5454,7 +5454,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxdmcp-1.1.5-hd74edd7_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xz-5.2.6-h57fd34a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/yaml-0.2.5-h3422bc3_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-h9f5b81c_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-hc1bb282_7.conda - conda: https://conda.anaconda.org/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zstd-1.5.6-hb46c0d2_0.conda @@ -5497,7 +5497,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/fmt-11.0.2-h434a139_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.54.1-py312h178313f_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.55.0-py312h178313f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.12.1-h267a509_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-hfea6d02_1.conda @@ -5588,7 +5588,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.4.0-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.4-hb346dea_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.5-hb346dea_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lz4-c-1.9.4-hcb278e6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lzo-2.10-hd590300_1001.conda @@ -5662,7 +5662,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxdmcp-1.1.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.2.6-h166bdaf_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_6.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.6-ha6fb4c9_0.conda osx-64: @@ -5704,7 +5704,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/fmt-11.0.2-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.54.1-py312hbe3f5e4_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.55.0-py312h3520af0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.12.1-h60636b9_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/gdbm-1.18-h8a0c380_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/gettext-0.22.5-hdfe23c8_3.conda @@ -5772,7 +5772,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.49.2-hd79239c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.4.0-h10d778d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.4-h12808cf_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.5-h495214b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-19.1.3-hf78d878_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-17.0.6-hbedff68_1.conda @@ -5845,7 +5845,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxdmcp-1.1.5-h00291cd_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xz-5.2.6-h775f41a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/yaml-0.2.5-h0d85af4_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-he4ceba3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-h7130eaa_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zlib-1.3.1-hd23fc13_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zstd-1.5.6-h915ae27_0.conda osx-arm64: @@ -5887,7 +5887,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fmt-11.0.2-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.54.1-py312ha0ccf2a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.55.0-py312h998013c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.12.1-hadb7bae_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-0.22.5-h8414b35_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gettext-tools-0.22.5-h8414b35_3.conda @@ -5955,7 +5955,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.49.2-h7ab814d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.4.0-h93a5062_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.4-h8424949_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.5-hbbdcc80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-19.1.3-hb52a8e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-17.0.6-h5090b49_2.conda @@ -6028,7 +6028,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxdmcp-1.1.5-hd74edd7_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xz-5.2.6-h57fd34a_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/yaml-0.2.5-h3422bc3_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-h9f5b81c_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-hc1bb282_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zlib-1.3.1-h8359307_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zstd-1.5.6-hb46c0d2_0.conda packages: @@ -8192,13 +8192,12 @@ packages: timestamp: 1723046725112 - kind: conda name: fonttools - version: 4.54.1 - build: py312h178313f_1 - build_number: 1 + version: 4.55.0 + build: py312h178313f_0 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.54.1-py312h178313f_1.conda - sha256: 45f405d6d1ef528226c20b681373db0bdb79cc70fec1e495003247b0d3d00140 - md5: bbbf5fa5cab622c33907bc8d7eeea9f7 + url: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.55.0-py312h178313f_0.conda + sha256: 2a8d4fe8968828584057f8b07f3e102e326d8ec08d0e30e4ecc21f35031239a0 + md5: f404f4fb99ccaea68b00c1cc64fc1e68 depends: - __glibc >=2.17,<3.0.a0 - brotli @@ -8209,111 +8208,106 @@ packages: - unicodedata2 >=15.1.0 license: MIT license_family: MIT - size: 2827447 - timestamp: 1729530553018 + size: 2843090 + timestamp: 1731643626471 - kind: conda name: fonttools - version: 4.54.1 - build: py312ha0ccf2a_1 - build_number: 1 - subdir: osx-arm64 - url: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.54.1-py312ha0ccf2a_1.conda - sha256: 7db92b5980ac60c362d2c7fa9c75c21578b0ebe58a23ba6e123f47d4d3baca53 - md5: 1d203fe9d62f4d2fea1c955d77bc642a + version: 4.55.0 + build: py312h3520af0_0 + subdir: osx-64 + url: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.55.0-py312h3520af0_0.conda + sha256: 30f6c8d85c2470b6f01c9e673a0f4f5662a58f75d9bef17a038d01071802246b + md5: 804285e14c733803a8301139185d02ad depends: - - __osx >=11.0 + - __osx >=10.13 - brotli - munkres - python >=3.12,<3.13.0a0 - - python >=3.12,<3.13.0a0 *_cpython - python_abi 3.12.* *_cp312 - unicodedata2 >=15.1.0 license: MIT license_family: MIT - size: 2730304 - timestamp: 1729530557674 + size: 2744633 + timestamp: 1731643699104 - kind: conda name: fonttools - version: 4.54.1 - build: py312hbe3f5e4_1 - build_number: 1 - subdir: osx-64 - url: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.54.1-py312hbe3f5e4_1.conda - sha256: bec969c41482df669dcc17e8450693d206e0c155c46c47924ceb634f766df180 - md5: e58d62085d1b304863373b89caf8f5d4 + version: 4.55.0 + build: py312h998013c_0 + subdir: osx-arm64 + url: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.55.0-py312h998013c_0.conda + sha256: 427d75267cfeee820498efeea59477790f7e28cdbe0f18a8484f23dae9a85cce + md5: b009bb8037e769ff4fd6439642268ecb depends: - - __osx >=10.13 + - __osx >=11.0 - brotli - munkres - python >=3.12,<3.13.0a0 + - python >=3.12,<3.13.0a0 *_cpython - python_abi 3.12.* *_cp312 - unicodedata2 >=15.1.0 license: MIT license_family: MIT - size: 2727792 - timestamp: 1729530530279 + size: 2752240 + timestamp: 1731643678207 - kind: conda name: fonttools - version: 4.54.1 - build: py39h20cc651_1 - build_number: 1 - subdir: osx-64 - url: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.54.1-py39h20cc651_1.conda - sha256: 1276b42d990604c39b00eb276dc8fd3f6f5d43a494bf0af80f447ea2dbaf2a25 - md5: 9d2f30b8505bf6d48f796f8f8a6a48d6 + version: 4.55.0 + build: py39h9399b63_0 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.55.0-py39h9399b63_0.conda + sha256: bf3a2b4e4b0bdfd8c57f4a1858b89b6b9ca3a87ac28b60eee58043db1248a73c + md5: 61762136d872c6d2de2de7742a0c60ef depends: - - __osx >=10.13 + - __glibc >=2.17,<3.0.a0 - brotli + - libgcc >=13 - munkres - python >=3.9,<3.10.0a0 - python_abi 3.9.* *_cp39 - unicodedata2 >=15.1.0 license: MIT license_family: MIT - size: 2233810 - timestamp: 1729530583159 + size: 2312812 + timestamp: 1731643585934 - kind: conda name: fonttools - version: 4.54.1 - build: py39h66d85bf_1 - build_number: 1 - subdir: osx-arm64 - url: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.54.1-py39h66d85bf_1.conda - sha256: 53dbc66325ff7c0ba38221c64bf56b9691c412d24ca9d1ad654b314de1196fc7 - md5: 3618c2076963d56465bf5137d6a9566f + version: 4.55.0 + build: py39hd18e689_0 + subdir: osx-64 + url: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.55.0-py39hd18e689_0.conda + sha256: 5d2a4322c9c20b97f7ae532036737a0e1fd8cca54896d9c16fe2519cbb39b1be + md5: 66008e96883e821ea1364e980b2bde1a depends: - - __osx >=11.0 + - __osx >=10.13 - brotli - munkres - python >=3.9,<3.10.0a0 - - python >=3.9,<3.10.0a0 *_cpython - python_abi 3.9.* *_cp39 - unicodedata2 >=15.1.0 license: MIT license_family: MIT - size: 2219590 - timestamp: 1729530690457 + size: 2246534 + timestamp: 1731643634168 - kind: conda name: fonttools - version: 4.54.1 - build: py39h9399b63_1 - build_number: 1 - subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.54.1-py39h9399b63_1.conda - sha256: 4f1afc6b458cfd043d3ed22151f4127aab395ff8ad06d44f0e7e7813e6e285bb - md5: 1a4772f78ffa4675c84a4219db3934fd + version: 4.55.0 + build: py39hefdd603_0 + subdir: osx-arm64 + url: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.55.0-py39hefdd603_0.conda + sha256: dffc5e81f0b55ba5e3edfd0598953499b7f2b9fc36d225c0b5e94d228c58bd63 + md5: 1d4e2d4e0e6eacd407abad673480e8e9 depends: - - __glibc >=2.17,<3.0.a0 + - __osx >=11.0 - brotli - - libgcc >=13 - munkres - python >=3.9,<3.10.0a0 + - python >=3.9,<3.10.0a0 *_cpython - python_abi 3.9.* *_cp39 - unicodedata2 >=15.1.0 license: MIT license_family: MIT - size: 2322932 - timestamp: 1729530575488 + size: 2237078 + timestamp: 1731643756889 - kind: conda name: freetype version: 2.12.1 @@ -12460,13 +12454,12 @@ packages: timestamp: 1702724383534 - kind: conda name: libxml2 - version: 2.13.4 - build: h12808cf_2 - build_number: 2 + version: 2.13.5 + build: h495214b_0 subdir: osx-64 - url: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.4-h12808cf_2.conda - sha256: ce806e0f7430b709145ac406e7aacf3833adbdb91e085ed3f4dc8e78cf07038c - md5: 0649b977d9e3d2fd579148643884535e + url: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.5-h495214b_0.conda + sha256: 66e1bf40699daf83b39e1281f06c64cf83499de3a9c05d59477fadded6d85b18 + md5: 8711bc6fb054192dc432741dcd233ac3 depends: - __osx >=10.13 - icu >=75.1,<76.0a0 @@ -12475,47 +12468,45 @@ packages: - xz >=5.2.6,<6.0a0 license: MIT license_family: MIT - size: 601997 - timestamp: 1730355958301 + size: 608931 + timestamp: 1731489767386 - kind: conda name: libxml2 - version: 2.13.4 - build: h8424949_2 - build_number: 2 - subdir: osx-arm64 - url: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.4-h8424949_2.conda - sha256: 51048cd9d4d7ab3ab440bac01d1db8193ae1bd3e9502cdf6792a69c792fec2e5 - md5: 3f0764c38bc02720231d49d6035531f2 + version: 2.13.5 + build: hb346dea_0 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.5-hb346dea_0.conda + sha256: 8c9d6a3a421ac5bf965af495d1b0a08c6fb2245ba156550bc064a7b4f8fc7bd8 + md5: c81a9f1118541aaa418ccb22190c817e depends: - - __osx >=11.0 + - __glibc >=2.17,<3.0.a0 - icu >=75.1,<76.0a0 + - libgcc >=13 - libiconv >=1.17,<2.0a0 - libzlib >=1.3.1,<2.0a0 - xz >=5.2.6,<6.0a0 license: MIT license_family: MIT - size: 572400 - timestamp: 1730356085177 + size: 689626 + timestamp: 1731489608971 - kind: conda name: libxml2 - version: 2.13.4 - build: hb346dea_2 - build_number: 2 - subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.4-hb346dea_2.conda - sha256: a111cb7f2deb6e20ebb475e8426ce5291451476f55f0dec6c220aa51e5a5784f - md5: 69b90b70c434b916abf5a1d5ee5d55fb + version: 2.13.5 + build: hbbdcc80_0 + subdir: osx-arm64 + url: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.5-hbbdcc80_0.conda + sha256: 936de9c0e91cb6f178c48ea14313cf6c79bdb1f474c785c117c41492b0407a98 + md5: 967d4a9dadd710415ee008d862a07c99 depends: - - __glibc >=2.17,<3.0.a0 + - __osx >=11.0 - icu >=75.1,<76.0a0 - - libgcc >=13 - libiconv >=1.17,<2.0a0 - libzlib >=1.3.1,<2.0a0 - xz >=5.2.6,<6.0a0 license: MIT license_family: MIT - size: 690019 - timestamp: 1730355770718 + size: 583082 + timestamp: 1731489765442 - kind: conda name: libzlib version: 1.3.1 @@ -15639,73 +15630,79 @@ packages: - kind: conda name: suitesparse version: 7.8.3 - build: h51aacc0_0 - subdir: osx-64 - url: https://conda.anaconda.org/conda-forge/osx-64/suitesparse-7.8.3-h51aacc0_0.conda - sha256: 1cf6c61eca7577b3044321092021de69c81cdc179f10efd207e0e4cd35fc279f - md5: 6cf9b5565082a6c987d9eff694ae9254 + build: h12cb078_1 + build_number: 1 + subdir: osx-arm64 + url: https://conda.anaconda.org/conda-forge/osx-arm64/suitesparse-7.8.3-h12cb078_1.conda + sha256: 495d32b7370a5772cc6e4e71f1d86f5616d6957af8e0ac386f5654b5abfc11ac + md5: 25a13d1e2e16bcdf1e5b6b4885cc6da6 depends: - - __osx >=10.13 + - __osx >=11.0 - gmp >=6.3.0,<7.0a0 - libblas >=3.9.0,<4.0a0 - libcblas >=3.9.0,<4.0a0 - - libcxx >=17 + - libcxx >=18 - libgfortran 5.* - libgfortran5 >=13.2.0 - liblapack >=3.9.0,<4.0a0 + - llvm-openmp >=18.1.8 - metis >=5.1.0,<5.1.1.0a0 - mpfr >=4.2.1,<5.0a0 - tbb >=2021.13.0 license: LGPL-2.1-or-later AND BSD-3-Clause AND GPL-2.0-or-later AND Apache-2.0 - size: 1907384 - timestamp: 1730383477915 + size: 1363524 + timestamp: 1731612132482 - kind: conda name: suitesparse version: 7.8.3 - build: hb42a789_0 - subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/suitesparse-7.8.3-hb42a789_0.conda - sha256: c89f67e032e39dea769c1ebf7383641b776aee2ab42878fbf5745fa300576cb1 - md5: 216922e19843f5662a2b260f905640cb + build: h440b1d8_1 + build_number: 1 + subdir: osx-64 + url: https://conda.anaconda.org/conda-forge/osx-64/suitesparse-7.8.3-h440b1d8_1.conda + sha256: c3be1bbc91c783ad97458922bad9949b620ccdbae96e7f947039d7eb5d30bdf8 + md5: 0a53159c1cb6716733dbf7af55f51308 depends: - - __glibc >=2.17,<3.0.a0 + - __osx >=10.13 - gmp >=6.3.0,<7.0a0 - libblas >=3.9.0,<4.0a0 - libcblas >=3.9.0,<4.0a0 - - libgcc >=13 - - libgfortran - - libgfortran5 >=13.3.0 + - libcxx >=18 + - libgfortran 5.* + - libgfortran5 >=13.2.0 - liblapack >=3.9.0,<4.0a0 - - libstdcxx >=13 + - llvm-openmp >=18.1.8 - metis >=5.1.0,<5.1.1.0a0 - mpfr >=4.2.1,<5.0a0 - tbb >=2021.13.0 license: LGPL-2.1-or-later AND BSD-3-Clause AND GPL-2.0-or-later AND Apache-2.0 - size: 1838665 - timestamp: 1730383035378 + size: 1919414 + timestamp: 1731612041377 - kind: conda name: suitesparse version: 7.8.3 - build: hcefb574_0 - subdir: osx-arm64 - url: https://conda.anaconda.org/conda-forge/osx-arm64/suitesparse-7.8.3-hcefb574_0.conda - sha256: d4459ec19fd92676e3fe2a53636c6f26ea56593d2a2266d72f0ad0505f8c7718 - md5: 4cbbd1ae8e2e74f2480de640c12941a2 + build: hb42a789_1 + build_number: 1 + subdir: linux-64 + url: https://conda.anaconda.org/conda-forge/linux-64/suitesparse-7.8.3-hb42a789_1.conda + sha256: dff3ad8d66a4050763b1b63f4cab7c9b5f2e0e93d71639aebd8814b5ab23a9b4 + md5: 216fa6eae33d712fa688fa2d113a65ad depends: - - __osx >=11.0 + - __glibc >=2.17,<3.0.a0 + - _openmp_mutex >=4.5 - gmp >=6.3.0,<7.0a0 - libblas >=3.9.0,<4.0a0 - libcblas >=3.9.0,<4.0a0 - - libcxx >=17 - - libgfortran 5.* - - libgfortran5 >=13.2.0 + - libgcc >=13 + - libgfortran + - libgfortran5 >=13.3.0 - liblapack >=3.9.0,<4.0a0 + - libstdcxx >=13 - metis >=5.1.0,<5.1.1.0a0 - mpfr >=4.2.1,<5.0a0 - tbb >=2021.13.0 license: LGPL-2.1-or-later AND BSD-3-Clause AND GPL-2.0-or-later AND Apache-2.0 - size: 1355028 - timestamp: 1730383410695 + size: 1840784 + timestamp: 1731611614601 - kind: conda name: sysroot_linux-64 version: '2.17' @@ -16664,12 +16661,12 @@ packages: - kind: conda name: zeromq version: 4.3.5 - build: h3b0a872_6 - build_number: 6 + build: h3b0a872_7 + build_number: 7 subdir: linux-64 - url: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_6.conda - sha256: e67288b1c98a31ee58a5c07bdd873dbe08e75f752e1ad605d5e8c0697339903e - md5: 113506c8d2d558e733f5c38f6bf08c50 + url: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda + sha256: a4dc72c96848f764bb5a5176aa93dd1e9b9e52804137b99daeebba277b31ea10 + md5: 3947a35e916fcc6b9825449affbf4214 depends: - __glibc >=2.17,<3.0.a0 - krb5 >=1.21.3,<1.22.0a0 @@ -16678,44 +16675,44 @@ packages: - libstdcxx >=13 license: MPL-2.0 license_family: MOZILLA - size: 335528 - timestamp: 1728364029042 + size: 335400 + timestamp: 1731585026517 - kind: conda name: zeromq version: 4.3.5 - build: h9f5b81c_6 - build_number: 6 - subdir: osx-arm64 - url: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-h9f5b81c_6.conda - sha256: 5c5061c976141eccbbb2aec21483ddd10fd1df4fd9bcf638e3fd57b2bd85721f - md5: 84121ef1717cdfbecedeae70142706cc + build: h7130eaa_7 + build_number: 7 + subdir: osx-64 + url: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-h7130eaa_7.conda + sha256: b932dce8c9de9a8ffbf0db0365d29677636e599f7763ca51e554c43a0c5f8389 + md5: 6a0a76cd2b3d575e1b7aaeb283b9c3ed depends: - - __osx >=11.0 + - __osx >=10.13 - krb5 >=1.21.3,<1.22.0a0 - - libcxx >=17 + - libcxx >=18 - libsodium >=1.0.20,<1.0.21.0a0 license: MPL-2.0 license_family: MOZILLA - size: 280870 - timestamp: 1728363954972 + size: 292112 + timestamp: 1731585246902 - kind: conda name: zeromq version: 4.3.5 - build: he4ceba3_6 - build_number: 6 - subdir: osx-64 - url: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-he4ceba3_6.conda - sha256: 0e2a6ced111fd99b66b76ec797804ab798ec190a88a2779060f7a8787c343ee0 - md5: 00ec9f2a5e21bbbd22ffbbc12b3df286 + build: hc1bb282_7 + build_number: 7 + subdir: osx-arm64 + url: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-hc1bb282_7.conda + sha256: 9e585569fe2e7d3bea71972cd4b9f06b1a7ab8fa7c5139f92a31cbceecf25a8a + md5: f7e6b65943cb73bce0143737fded08f1 depends: - - __osx >=10.13 + - __osx >=11.0 - krb5 >=1.21.3,<1.22.0a0 - - libcxx >=17 + - libcxx >=18 - libsodium >=1.0.20,<1.0.21.0a0 license: MPL-2.0 license_family: MOZILLA - size: 290634 - timestamp: 1728364170966 + size: 281565 + timestamp: 1731585108039 - kind: conda name: zipp version: 3.21.0 diff --git a/pixi.toml b/pixi.toml index 1350c02f5..ca4af5758 100644 --- a/pixi.toml +++ b/pixi.toml @@ -20,7 +20,7 @@ libboost-python-devel = ">=1.80.0" eigen = ">=3.4.0" python = ">=3.9.0" eigenpy = ">=3.8.0,!=3.10.0" -proxsuite-nlp = ">=0.8.0" +proxsuite-nlp = ">=0.10.0" fmt = ">=10.0.0" benchmark = ">=1.8.0" pytest = ">=8.3.0" diff --git a/src/core/history-callback.cpp b/src/core/history-callback.cpp index ddccaccb0..301ed98b2 100644 --- a/src/core/history-callback.cpp +++ b/src/core/history-callback.cpp @@ -1,4 +1,4 @@ -#include "aligator/helpers/history-callback.hpp" +#include "aligator/helpers/history-callback.hxx" namespace aligator { diff --git a/tests/python/test_constrained_dynamics.py b/tests/python/test_constrained_dynamics.py index c8ca1e745..e93bb9116 100644 --- a/tests/python/test_constrained_dynamics.py +++ b/tests/python/test_constrained_dynamics.py @@ -258,9 +258,7 @@ def test_constrained_dynamics(): tol = 1e-5 mu_init = 0.01 verbose = aligator.VerboseLevel.VERBOSE - history_cb = aligator.HistoryCallback() solver = aligator.SolverProxDDP(tol, mu_init, verbose=verbose, max_iters=200) - solver.registerCallback("his", history_cb) solver.setup(problem) conv = solver.run(problem, xs_init, us_init) diff --git a/tests/python/test_solver.py b/tests/python/test_solver.py index 32f200d75..d0915b612 100644 --- a/tests/python/test_solver.py +++ b/tests/python/test_solver.py @@ -60,7 +60,14 @@ def test_no_node(): solver.setup(problem) -@pytest.mark.parametrize("strategy", [aligator.SA_FILTER, aligator.SA_LINESEARCH]) +@pytest.mark.parametrize( + "strategy", + [ + aligator.SA_FILTER, + aligator.SA_LINESEARCH_ARMIJO, + aligator.SA_LINESEARCH_NONMONOTONE, + ], +) def test_proxddp_lqr(strategy): nx = 3 nu = 3