diff --git a/.devcontainer/Dockerfile b/.devcontainer/Dockerfile index 0b3ac48..829e822 100644 --- a/.devcontainer/Dockerfile +++ b/.devcontainer/Dockerfile @@ -1,6 +1,8 @@ FROM ros:humble ENV DEBIAN_FRONTEND noninteractive -SHELL ["/bin/bash", "-c"] +ARG CONDA_VER=latest +ARG OS_TYPE=x86_64 + RUN apt-get update && apt-get install -y -qq --no-install-recommends \ libglvnd-dev \ libgl1-mesa-dev \ @@ -23,10 +25,22 @@ RUN apt-get update && apt-get install -y -qq --no-install-recommends \ build-essential \ cmake \ git \ + wget \ && rm -rf /var/lib/apt/lists/* RUN curl -s https://packagecloud.io/install/repositories/github/git-lfs/script.deb.sh | bash RUN apt-get install git-lfs +# Install Miniconda +RUN wget https://github.com/conda-forge/miniforge/releases/${CONDA_VER}/download/Miniforge3-Linux-${OS_TYPE}.sh -O ~/miniconda.sh \ + && /bin/bash ~/miniconda.sh -b -p /opt/conda \ + && rm ~/miniconda.sh \ + && ln -s /opt/conda/etc/profile.d/conda.sh /etc/profile.d/conda.sh \ + && echo ". /opt/conda/etc/profile.d/conda.sh" >> ~/.bashrc \ + && echo "conda activate base" >> ~/.bashrc + +ENV PATH /opt/conda/bin:$PATH +SHELL ["conda", "run", "-n", "base", "/bin/bash", "-c"] +ENV CONDA_PREFIX /opt/conda # Cheange the ROS2 RMW to CycloneDDS as instructed by Unitree RUN cd / && git clone https://github.com/unitreerobotics/unitree_ros2 && cd /unitree_ros2/cyclonedds_ws/src && \ @@ -34,16 +48,15 @@ git clone https://github.com/ros2/rmw_cyclonedds -b humble && git clone https:// cd .. && colcon build --packages-select cyclonedds && source /opt/ros/humble/setup.bash && colcon build # Install Python dependencies -RUN pip3 install scipy ipykernel warp-lang -RUN pip3 install torch torchvision torchaudio --index-url https://download.pytorch.org/whl/cu118 -RUN pip3 install matplotlib opencv-python proxsuite -RUN pip3 install isort black -RUN pip3 install warp-lang scikit-learn casadi mujoco pin +RUN pip install torch torchvision torchaudio --index-url https://download.pytorch.org/whl/cu118 +RUN pip install matplotlib opencv-python proxsuite scipy isort black +RUN pip install warp-lang scikit-learn casadi -RUN pip install jupyter ipykernel -RUN pip install cyclonedds pygame -RUN pip install pynput pygame -RUN pip install onnx onnxruntime +RUN pip install cyclonedds pygame pynput onnx onnxruntime jupyter ipykernel meshcat mujoco +RUN conda install -y -c conda-forge \ + pinocchio \ + crocoddyl \ + mim-solvers # Set environmental variables required for using ROS RUN echo 'source /opt/ros/humble/setup.bash' >> ~/.bashrc diff --git a/Go2Py/assets/urdf/go2_reordered.urdf b/Go2Py/assets/urdf/go2_reordered.urdf new file mode 100644 index 0000000..af4e24b --- /dev/null +++ b/Go2Py/assets/urdf/go2_reordered.urdf @@ -0,0 +1,683 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/09-crododdyl.ipynb b/examples/09-crododdyl.ipynb new file mode 100644 index 0000000..7cdc27f --- /dev/null +++ b/examples/09-crododdyl.ipynb @@ -0,0 +1,372 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 65, + "metadata": {}, + "outputs": [], + "source": [ + "import pinocchio as pin\n", + "import crocoddyl\n", + "import pinocchio\n", + "import numpy as np\n", + "urdf_root_path = '/home/Go2py/Go2Py/assets'\n", + "urdf_path = '/home/Go2py/Go2Py/assets/urdf/go2_reordered.urdf'\n", + "robot = pin.RobotWrapper.BuildFromURDF(\n", + "urdf_path, urdf_root_path, pin.JointModelFreeFlyer())" + ] + }, + { + "cell_type": "code", + "execution_count": 66, + "metadata": {}, + "outputs": [], + "source": [ + "import sys\n", + "import mim_solvers\n", + "pinRef = pin.LOCAL_WORLD_ALIGNED\n", + "FRICTION_CSTR = True\n", + "MU = 0.8 # friction coefficient" + ] + }, + { + "cell_type": "code", + "execution_count": 67, + "metadata": {}, + "outputs": [], + "source": [ + "ee_frame_names = ['FL_foot', 'FR_foot', 'RL_foot', 'RR_foot']\n", + "rmodel = robot.model\n", + "rdata = robot.data\n", + "# # set contact frame_names and_indices\n", + "lfFootId = rmodel.getFrameId(ee_frame_names[0])\n", + "rfFootId = rmodel.getFrameId(ee_frame_names[1])\n", + "lhFootId = rmodel.getFrameId(ee_frame_names[2])\n", + "rhFootId = rmodel.getFrameId(ee_frame_names[3])" + ] + }, + { + "cell_type": "code", + "execution_count": 68, + "metadata": {}, + "outputs": [], + "source": [ + "q0 = np.array([0.0, 0.0, 0.35, 0.0, 0.0, 0.0, 1.0] \n", + " +4*[0.0, 0.77832842, -1.56065452]\n", + " )\n", + "x0 = np.concatenate([q0, np.zeros(rmodel.nv)])" + ] + }, + { + "cell_type": "code", + "execution_count": 69, + "metadata": {}, + "outputs": [], + "source": [ + "pinocchio.forwardKinematics(rmodel, rdata, q0)\n", + "pinocchio.updateFramePlacements(rmodel, rdata)\n", + "rfFootPos0 = rdata.oMf[rfFootId].translation\n", + "rhFootPos0 = rdata.oMf[rhFootId].translation\n", + "lfFootPos0 = rdata.oMf[lfFootId].translation\n", + "lhFootPos0 = rdata.oMf[lhFootId].translation " + ] + }, + { + "cell_type": "code", + "execution_count": 70, + "metadata": {}, + "outputs": [], + "source": [ + "comRef = (rfFootPos0 + rhFootPos0 + lfFootPos0 + lhFootPos0) / 4\n", + "comRef[2] = pinocchio.centerOfMass(rmodel, rdata, q0)[2].item() " + ] + }, + { + "cell_type": "code", + "execution_count": 71, + "metadata": {}, + "outputs": [], + "source": [ + "supportFeetIds = [lfFootId, rfFootId, lhFootId, rhFootId]\n", + "supportFeePos = [lfFootPos0, rfFootPos0, lhFootPos0, rhFootPos0]" + ] + }, + { + "cell_type": "code", + "execution_count": 72, + "metadata": {}, + "outputs": [], + "source": [ + "state = crocoddyl.StateMultibody(rmodel)\n", + "actuation = crocoddyl.ActuationModelFloatingBase(state)\n", + "nu = actuation.nu" + ] + }, + { + "cell_type": "code", + "execution_count": 73, + "metadata": {}, + "outputs": [], + "source": [ + "comDes = []\n", + "\n", + "N_ocp = 250 #100\n", + "dt = 0.02\n", + "T = N_ocp * dt\n", + "radius = 0.065\n", + "for t in range(N_ocp+1):\n", + " comDes_t = comRef.copy()\n", + " w = (2 * np.pi) * 0.2 # / T\n", + " comDes_t[0] += radius * np.sin(w * t * dt) \n", + " comDes_t[1] += radius * (np.cos(w * t * dt) - 1)\n", + " comDes += [comDes_t]" + ] + }, + { + "cell_type": "code", + "execution_count": 74, + "metadata": {}, + "outputs": [], + "source": [ + "import friction_utils\n", + "running_models = []\n", + "constraintModels = []\n", + "\n", + "for t in range(N_ocp+1):\n", + " contactModel = crocoddyl.ContactModelMultiple(state, nu)\n", + " costModel = crocoddyl.CostModelSum(state, nu)\n", + "\n", + " # Add contact\n", + " for frame_idx in supportFeetIds:\n", + " support_contact = crocoddyl.ContactModel3D(state, frame_idx, np.array([0., 0., 0.]), pinRef, nu, np.array([0., 0.]))\n", + " # print(\"contact name = \", rmodel.frames[frame_idx].name + \"_contact\")\n", + " contactModel.addContact(rmodel.frames[frame_idx].name + \"_contact\", support_contact) \n", + "\n", + " # Add state/control reg costs\n", + "\n", + " state_reg_weight, control_reg_weight = 1e-1, 1e-3\n", + "\n", + " freeFlyerQWeight = [0.]*3 + [500.]*3\n", + " freeFlyerVWeight = [10.]*6\n", + " legsQWeight = [0.01]*(rmodel.nv - 6)\n", + " legsWWeights = [1.]*(rmodel.nv - 6)\n", + " stateWeights = np.array(freeFlyerQWeight + legsQWeight + freeFlyerVWeight + legsWWeights) \n", + "\n", + "\n", + " stateResidual = crocoddyl.ResidualModelState(state, x0, nu)\n", + " stateActivation = crocoddyl.ActivationModelWeightedQuad(stateWeights**2)\n", + " stateReg = crocoddyl.CostModelResidual(state, stateActivation, stateResidual)\n", + "\n", + " if t == N_ocp:\n", + " costModel.addCost(\"stateReg\", stateReg, state_reg_weight*dt)\n", + " else:\n", + " costModel.addCost(\"stateReg\", stateReg, state_reg_weight)\n", + "\n", + " if t != N_ocp:\n", + " ctrlResidual = crocoddyl.ResidualModelControl(state, nu)\n", + " ctrlReg = crocoddyl.CostModelResidual(state, ctrlResidual)\n", + " costModel.addCost(\"ctrlReg\", ctrlReg, control_reg_weight) \n", + "\n", + "\n", + " # Add COM task\n", + " com_residual = crocoddyl.ResidualModelCoMPosition(state, comDes[t], nu)\n", + " com_activation = crocoddyl.ActivationModelWeightedQuad(np.array([1., 1., 1.]))\n", + " com_track = crocoddyl.CostModelResidual(state, com_activation, com_residual)\n", + " if t == N_ocp:\n", + " costModel.addCost(\"comTrack\", com_track, 1e5)\n", + " else:\n", + " costModel.addCost(\"comTrack\", com_track, 1e5)\n", + "\n", + " constraintModelManager = crocoddyl.ConstraintModelManager(state, actuation.nu)\n", + " if(FRICTION_CSTR):\n", + " if(t != N_ocp):\n", + " for frame_idx in supportFeetIds:\n", + " name = rmodel.frames[frame_idx].name + \"_contact\"\n", + " residualFriction = friction_utils.ResidualFrictionCone(state, name, MU, actuation.nu)\n", + " constraintFriction = crocoddyl.ConstraintModelResidual(state, residualFriction, np.array([0.]), np.array([np.inf]))\n", + " constraintModelManager.addConstraint(name + \"friction\", constraintFriction)\n", + "\n", + " dmodel = crocoddyl.DifferentialActionModelContactFwdDynamics(state, actuation, contactModel, costModel, constraintModelManager, 0., True)\n", + " model = crocoddyl.IntegratedActionModelEuler(dmodel, dt)\n", + "\n", + " running_models += [model]\n" + ] + }, + { + "cell_type": "code", + "execution_count": 75, + "metadata": {}, + "outputs": [], + "source": [ + "# Create shooting problem\n", + "ocp = crocoddyl.ShootingProblem(x0, running_models[:-1], running_models[-1])\n", + "\n", + "solver = mim_solvers.SolverCSQP(ocp)\n", + "solver.max_qp_iters = 1000\n", + "max_iter = 500\n", + "solver.with_callbacks = True\n", + "solver.use_filter_line_search = False\n", + "solver.termination_tolerance = 1e-4\n", + "solver.eps_abs = 1e-6\n", + "solver.eps_rel = 1e-6" + ] + }, + { + "cell_type": "code", + "execution_count": 76, + "metadata": {}, + "outputs": [ + { + "data": { + "text/plain": [ + "True" + ] + }, + "execution_count": 76, + "metadata": {}, + "output_type": "execute_result" + } + ], + "source": [ + "xs = [x0]*(solver.problem.T + 1)\n", + "us = solver.problem.quasiStatic([x0]*solver.problem.T) \n", + "solver.solve(xs, us, max_iter) " + ] + }, + { + "cell_type": "code", + "execution_count": 93, + "metadata": {}, + "outputs": [], + "source": [ + "nq, nv, N = rmodel.nq, rmodel.nv, len(xs) \n", + "jointPos_sol = []\n", + "jointVel_sol = []\n", + "jointAcc_sol = []\n", + "jointTorques_sol = []\n", + "centroidal_sol = []\n", + "\n", + "x = []\n", + "for time_idx in range (N):\n", + " q, v = xs[time_idx][:nq], xs[time_idx][nq:]\n", + " pin.framesForwardKinematics(rmodel, rdata, q)\n", + " pin.computeCentroidalMomentum(rmodel, rdata, q, v)\n", + " centroidal_sol += [\n", + " np.concatenate(\n", + " [pin.centerOfMass(rmodel, rdata, q, v), np.array(rdata.hg.linear), np.array(rdata.hg.angular)]\n", + " )\n", + " ]\n", + " jointPos_sol += [q]\n", + " jointVel_sol += [v]\n", + " x += [xs[time_idx]]\n", + " if time_idx < N-1:\n", + " jointAcc_sol += [solver.problem.runningDatas[time_idx].xnext[nq::]] \n", + " jointTorques_sol += [us[time_idx]]\n", + "\n", + "\n", + "\n", + "\n", + "sol = {'x':x, 'centroidal':centroidal_sol, 'jointPos':jointPos_sol, \n", + " 'jointVel':jointVel_sol, 'jointAcc':jointAcc_sol, \n", + " 'jointTorques':jointTorques_sol} \n", + "\n", + "for frame_idx in supportFeetIds:\n", + " # print('extract foot id ', frame_idx, \"_name = \", rmodel.frames[frame_idx].name)\n", + " ct_frame_name = rmodel.frames[frame_idx].name + \"_contact\"\n", + " datas = [solver.problem.runningDatas[i].differential.multibody.contacts.contacts[ct_frame_name] for i in range(N-1)]\n", + " ee_forces = [datas[k].f.vector for k in range(N-1)] \n", + " sol[ct_frame_name] = [ee_forces[i] for i in range(N-1)] \n", + " " + ] + }, + { + "cell_type": "code", + "execution_count": 97, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "import matplotlib.pyplot as plt\n", + "constrained_sol = sol\n", + "time_lin = np.linspace(0, T, solver.problem.T)\n", + "fig, axs = plt.subplots(4, 3, constrained_layout=True)\n", + "for i, frame_idx in enumerate(supportFeetIds):\n", + " ct_frame_name = rmodel.frames[frame_idx].name + \"_contact\"\n", + " forces = np.array(constrained_sol[ct_frame_name])\n", + " axs[i, 0].plot(time_lin, forces[:, 0], label=\"Fx\")\n", + " axs[i, 1].plot(time_lin, forces[:, 1], label=\"Fy\")\n", + " axs[i, 2].plot(time_lin, forces[:, 2], label=\"Fz\")\n", + " # Add friction cone constraints \n", + " Fz_lb = (1./MU)*np.sqrt(forces[:, 0]**2 + forces[:, 1]**2)\n", + " # Fz_ub = np.zeros(time_lin.shape)\n", + " # axs[i, 2].plot(time_lin, Fz_ub, 'k-.', label='ub')\n", + " axs[i, 2].plot(time_lin, Fz_lb, 'k-.', label='lb')\n", + " axs[i, 0].grid()\n", + " axs[i, 1].grid()\n", + " axs[i, 2].grid()\n", + " axs[i, 0].set_ylabel(ct_frame_name)\n", + "axs[0, 0].legend()\n", + "axs[0, 1].legend()\n", + "axs[0, 2].legend()\n", + "\n", + "axs[3, 0].set_xlabel(r\"$F_x$\")\n", + "axs[3, 1].set_xlabel(r\"$F_y$\")\n", + "axs[3, 2].set_xlabel(r\"$F_z$\")\n", + "fig.suptitle('Force', fontsize=16)\n", + "\n", + "\n", + "comDes = np.array(comDes)\n", + "centroidal_sol = np.array(constrained_sol['centroidal'])\n", + "plt.figure()\n", + "plt.plot(comDes[:, 0], comDes[:, 1], \"--\", label=\"reference\")\n", + "plt.plot(centroidal_sol[:, 0], centroidal_sol[:, 1], label=\"solution\")\n", + "plt.legend()\n", + "plt.xlabel(\"x\")\n", + "plt.ylabel(\"y\")\n", + "plt.title(\"COM trajectory\")\n", + "plt.show()" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "base", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.7" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/examples/friction_utils.py b/examples/friction_utils.py new file mode 100644 index 0000000..fdf5b7b --- /dev/null +++ b/examples/friction_utils.py @@ -0,0 +1,256 @@ +import pinocchio as pin +import numpy as np +try: + import meshcat + import meshcat.geometry as g + import meshcat.transformations as tf +except: + print("You need to install meshcat.") + +import crocoddyl + + + +class ResidualForce3D(crocoddyl.ResidualModelAbstract): + def __init__(self, state, contact_name, nu): + crocoddyl.ResidualModelAbstract.__init__(self, state, 3, nu, True, True, True) + self.contact_name = contact_name + + def calc(self, data, x, u=None): + data.r = data.shared.contacts.contacts[self.contact_name].f.vector[:3] + + def calcDiff(self, data, x, u=None): + data.Rx = data.shared.contacts.contacts[self.contact_name].df_dx[:3] + data.Ru = data.shared.contacts.contacts[self.contact_name].df_du[:3] + + +class ResidualFrictionCone(crocoddyl.ResidualModelAbstract): + def __init__(self, state, contact_name, mu, nu): + crocoddyl.ResidualModelAbstract.__init__(self, state, 1, nu, True, True, True) + self.mu = mu + self.contact_name = contact_name + + self.dcone_df = np.zeros((1, 3)) + self.df_dx = np.zeros((3, self.state.ndx)) + self.df_du = np.zeros((3, self.nu)) + + def calc(self, data, x, u=None): + F = data.shared.contacts.contacts[self.contact_name].f.vector[:3] + data.r[0] = np.array([self.mu * F[2] - np.sqrt(F[0]**2 + F[1]**2)]) + + def calcDiff(self, data, x, u=None): + F = data.shared.contacts.contacts[self.contact_name].f.vector[:3] + + self.dcone_df[0, 0] = -F[0] / np.sqrt(F[0]**2 + F[1]**2) + self.dcone_df[0, 1] = -F[1] / np.sqrt(F[0]**2 + F[1]**2) + self.dcone_df[0, 2] = self.mu + + + self.df_dx = data.shared.contacts.contacts[self.contact_name].df_dx[:3] + self.df_du = data.shared.contacts.contacts[self.contact_name].df_du[:3] + + data.Rx = self.dcone_df @ self.df_dx + data.Ru = self.dcone_df @ self.df_du + + +def meshcat_material(r, g, b, a): + material = meshcat.geometry.MeshPhongMaterial() + material.color = int(r * 255) * 256 ** 2 + int(g * 255) * 256 + int(b * 255) + material.opacity = a + material.linewidth = 5.0 + return material + +def addViewerBox(viz, name, sizex, sizey, sizez, rgba): + if isinstance(viz, pin.visualize.MeshcatVisualizer): + viz.viewer[name].set_object(meshcat.geometry.Box([sizex, sizey, sizez]), + meshcat_material(*rgba)) + + +def addLineSegment(viz, name, vertices, rgba): + if isinstance(viz, pin.visualize.MeshcatVisualizer): + viz.viewer[name].set_object(meshcat.geometry.LineSegments( + meshcat.geometry.PointsGeometry(np.array(vertices)), + meshcat_material(*rgba) + )) + +def addPoint(viz, name, vertices, rgba): + if isinstance(viz, pin.visualize.MeshcatVisualizer): + viz.viewer[name].set_object(meshcat.geometry.Points( + meshcat.geometry.PointsGeometry(np.array(vertices)), + meshcat_material(*rgba) + )) + +def meshcat_transform(x, y, z, q, u, a, t): + return np.array(pin.XYZQUATToSE3([x, y, z, q, u, a, t])) + +def applyViewerConfiguration(viz, name, xyzquat): + if isinstance(viz, pin.visualize.MeshcatVisualizer): + viz.viewer[name].set_transform(meshcat_transform(*xyzquat)) + +def get_solution_trajectories(solver, rmodel, rdata, supportFeetIds): + xs, us = solver.xs, solver.us + nq, nv, N = rmodel.nq, rmodel.nv, len(xs) + jointPos_sol = [] + jointVel_sol = [] + jointAcc_sol = [] + jointTorques_sol = [] + centroidal_sol = [] + + x = [] + for time_idx in range (N): + q, v = xs[time_idx][:nq], xs[time_idx][nq:] + pin.framesForwardKinematics(rmodel, rdata, q) + pin.computeCentroidalMomentum(rmodel, rdata, q, v) + centroidal_sol += [ + np.concatenate( + [pin.centerOfMass(rmodel, rdata, q, v), np.array(rdata.hg)] + ) + ] + jointPos_sol += [q] + jointVel_sol += [v] + x += [xs[time_idx]] + if time_idx < N-1: + jointAcc_sol += [solver.problem.runningDatas[time_idx].xnext[nq::]] + jointTorques_sol += [us[time_idx]] + + + + + sol = {'x':x, 'centroidal':centroidal_sol, 'jointPos':jointPos_sol, + 'jointVel':jointVel_sol, 'jointAcc':jointAcc_sol, + 'jointTorques':jointTorques_sol} + + + for frame_idx in supportFeetIds: + # print('extract foot id ', frame_idx, "_name = ", rmodel.frames[frame_idx].name) + ct_frame_name = rmodel.frames[frame_idx].name + "_contact" + datas = [solver.problem.runningDatas[i].differential.multibody.contacts.contacts[ct_frame_name] for i in range(N-1)] + ee_forces = [datas[k].f.vector for k in range(N-1)] + sol[ct_frame_name] = [ee_forces[i] for i in range(N-1)] + + return sol + + + + +class Arrow(object): + def __init__(self, meshcat_vis, name, + location=[0,0,0], + vector=[0,0,1], + length_scale=1, + color=0xff0000): + + self.vis = meshcat_vis[name] + self.cone = self.vis["cone"] + self.line = self.vis["line"] + self.material = g.MeshBasicMaterial(color=color, reflectivity=0.5) + + self.location, self.length_scale = location, length_scale + self.anchor_as_vector(location, vector) + + def _update(self): + # pass + translation = tf.translation_matrix(self.location) + rotation = self.orientation + offset = tf.translation_matrix([0, self.length/2, 0]) + self.pose = translation @ rotation @ offset + self.vis.set_transform(self.pose) + + def set_length(self, length, update=True): + self.length = length * self.length_scale + cone_scale = self.length/0.08 + self.line.set_object(g.Cylinder(height=self.length, radius=0.005), self.material) + self.cone.set_object(g.Cylinder(height=0.015, + radius=0.01, + radiusTop=0., + radiusBottom=0.01), + self.material) + self.cone.set_transform(tf.translation_matrix([0.,cone_scale*0.04,0])) + if update: + self._update() + + def set_direction(self, direction, update=True): + orientation = np.eye(4) + orientation[:3, 0] = np.cross([1,0,0], direction) + orientation[:3, 1] = direction + orientation[:3, 2] = np.cross(orientation[:3, 0], orientation[:3, 1]) + self.orientation = orientation + if update: + self._update() + + def set_location(self, location, update=True): + self.location = location + if update: + self._update() + + def anchor_as_vector(self, location, vector, update=True): + self.set_direction(np.array(vector)/np.linalg.norm(vector), False) + self.set_location(location, False) + self.set_length(np.linalg.norm(vector), False) + if update: + self._update() + + def delete(self): + self.vis.delete() + + + + +class Cone(object): + def __init__(self, meshcat_vis, name, + location=[0,0,0], mu=1, + vector=[0,0,1], + length_scale=0.06): + + self.vis = meshcat_vis[name] + self.cone = self.vis["cone"] + self.material = g.MeshBasicMaterial(color=0xffffff, opacity = 0.5, reflectivity=0.5) + + + self.mu = mu * length_scale + self.location, self.length_scale = location, length_scale + self.anchor_as_vector(location, vector) + + def _update(self): + # pass + translation = tf.translation_matrix(self.location) + rotation = self.orientation + offset = tf.translation_matrix([0, self.length/2, 0]) + self.pose = translation @ rotation @ offset + self.vis.set_transform(self.pose) + + def set_length(self, length, update=True): + self.length = length * self.length_scale + cone_scale = self.length + self.cone.set_object(g.Cylinder(height=cone_scale, + radius=self.mu, + radiusTop=self.mu, + radiusBottom=0), + self.material) + # self.cone.set_transform(tf.translation_matrix([0.,cone_scale*0.04,0])) + if update: + self._update() + + def set_direction(self, direction, update=True): + orientation = np.eye(4) + orientation[:3, 0] = np.cross([1,0,0], direction) + orientation[:3, 1] = direction + orientation[:3, 2] = np.cross(orientation[:3, 0], orientation[:3, 1]) + self.orientation = orientation + if update: + self._update() + + def set_location(self, location, update=True): + self.location = location + if update: + self._update() + + def anchor_as_vector(self, location, vector, update=True): + self.set_direction(np.array(vector)/np.linalg.norm(vector), False) + self.set_location(location, False) + self.set_length(np.linalg.norm(vector), False) + if update: + self._update() + + def delete(self): + self.vis.delete() \ No newline at end of file