Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add a first shell of the agimus_controller API #97

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
33 commits
Select commit Hold shift + click to select a range
7a629d2
Add a first shell of the agimus_controller API
MaximilienNaveau Dec 2, 2024
4397255
[pre-commit.ci] auto fixes from pre-commit.com hooks
pre-commit-ci[bot] Dec 2, 2024
7fe2969
add a robot model parser
MaximilienNaveau Dec 2, 2024
6b643cf
[pre-commit.ci] auto fixes from pre-commit.com hooks
pre-commit-ci[bot] Dec 2, 2024
6c654f7
move the timer inside the debug data
MaximilienNaveau Dec 3, 2024
1490b3e
[pre-commit.ci] auto fixes from pre-commit.com hooks
pre-commit-ci[bot] Dec 3, 2024
8e55069
remove unused internal variable
MaximilienNaveau Dec 3, 2024
8853e34
[pre-commit.ci] auto fixes from pre-commit.com hooks
pre-commit-ci[bot] Dec 3, 2024
c8f2ab8
fix relative import using absolute imports
MaximilienNaveau Dec 3, 2024
370bcb9
fix some comments
MaximilienNaveau Dec 3, 2024
a21f0fb
Update the robot_model_factory interface
MaximilienNaveau Dec 3, 2024
2d91d3f
fix imports
MaximilienNaveau Dec 3, 2024
2b02a53
Take a second shot at the Main API.
MaximilienNaveau Dec 5, 2024
870a8f5
Remove the ROS node API from this refactor for now
MaximilienNaveau Dec 5, 2024
d24d4fe
update the warmstart api
MaximilienNaveau Dec 5, 2024
ebdd0a6
Change the factories to functions
MaximilienNaveau Dec 6, 2024
10c0b65
Update the Debug data content for a more stuctured approach
MaximilienNaveau Dec 6, 2024
66e6855
move the clear_path to the buffer and rename the buffer in mpc
MaximilienNaveau Dec 6, 2024
781becc
Clear the model classes
MaximilienNaveau Dec 6, 2024
b0d6246
add deprecated folder in gitignore
MaximilienNaveau Dec 6, 2024
505c90a
Remove the obstacle parser as not part of the main api
MaximilienNaveau Dec 6, 2024
ac00b8f
Move the factories in a subfolder
MaximilienNaveau Dec 6, 2024
14c69f0
Update the duration measurement to be in nanosecond
MaximilienNaveau Dec 6, 2024
b851f4b
revert changes
MaximilienNaveau Dec 6, 2024
c5661be
Use extend from deque
MaximilienNaveau Dec 6, 2024
c4ef2dc
Clean the code from review
MaximilienNaveau Dec 6, 2024
0967dc9
Clean the data structure usage.
MaximilienNaveau Dec 6, 2024
a6a47c2
Return None in ocp functions expected throw in case of failure
MaximilienNaveau Dec 6, 2024
1126d21
fix the init value for the timers.
MaximilienNaveau Dec 9, 2024
748425d
Update the api of the buffer on the get horizon. Organize the includes
MaximilienNaveau Dec 9, 2024
b109535
update Setup function fro more flexibility on the buffer API
MaximilienNaveau Dec 9, 2024
637222c
Add update_previous_solution into the warm_start
MaximilienNaveau Dec 9, 2024
462e498
Fix naming
MaximilienNaveau Dec 9, 2024
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions deprecated/.gitignore → .gitignore
Original file line number Diff line number Diff line change
@@ -1,2 +1,3 @@
*__pycache__*
*.npy
deprecated
Empty file.
Empty file.
24 changes: 24 additions & 0 deletions agimus_controller/agimus_controller/factory/ocp.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
from agimus_controller.ocp_base import OCPBase


def _create_ocp_hpp_crocco() -> OCPBase:
pass


def _create_ocp_collision_avoidance() -> OCPBase:
pass


def _create_ocp_single_ee_ref() -> OCPBase:
pass


def create_ocp(name: str) -> OCPBase:
if name == "hpp_crocco":
return _create_ocp_hpp_crocco()

if name == "collision_avoidance":
return _create_ocp_collision_avoidance()

if name == "single_ee_ref":
return _create_ocp_single_ee_ref()
96 changes: 96 additions & 0 deletions agimus_controller/agimus_controller/factory/robot_model.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,96 @@
from copy import deepcopy
from dataclasses import dataclass
import numpy as np
from pathlib import Path
import pinocchio as pin
from typing import Union


@dataclass
class RobotModelParameters:
q0_name = str()
free_flyer = False
locked_joint_names = []
urdf = Path() | str
srdf = Path() | str
collision_as_capsule = False
self_collision = False


class RobotModelFactory:
"""Parse the robot model, reduce it and filter the collision model."""

