Skip to content

Commit

Permalink
Merge pull request #2 from LudovicDeMatteis/main
Browse files Browse the repository at this point in the history
Minor changes during tests
  • Loading branch information
LudovicDeMatteis authored Sep 23, 2024
2 parents fc6b36c + d31dd4d commit 8974695
Show file tree
Hide file tree
Showing 12 changed files with 27 additions and 195 deletions.
4 changes: 0 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -94,8 +94,4 @@ if(BUILD_PYTHON_INTERFACE)

endif(BUILD_PYTHON_INTERFACE)

if(BUILD_TESTING)
add_subdirectory(unittest)
endif(BUILD_TESTING)

install(FILES package.xml DESTINATION share/${PROJECT_NAME})
13 changes: 12 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,18 @@ Installation instuctions are to be added.

## Run examples

## Code detail
## Contents
* ActuationModel and ActuationData - *class for containing usefull information about the robot actuation (essentially which joints are actuated)*
* Actuation utils - *utility functions to manipulate actuated and free joints configuration (e.g. recreate robot configuration from separated actuated and free joint configuration, extract actuated joints configuration from complete state...)*
* Closures - *Functions to determine closed configurations based on open configuration and fixed serial joints*
* Constraints - *Functions to compute contact constraint violation for 6D and 3D contacts*
* Forward Kinematics
* Inverse Dynamics
* Inverse Kinematics
* Freeze Joints - *Fixes some joints and recreate the Acutation and Constraints models*
* Jacobian - *Computes closed-loop jacobians*
* Mounting - *Computes a mounted condiguration based on the contact constraints (internal and with the environment)
* Projection - *Projects configuration to the closest closed-loop configuration*

## :copyright: Credits

Expand Down
4 changes: 2 additions & 2 deletions pyproject.toml
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,10 @@ build-backend = "setuptools.build_meta"
name = "toolbox-parallel-robots"
version = "0.0.1"
dependencies = [
"pin",
"pin"
]

[tool.setuptools]
packages = [
"toolbox_parallel_robots",
"toolbox_parallel_robots"
]
10 changes: 5 additions & 5 deletions toolbox_parallel_robots/__init__.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
# ruff: noqa: F401
from .actuation import mergeq, mergev, qfree, qmot, vfree, vmot
from .actuation_data import ActuationData
from .actuation_model import ActuationModel
from .actuation_data import ActuationData
from .actuation import qfree, qmot, vfree, vmot, mergeq, mergev
from .closures import partialLoopClosure, partialLoopClosureFrames
from .constraints import (
constraintResidual,
Expand All @@ -19,14 +19,14 @@
from .inverse_kinematics import (
closedLoopInverseKinematics,
closedLoopInverseKinematicsCasadi,
closedLoopInverseKinematicsProximal,
closedLoopInverseKinematicsScipy,
closedLoopInverseKinematicsProximal,
)
from .jacobian import (
separateConstraintJacobian,
computeClosedLoopFrameJacobian,
computeDerivative_dq_dqmot,
inverseConstraintKinematicsSpeed,
separateConstraintJacobian,
)
from .mounting import (
closedLoopMount,
Expand All @@ -35,8 +35,8 @@
closedLoopMountScipy,
)
from .projections import (
accelerationProjection,
configurationProjection,
configurationProjectionProximal,
velocityProjection,
accelerationProjection,
)
2 changes: 1 addition & 1 deletion toolbox_parallel_robots/freeze_joints.py
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ def freezeJoints(
reduced_constraint_models = [
pin.RigidConstraintModel(
cm.type,
model,
reduced_model,
cm.joint1_id,
cm.joint1_placement,
cm.joint2_id, # To the world
Expand Down
Empty file.
28 changes: 6 additions & 22 deletions toolbox_parallel_robots/sliders/foo.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,13 +6,11 @@
"""

import tkinter as tk

import meshcat
import tkinter as tk
import pinocchio as pin

from sliders.tk_robot_sliders import SlidersFrame
from sliders.tk_sliders_manager import SlidersManager
from toolbox_parallel_robots.tk_robot_sliders import SlidersFrame
from toolbox_parallel_robots.tk_sliders_manager import SlidersManager


# * Interface to activate or deactivate constraints on the robot
Expand Down Expand Up @@ -43,21 +41,6 @@ def createSlidersInterface(
if q0 is None:
q0 = pin.neutral(model)

# # * Adding constraints
# addXYZAxisToConstraints(model, visual_model, constraint_models, scale=scale)

# # * Add frames to all joints
# addXYZAxisToJoints(model, visual_model, scale=scale)

# * Create data
# data = model.createData()
# constraint_datas = [cm.createData() for cm in constraint_models]
# * Set a scale factor to handle too small and too big robots
# scale = 1

# replaceGeomByXYZAxis(visual_model, viz, scale=scale)
# viz.display(q0)

# * Create the interface
root = tk.Tk()
root.bind("<Escape>", lambda ev: root.destroy())
Expand Down Expand Up @@ -88,10 +71,11 @@ def createSlidersInterface(
# constraint_models = []
# mot_ids_q = [model.getJointId(joint_name) for joint_name in ["FL_HAA", "FL_HFE", "FL_KFE", "FR_HAA", "FR_HFE", "FR_KFE", "HL_HAA", "HL_HFE", "HL_KFE", "HR_HAA", "HR_HFE", "HR_KFE"]]
# * Create the visualizer
import meshcat
import pinocchio as pin
from pinocchio.visualize import MeshcatVisualizer
import meshcat

viz = pin.visualize.MeshcatVisualizer(model, collision_model, visual_model)
viz = MeshcatVisualizer(model, collision_model, visual_model)
viz.viewer = meshcat.Visualizer(zmq_url="tcp://127.0.0.1:6000")
viz.clean()
viz.loadViewerModel(rootNodeName="universe")
Expand Down
4 changes: 1 addition & 3 deletions toolbox_parallel_robots/sliders/util_frames.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
import hppfcl
import pinocchio as pin
import hppfcl


def addXYZAxisToFrames(rm, vm, basename="XYZ", scale=1, world=False):
Expand Down Expand Up @@ -83,8 +83,6 @@ def replaceGeomByXYZAxis(vm, viz, prefix="XYZ_", visible="OFF", scale=1):
print(g.name)
# gname = viz.getViewerNodeName(g, pin.VISUAL)
viz.delete(g, pin.VISUAL)
# gv.addXYZaxis(gname, [1., 1, 1., 1.], .01*scale, .2*scale)
# gv.setVisibility(gname, visible)


def freeze(robot, indexToLock, referenceConfigurationName=None, rebuildData=True):
Expand Down
5 changes: 0 additions & 5 deletions unittest/CMakeLists.txt

This file was deleted.

63 changes: 0 additions & 63 deletions unittest/test_inverseKinematics.py

This file was deleted.

41 changes: 0 additions & 41 deletions unittest/test_jacobian.py

This file was deleted.

48 changes: 0 additions & 48 deletions unittest/test_mounting.py

This file was deleted.

0 comments on commit 8974695

Please sign in to comment.