Skip to content

Commit

Permalink
Initial path types
Browse files Browse the repository at this point in the history
  • Loading branch information
Victorlouisdg committed Feb 1, 2024
1 parent ab757dd commit f3be0d1
Showing 1 changed file with 58 additions and 2 deletions.
60 changes: 58 additions & 2 deletions airo-typing/airo_typing/__init__.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
from dataclasses import dataclass
from typing import Dict, Optional, Tuple, Union
from typing import Callable, Dict, List, Optional, Tuple, Union

import numpy as np

Expand Down Expand Up @@ -69,11 +69,67 @@
shorthand notation is ^C T^B_A, where C is the frame the velocity is measured in, B is the frame the velocity is expressed in.
"""

# manipulator types
#####################
# Manipulator types #
#####################

JointConfigurationType = np.ndarray
"""an (N,) numpy array that represents the joint angles for a robot"""

#########################
# Single-arm path types #
#########################
JointPathType = List[JointConfigurationType]
""" a list of joint configurations that describe a path in joint space"""

JointPathArrayType = np.ndarray
""" a (N, DoFs) numpy array that represents a path in joint space"""

PosePathType = List[HomogeneousMatrixType]
""" a list of homogeneous matrices that describe a path in cartesian space"""

PosePathArrayType = np.ndarray
""" a (N, 4, 4) numpy array that represents a path in cartesian space"""

TimePathType = List[float]
""" a list of times that describe a path in time, must be monotonically increasing"""

TimePathArrayType = np.ndarray
""" a (N,) numpy array that represents a path in time, must be monotonically increasing"""

#######################
# Dual-arm path types #
#######################
DualJointConfigurationType = np.ndarray
""" a (2 * DoFs,) numpy array, result of np.hstack((left_joints, right_joints))"""

DualJointPathType = List[DualJointConfigurationType]
""" a list of dual arm joint configurations that describe a path in joint space"""

DualJointPathArrayType = np.ndarray
""" a (N, 2 * DoFs) array, result of np.hstack((left_joint_path, right_joint_path))"""

#######################
# Single-arm types #
#######################
ForwardKinematicsType = Callable[[JointConfigurationType], HomogeneousMatrixType]
""" a function that computes the forward kinematics of a given joint configuration"""

InverseKinematicsType = Callable[[HomogeneousMatrixType], List[JointConfigurationType]]
""" a function that computes one or more inverse kinematics solutions of a given TCP pose"""


#########################
# Motion planning types #
#########################

JointConfigurationCheckerType = Callable[[JointConfigurationType], bool]
""" a function that checks a certain condition on a joint configuration, e.g. collision checking"""

DualJointConfigurationCheckerType = Callable[[DualJointConfigurationType], bool]
""" a function that checks a dual joint configuration, where the JointConfigurationType is the stacked version of the left and right joint configurations"""


######################
# camera related types
######################
Expand Down

0 comments on commit f3be0d1

Please sign in to comment.