"""Complete model of the robot."""
_complete_model = pin.Model()
""" Complete model of the robot with collision meshes. """
_complete_collision_model = pin.GeometryModel()
""" Complete model of the robot with visualization meshes. """
_complete_visual_model = pin.GeometryModel()
""" Reduced model of the robot. """
_rmodel = pin.Model()
""" Reduced model of the robot with visualization meshes. """
_rcmodel = pin.GeometryModel()
""" Reduced model of the robot with collision meshes. """
_rvmodel = pin.GeometryModel()
""" Default configuration q0. """
_q0 = np.array([])
""" Parameters of the model. """
_params = RobotModelParameters()
""" Path to the collisions environment. """
_env = Path()

def load_model(self, param: RobotModelParameters, env: Union[Path, None]) -> None:
self._params = param
self._env = env
self._load_pinocchio_models(param.urdf, param.free_flyer)
self._load_default_configuration(param.srdf, param.q0_name)
self._load_reduced_model(param.locked_joint_names, param.q0_name)
self._update_collision_model(
env, param.collision_as_capsule, param.self_collision, param.srdf
)

def _load_pinocchio_models(self, urdf: Path, free_flyer: bool) -> None:
pass

def _load_default_configuration(self, srdf_path: Path, q0_name: str) -> None:
pass

def _load_reduced_model(self, locked_joint_names, q0_name) -> None:
pass

def _update_collision_model(
self,
env: Union[Path, None],
collision_as_capsule: bool,
self_collision: bool,
srdf: Path,
) -> None:
pass

def create_complete_robot_model(self) -> pin.Model:
return self._complete_model.copy()

def create_complete_collision_model(self) -> pin.GeometryModel:
return self._complete_collision_model.copy()

def create_complete_visual_model(self) -> pin.GeometryModel:
return self._complete_visual_model.copy()

def create_reduced_robot_model(self) -> pin.Model:
return self._rmodel.copy()

def create_reduced_collision_model(self) -> pin.GeometryModel:
return self._rcmodel.copy()

def create_reduced_visual_model(self) -> pin.GeometryModel:
return self._rvmodel.copy()

def create_default_configuration(self) -> np.array:
return self._q0.copy()

def create_model_parameters(self) -> RobotModelParameters:
return deepcopy(self._params)

def print_model(self):
print("full model =\n", self._complete_model)
print("reduced model =\n", self._rmodel)
17 changes: 17 additions & 0 deletions agimus_controller/agimus_controller/factory/warm_start.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
from agimus_controller.warm_start_base import WarmStartBase


def _create_warm_start_from_previous_solution() -> WarmStartBase:
pass


def _create_warm_start_from_diffusion_model() -> WarmStartBase:
pass


def create_warm_start(name: str) -> WarmStartBase:
if name == "from_previous_solution":
return _create_warm_start_from_previous_solution()

if name == "from_diffusion_model":
return _create_warm_start_from_diffusion_model()
68 changes: 68 additions & 0 deletions agimus_controller/agimus_controller/mpc.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
import time
MaximilienNaveau marked this conversation as resolved.
Show resolved Hide resolved

from agimus_controller.mpc_data import OCPResults, MPCDebugData
from agimus_controller.ocp_base import OCPBase
from agimus_controller.trajectory import (
TrajectoryBuffer,
TrajectoryPoint,
WeightedTrajectoryPoint,
)
from agimus_controller.warm_start_base import WarmStartBase


class MPC(object):
def __init__(self) -> None:
self._ocp = None
self._warm_start = None
self._mpc_debug_data: MPCDebugData = None
self._buffer = None

def setup(
self,
ocp: OCPBase,
warm_start: WarmStartBase,
buffer: TrajectoryBuffer = TrajectoryBuffer(),
) -> None:
self._ocp = ocp
self._warm_start = warm_start
self._buffer = buffer

MaximilienNaveau marked this conversation as resolved.
Show resolved Hide resolved
def run(self, initial_state: TrajectoryPoint, current_time_ns: int) -> OCPResults:
assert self._ocp is not None
assert self._warm_start is not None
timer1 = time.perf_counter_ns()
self._buffer.clear_past(current_time_ns)
reference_trajectory = self._extract_horizon_from_buffer()
self._ocp.set_reference_horizon(reference_trajectory)
TheoMF marked this conversation as resolved.
Show resolved Hide resolved
timer2 = time.perf_counter_ns()
x0, x_init, u_init = self._warm_start.generate(
initial_state, reference_trajectory, self._ocp.debug_data.result
)
timer3 = time.perf_counter_ns()
self._ocp.solve(x0, x_init, u_init)
self._warm_start.update_previous_solution(self._ocp.debug_data.result)
timer4 = time.perf_counter_ns()

# Extract the solution.
self._mpc_debug_data = self._ocp.debug_data
self._mpc_debug_data.duration_iteration_ns = timer4 - timer1
self._mpc_debug_data.duration_horizon_update_ns = timer2 - timer1
self._mpc_debug_data.duration_generate_warm_start_ns = timer3 - timer2
self._mpc_debug_data.duration_ocp_solve_ns = timer4 - timer3

return self._ocp.ocp_results

@property
def mpc_debug_data(self) -> MPCDebugData:
return self._mpc_debug_data

def append_trajectory_point(self, trajectory_point: WeightedTrajectoryPoint):
self._buffer.append(trajectory_point)

def append_trajectory_points(
self, trajectory_points: list[WeightedTrajectoryPoint]
):
self._buffer.extend(trajectory_points)

def _extract_horizon_from_buffer(self):
return self._buffer.horizon(self._ocp.horizon_size, self._ocp.dt)
36 changes: 36 additions & 0 deletions agimus_controller/agimus_controller/mpc_data.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
from dataclasses import dataclass
import numpy as np
import numpy.typing as npt

from agimus_controller.trajectory import TrajectoryPoint


@dataclass
class OCPResults:
"""Output data structure of the MPC."""

states: list[npt.NDArray[np.float64]]
ricatti_gains: list[npt.NDArray[np.float64]]
feed_forward_terms: list[npt.NDArray[np.float64]]


@dataclass
class OCPDebugData:
# Solver infos
problem_solved: bool = False

# Debug data
result: list[TrajectoryPoint]
references: list[TrajectoryPoint]
kkt_norms: list[np.float64]
collision_distance_residuals: list[dict[np.float64]]


@dataclass
class MPCDebugData:
ocp: OCPDebugData
# Timers
duration_iteration_ns: int = 0
duration_horizon_update_ns: int = 0
duration_generate_warm_start_ns: int = 0
duration_ocp_solve_ns: int = 0
42 changes: 42 additions & 0 deletions agimus_controller/agimus_controller/ocp_base.py
MaximilienNaveau marked this conversation as resolved.
Show resolved Hide resolved
MaximilienNaveau marked this conversation as resolved.
Show resolved Hide resolved
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
from abc import ABC, abstractmethod
import numpy as np
MaximilienNaveau marked this conversation as resolved.
Show resolved Hide resolved

from agimus_controller.mpc_data import OCPResults, OCPDebugData
from agimus_controller.trajectory import WeightedTrajectoryPoint


class OCPBase(ABC):
def __init__(self) -> None:
pass

@abstractmethod
def set_reference_horizon(
self, reference_trajectory: list[WeightedTrajectoryPoint]
) -> None:
...

@abstractmethod
@property
def horizon_size() -> int:
...

@abstractmethod
@property
def dt() -> int:
...

@abstractmethod
def solve(
self, x0: np.ndarray, x_init: list[np.ndarray], u_init: list[np.ndarray]
MaximilienNaveau marked this conversation as resolved.
Show resolved Hide resolved
) -> None:
...

@abstractmethod
@property
def ocp_results(self) -> OCPResults:
...

@abstractmethod
@property
def debug_data(self) -> OCPDebugData:
...
49 changes: 49 additions & 0 deletions agimus_controller/agimus_controller/trajectory.py
MaximilienNaveau marked this conversation as resolved.
Show resolved Hide resolved
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
from collections import deque
from dataclasses import dataclass
import numpy as np
MaximilienNaveau marked this conversation as resolved.
Show resolved Hide resolved
from pinocchio import SE3, Force


@dataclass
class TrajectoryPoint:
MedericFourmy marked this conversation as resolved.
Show resolved Hide resolved
"""Trajectory point aiming at being a reference for the MPC."""

time_ns: int
robot_configuration: np.ndarray
robot_velocity: np.ndarray
robot_acceleration: np.ndarray
robot_effort: np.ndarray
MaximilienNaveau marked this conversation as resolved.
Show resolved Hide resolved
forces: dict[Force] # Dictionary of pinocchio.Force
end_effector_poses: dict[SE3] # Dictionary of pinocchio.SE3

MaximilienNaveau marked this conversation as resolved.
Show resolved Hide resolved

@dataclass
class TrajectoryPointWeights:
"""Trajectory point weights aiming at being set in the MPC costs."""

w_robot_configuration: np.ndarray
w_robot_velocity: np.ndarray
Comment on lines +24 to +25
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

in crocoddyl there's no cost for only q or qdot so I guess we only have this instead :

Suggested change
w_robot_configuration: np.ndarray
w_robot_velocity: np.ndarray
w_robot_state: np.ndarray

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the weights are consistent with the trajectory point entries. I would say we either

  1. use state instead of configuration and velocity
    or 2) keep them separate and merge in ocp to state

Also, I remember @MaximilienNaveau mentioning that state is not always [config, velocity], so option 1) might be misleading in the future

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

for the second option how would we merge it in ocp to state ? the state will indeed not always be [config, velocity], but maybe it will still needs only one weight, that's something we have to check I guess

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The more information the better. If you have weights that you do not use: so be it.
But I don't believe so. In your case you should have nv+nv weights for x which means you have the same amount of weights than in the message. It might happen that a lot of weights are identical. But again this way you give more flexibility to the user with a small cost.

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The ocp is responsible to recreate the weights matrix. And it knows everything: x, robot_model, costs etc.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

are you talking about the activation weights when creating the residuals ? in this case I agree there are nv+nv weights or maybe something else, but for the cost itself it's always a scalar right ?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Well you can see the quadratic cost like so:
$$
alpha * X^T W X
$$
What the weights inside the message will give you is W as a diagonal matrix.
Should we consider adding the alpha as well?
I would believe that W is enough to weight the cost. If all diagonal members are equal you can actually factorize and get $$ alpha X^T X $$.
Maybe I am mistaken...

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yeah, I agree with you, Max; we can control alpha by controlling W.
And for me, having W_q and W_v and stacking them on the OCP side makes more sense than having W_{state} (since it is consistent with TrajectoryPoint definition)

w_robot_acceleration: np.ndarray
w_robot_effort: np.ndarray
w_forces: dict[np.ndarray]
w_end_effector_poses: dict[np.ndarray]
MaximilienNaveau marked this conversation as resolved.
Show resolved Hide resolved


@dataclass
class WeightedTrajectoryPoint:
"""Trajectory point and it's corresponding weights."""

point: TrajectoryPoint
weight: TrajectoryPointWeights


class TrajectoryBuffer(deque):
"""List of variable size in which the HPP trajectory nodes will be."""

def clear_past(self, current_time_ns):
while self and self[0].point.time_ns < current_time_ns:
self.popleft()

def horizon(self, horizon_size, dt_ocp):
# TBD improve this implementation in case the dt_mpc != dt_ocp
return self._buffer[: self._ocp.horizon_size]
24 changes: 24 additions & 0 deletions agimus_controller/agimus_controller/warm_start_base.py
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Shouldn't warmstart know about the previous solution? I thought we assumed that OCP is stateless and warmstart is responsible for blending old solutions with incomming trajectory?

Maybe function:

    @abstractmethod
    def generate(self, us: list[np.ndarray]) -> None:
        """Stores trajecroty obtained from OCP."""
        pass

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

So isn't that enough for all warm starts?

def generate(
        self,
        reference_trajectory: list[TrajectoryPoint],
        previous_solution: list[TrajectoryPoint],
    ) -> tuple(np.ndarray, np.ndarray):
        """Returns x_init, u_init."""
        ...

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I want to apologise for the confusion. It was supposed to be similarly to what @petrikvladimir suggested, but I messed up the name of the function. I wanted it to be:

    @abstractmethod
    def update_last_solution(self, us: list[np.ndarray], xs: list[np.ndarray]) -> None:
        """Stores trajecroty obtained from OCP."""
        pass

Or something like this.
In reference to #97 (comment)

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Having access to the previous solution makes sense to me. Maybe we can optionally pass xs and us to generate?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I pushed a commit related to this.

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I wasn't sure about the list[np.ndarray] vs list[TrajectoryPoint]

Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
from abc import ABC, abstractmethod
import numpy as np
MaximilienNaveau marked this conversation as resolved.
Show resolved Hide resolved

from agimus_controller.trajectory import TrajectoryPoint


class WarmStartBase(ABC):
def __init__(self) -> None:
super().__init__()
self._previous_solution: list[TrajectoryPoint] = list()

@abstractmethod
def generate(
self,
reference_trajectory: list[TrajectoryPoint],
) -> tuple(np.ndarray, np.ndarray):
MaximilienNaveau marked this conversation as resolved.
Show resolved Hide resolved
"""Returns x_init, u_init."""
...

def update_previous_solution(
self, previous_solution: list[TrajectoryPoint]
) -> None:
"""Stores internally the previous solution of the OCP"""
self._previous_solution = previous_solution
21 changes: 21 additions & 0 deletions agimus_controller/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
from setuptools import find_packages, setup

PACKAGE_NAME = "agimus_controller"
REQUIRES_PYTHON = ">=3.10.0"

setup(
name=PACKAGE_NAME,
version="0.0.0",
packages=find_packages(exclude=["tests"]),
python_requires=REQUIRES_PYTHON,
install_requires=[
"setuptools",
"numpy==1.21.5",
],
MaximilienNaveau marked this conversation as resolved.
Show resolved Hide resolved
zip_safe=True,
maintainer="Guilhem Saurel",
maintainer_email="[email protected]",
description="Implements whole body MPC in python using the Croccodyl framework.",
license="BSD-2",
tests_require=["pytest"],
)
Loading