Global backend configuration for rational_linkages.
Controls whether numeric (NumPy) or symbolic (SymPy) computation is used
across all classes. Call set_backend() once at the top of a script
before constructing any objects.
Must be called before constructing any objects. Switching backends
after objects have already been created leads to undefined behaviour
when mixing instances from different backends.
Parameters:
name (str) – Backend identifier. Either "numpy" (default) or "sympy".
Affine metric for a motion defined by a rational curve.
The affine metric aggregates point-wise metric contributions of a set of
homogeneous 3D points and provides distances and inner-products for
affine displacements represented as dual quaternions.
References
Hofer, “Variational Motion Design in the Presence of Obstacles”,
dissertation thesis (2004), Page 7, Equation 2.4
Schroecker, Weber, “Guaranteed collision detection with toleranced
Compute the aggregate affine metric matrix for the motion.
The metric is computed by summing the per-point metric contributions of
the homogeneous 3D points stored in self.points (see
get_point_metric_matrix()). The returned matrix operates on 12D
representations of affine displacements.
Return two representative transformations of the rational curve.
The method evaluates the stored motion curve at -1 and at infinity
(implemented as evaluation with inverted_part=True at parameter 0)
and returns the corresponding dual quaternions.
Compute squared distance between two points given in projective R12.
Parameters:
a (ndarray) – Projective R12 points where the first component is the homogeneous
scale and the remaining 12 components form the 12D representation
(this function uses a[1:] and b[1:] internally).
b (ndarray) – Projective R12 points where the first component is the homogeneous
scale and the remaining 12 components form the 12D representation
(this function uses a[1:] and b[1:] internally).
Return the squared distance between two affine displacements.
Parameters:
a (DualQuaternion) – Affine displacements represented as dual quaternions. If both
have non-zero scalar parts they will be normalized by their scalar
components before computing the inner product.
b (DualQuaternion) – Affine displacements represented as dual quaternions. If both
have non-zero scalar parts they will be normalized by their scalar
components before computing the inner product.
Compute the inner product of two dual quaternions w.r.t. this metric.
The inner product is computed by acting both dual quaternions on each of
the reference points that define the metric and summing the squared
Euclidean distances between the resulting acted points.
Parameters:
a (DualQuaternion) – Affine displacements represented as dual quaternions.
b (DualQuaternion) – Affine displacements represented as dual quaternions.
Returns:
float – The inner product value (a non-negative scalar).
Optimization helpers for finding collision-free full-cycle designs.
The class contains utilities to estimate an initial configuration for the
mechanism (smallest polyline) and to run higher-level optimization
routines (for example combinatorial search).
Find points on mechanism axes that form the smallest polyline.
The routine represents each mechanism axis as a normalized line and
chooses one point on each axis such that the closed polyline connecting
these points has minimal total Euclidean length. The optimization is
performed with scipy.optimize.minimize.
tuple – (points,points_params,result) where points is a list of
3D points on the axes, points_params are the parameter values
used to generate these points (duplicated per joint connection
point), and result is the optimizer result object.
The algorithm follows the approach in the referenced work
([1]) and performs an enumerative search over discrete
shift values for links and joint connection points to find collision-free
mechanism designs.
The search iterates over increasing shift magnitudes and first attempts
to find collision-free link-only configurations before searching the
full mechanism including joint segments.
Parameters:
**kwargs – Optional control parameters (for example start_iteration and
end_iteration can be provided). See method usage in the code.
Returns:
list or None – Collision-free point parameters or None if no solution was
found.
Search for a full collision-free mechanism design including joints.
Parameters:
coll_free_links_params (list) – Collision-free points parameters for links (as returned by
search_links()). These parameters are doubled and adjusted
to represent joint connection point pairs.
combinations (list) – Precomputed joint-shift combinations to try. If None, these
are generated internally.
optional – Precomputed joint-shift combinations to try. If None, these
are generated internally.
Returns:
list or None – Collision-free point parameters for the full mechanism, or
None if no configuration could be found.
Dual quaternion representing a rigid body displacement in 3D space.
A dual quaternion consists of a primal part p (rotation) and a dual
part d (translation), stored as two Quaternion
instances. The 8 Study parameters [p0,p1,p2,p3,d0,d1,d2,d3]
are the concatenation of the two quaternion coefficient vectors.
By default, all computation is performed with NumPy (float64). When
the global backend is set to "sympy" via
set_backend(), construction transparently returns a
DualQuaternionSymbolic instance instead.
Parameters:
coeffs (Optional[Sequence[float]]) – 8-vector of Study parameters [p0,p1,p2,p3,d0,d1,d2,d3].
If None, the identity dual quaternion [1,0,0,0,0,0,0,0]
is constructed.
Construct a DualQuaternion from SymPy Rational numbers.
Deprecated since version ``as_rational``: is deprecated and will be removed in a future
version. Pass SymPy Rational values directly to the
DualQuaternion constructor instead::
Each element of coeffs is converted to a
sympy.Rational. Elements may be plain numbers (converted via
Rational(x)), or 2-tuples (p,q) (converted via
Rational(p,q)). If None, the rational identity dual quaternion
is returned.
Parameters:
coeffs (Optional[Sequence]) – List or array of 8 numbers or (numerator,denominator) tuples.
If None, the identity is constructed.
Construct a DualQuaternion from a degree-1 biquaternion_py polynomial.
The polynomial is expected to be of the form (t-h), where t
is the indeterminate and h is a BiQuaternion. The DualQuaternion is
assembled from the negated constant coefficients of the polynomial.
Parameters:
poly – A biquaternion_py.polynomials.Poly instance of degree 1.
indet – The SymPy symbol used as indeterminate of the polynomial.
Act on a geometric object (line or point) with this dual quaternion.
The action is a half-turn about the dual quaternion’s axis. If
affected_object is itself a DualQuaternion (treated as a
rotation-axis dual quaternion), it is first converted to a
NormalizedLine and the action is performed on that.
Parameters:
affected_object – A NormalizedLine, PointHomogeneous, or DualQuaternion
to act upon.
Symbolic dual quaternion backed by SymPy expressions.
Subclass of DualQuaternion for algebraic
computation. Typically, not instantiated directly — when the global backend
is set to "sympy" via set_backend(),
DualQuaternion transparently returns instances
of this class via its __new__ factory.
All arithmetic operators return DualQuaternionSymbolic instances.
Products are simplified via sympy.expand() and inverses via
sympy.simplify() for clean algebraic output.
Parameters:
coeffs (Optional[Sequence]) – 8-vector of Study parameters [p0,p1,p2,p3,d0,d1,d2,d3] as
SymPy expressions or plain numbers. If None, the identity dual
quaternion [1,0,0,0,0,0,0,0] is constructed.
Create a random dual quaternion with rational coefficients.
Parameters:
interval (int) – SymPy number specifying the range of random coefficients. Each
coefficient is sampled uniformly from the interval [-interval,interval].
Default is 1.
max_denominator (int) – Maximum denominator for the random rational coefficients. Default is 4.
Act on a geometric object with a dual quaternion (or a list of factors).
Dispatches to _act_on_line or _act_on_point based on the
type of affected_object. When acting_object is a list, the factors
are multiplied left-to-right before the action is applied.
Prepare parameter tuples required to build an Exudyn model.
The returned values can be used to create rigid bodies, define joint
axes and populate body geometry in an Exudyn multibody system. The
tuple contains the following elements:
links_pts: positions of the link connection points (list of point pairs)
links_lengths: scalar lengths for each link
body_dim: per-link body dimensions used to size primitive geometries
links_masses_pts: center-of-gravity positions for each link
joint_axes: unit axes for the joints
relative_links_pts: connection points relative to each link’s COG
Parameters:
mechanism (RationalMechanism) – The mechanism to convert into Exudyn parameters.
is_rational (bool) – If True, use the mechanism’s rational representation; otherwise a
static representation is used.
optional – If True, use the mechanism’s rational representation; otherwise a
static representation is used.
link_radius (float) – Radius (thickness) to use for link bodies when creating body
dimensions.
optional – Radius (thickness) to use for link bodies when creating body
dimensions.
scale (float) – Length scaling factor applied to all link points.
optional – Length scaling factor applied to all link points.
Provide motion factorizations for polynomial or curve inputs.
This class provides methods to factorize a polynomial or a
RationalCurve into motion factorizations. It integrates with the
external biquaternion_py project (BiQuaternions_py).
Store and manage connection points for a joint axis.
A Linkage holds two connection points (or a single point duplicated) on a
joint axis and exposes utilities to query and set those points by their
parametric position on the axis.
Represent a physical line segment produced by two moving points.
A LineSegment stores parametric point expressions (typically
PointHomogeneous instances with parameter t) for its endpoints and
bookkeeping metadata such as type and factorization indices.
Check whether a 3D point lies on the segment at parameter t_val.
The endpoints of the segment are evaluated at t_val and the point
is considered part of the segment when the sum of distances from the
endpoints equals the segment length within numerical tolerance.
Return arrays suitable for plotting the moving line segment.
The function samples the segment endpoints over a finite parameter
interval and returns three 2xN arrays containing the X, Y and Z
coordinates for both endpoints. These arrays can be plotted as a mesh
to display the moving segment.
Utilities to approximate rational motion curves from samples.
The class provides routines to approximate a low-degree rational motion
curve that passes close to a set of given poses or points. Optimization
is performed using SciPy when available.
This class encapsulates the Qt application and provides convenience
constructors to create and show the interactive MotionDesigner widget.
Examples
# Run motion designer without initial points or posesfromrational_linkagesimportMotionDesignerd=MotionDesigner(method='quadratic_from_poses')d.show()
# Run motion designer with initial points:fromrational_linkagesimportMotionDesigner,PointHomogeneouschosen_points=[PointHomogeneous(pt)forptin[[1.,-0.2,0.,1.76],[1.,1.,1.,2.],[1.,3.,-3.,1.],[1.,2.,-4.,1.],[1.,-2.,-2.,2.]]]d=MotionDesigner(method='quadratic_from_points',initial_points_or_poses=chosen_points)d.show()
The widget displays a 3D view of the motion curve and control points
together with a side panel containing sliders and controls to modify
the selected control point. The curve updates interactively when
control values change.
Set slider values and textboxes to match a control point.
The function updates sliders and their associated textboxes to
reflect the coordinates (and, for pose methods, rotations) of the
selected control point.
Synthesize and show a mechanism preview from the current curve.
The method computes an interpolated curve from the current
control points, constructs a RationalMechanism and adds a
preview interactive widget for the mechanism.
Handle slider changes: update the selected control point and redraw.
Converts integer slider values into floating point coordinates and
updates the internal point list and plotted markers. The motion
curve visualization is then refreshed.
Representation of a motion factorization sequence.
This class inherits from rational_linkages.RationalCurve and
represents a motion as a product of linear dual-quaternion factors. See
the accompanying paper for details ([2]).
Parameters:
sequence_of_factored_dqs (list[DualQuaternion]) – Sequence of DualQuaternion instances representing the revolute
axes (factors) of the motion factorization.
Variables:
dq_axes – List of dual-quaternion axes used by the factorization.
factors_with_parameter – List of symbolic factor expressions of the form (t-axis).
number_of_factors – Number of factors in the factorization.
linkage – Lazy property returning the per-axis Linkage objects.
Example
The following example demonstrates creating a factorization for a simple
2R mechanism
# 4-pose interpolationfromrational_linkagesimport(DualQuaternion,Plotter,MotionInterpolation,RationalMechanism)# 4 posesp0=DualQuaternion()# identityp1=DualQuaternion([0,0,0,1,1,0,1,0])p2=DualQuaternion([1,2,0,0,-2,1,0,0])p3=DualQuaternion([3,0,1,0,1,0,-3,0])# obtain the interpolated motion curvec=MotionInterpolation.interpolate([p0,p1,p2,p3])# factorize the motion curvef=c.factorize()# create a mechanism from the factorizationm=RationalMechanism(f)# create an interactive plotter object, with 1000 descrete steps# for the input rational curves, and arrows scaled to 0.5 lengthmyplt=Plotter(mechanism=m,steps=1000,arrows_length=0.5)# plot the posesforposein[p0,p1,p2,p3]:myplt.plot(pose)# show the plotmyplt.show()
Optimized search for a helper third pose for quadratic interpolation.
Deprecated since version :meth:`interpolate_quadratic_2_poses_optimized`: is deprecated and will be
removed in a future release. Use
interpolate_quadratic_2_poses_random() instead.
Line in 3D space represented by Plücker coordinates (unit screw axis).
Plücker coordinates [l1,l2,l3,m1,m2,m3] encode a line as a
direction vector l (unit-length) and a moment vector m, satisfying
the Plücker condition l·m=0.
By default, all computation is performed with NumPy (float64). When
the global backend is set to "sympy" via
set_backend(), construction transparently returns a
NormalizedLineSymbolic instance instead.
Parameters:
unit_screw (Optional[Sequence[float]]) – 6-vector of Plücker coordinates [l1,l2,l3,m1,m2,m3]. If
None, the Z-axis through the origin [0,0,1,0,0,0] is
constructed.
Variables:
direction (numpy.ndarray) – Unit direction vector [l1,l2,l3].
Compute the common perpendicular between this line and other.
Returns the two foot-points, the distance, and the cosine of the
angle between the lines. Falls back to the principal-point distance
when the lines are parallel.
Symbolic Plücker line backed by SymPy expressions.
Subclass of NormalizedLine for algebraic
computation. Typically, not instantiated directly — when the global backend
is set to "sympy" via set_backend(),
NormalizedLine transparently returns instances
of this class via its __new__ factory.
Parameters:
unit_screw (Optional[Sequence]) – 6-vector of Plücker coordinates [l1,l2,l3,m1,m2,m3] as
SymPy expressions or plain numbers. If None, the Z-axis through
the origin is constructed.
Variables:
direction – Object-dtype array of SymPy expressions [l1,l2,l3].
moment – Object-dtype array of SymPy expressions [m1,m2,m3].
Construct a NormalizedLine from the given direction and point.
Parameters:
direction – 3-vector of SymPy expressions or plain numbers representing the line’s
direction. Should be unit-length for correct behavior, but this is not
enforced.
point – 3-vector of SymPy expressions or plain numbers representing a point
on the line.
Construct a NormalizedLine from the given direction and moment.
Parameters:
direction – 3-vector of SymPy expressions or plain numbers representing the line’s
direction. Should be unit-length for correct behavior, but this is not
enforced.
moment – 3-vector of SymPy expressions or plain numbers representing the line’s
moment.
Construct a NormalizedLine from the given pt0 and pt1.
Parameters:
pt0 (Union[PointHomogeneous, Sequence[float]]) – A PointHomogeneous or a 3-vector of SymPy expressions
or numbers representing a point on the line.
pt1 (Union[PointHomogeneous, Sequence[float]]) – A PointHomogeneous or a 3-vector of SymPy expressions
or numbers representing a different point on the line.
Compute the common perpendicular between this line and other.
Returns the two foot-points, the distance, and the cosine of the
angle between the lines. Falls back to the principal-point distance
when the lines are parallel.
Plane in 3D space represented by a unit normal and an oriented distance.
The plane is stored as [d,n1,n2,n3] where n is the unit normal
and d=n·(-point) is the signed distance from the origin.
By default, all computation is performed with NumPy (float64). When
the global backend is set to "sympy" via
set_backend(), construction transparently returns a
NormalizedPlaneSymbolic instance instead.
Parameters:
normal (Sequence[float]) – 3-vector normal to the plane. Normalized to unit length on construction.
point (Sequence[float]) – 3-vector of any point lying on the plane.
Variables:
normal (numpy.ndarray) – Unit normal vector [n1,n2,n3].
point (numpy.ndarray) – A point on the plane [x,y,z].
oriented_distance (float) – Signed distance from the origin, d=n·(-point).
fromrational_linkagesimportNormalizedPlaneplane=NormalizedPlane([0,0,1],[0,0,5])# z = 5
# Symbolic backendimportrational_linkagesrational_linkages.set_backend("sympy")fromrational_linkagesimportNormalizedPlanefromsympyimportsymbolsa,b,c,d=symbols("a b c d",real=True)plane=NormalizedPlane([a,b,c],[d,0,0])rational_linkages.set_backend("numpy")
Subclass of NormalizedPlane for algebraic
computation. Typically not instantiated directly — when the global backend
is set to "sympy" via set_backend(),
NormalizedPlane transparently returns instances
of this class via its __new__ factory.
Parameters:
normal (Sequence) – 3-vector normal as SymPy expressions or plain numbers.
point (Sequence) – 3-vector point on the plane as SymPy expressions or plain numbers.
Variables:
normal (numpy.ndarray) – Object-dtype unit normal [n1,n2,n3] of SymPy expressions.
point (numpy.ndarray) – Object-dtype array [x,y,z] of SymPy expressions.
oriented_distance (sympy.Expr) – Signed distance d=n·(-point) as a SymPy expression.
importrational_linkagesrational_linkages.set_backend("sympy")fromrational_linkagesimportNormalizedPlanefromsympyimportsymbolsa,b,c,d=symbols("a b c d",real=True)plane=NormalizedPlane([a,b,c],[d,0,0])print(plane.oriented_distance)rational_linkages.set_backend("numpy")
Create and return an appropriate plotter instance based on parameters.
Default backend is 'pyqtgraph' but can be changed to
'matplotlib'.
Parameters:
mechanism (RationalMechanism) – Optional RationalMechanism
instance used by an interactive
plotter. If provided and jupyter_notebook is False an
interactive widget is created.
base – Optional base transform or object passed to backends.
show_tool (bool) – Whether to draw the end-effector/tool in the plots.
backend (str) – Backend name to use ('pyqtgraph' or 'matplotlib').
jupyter_notebook (bool) – If True, create plotters suited for Jupyter notebooks.
show_legend (bool) – Whether to display a legend (only supported by Matplotlib
backend).
show_controls (bool) – Whether to show interactive controls (only supported by
Matplotlib backend when running non-interactively).
paper_visual (bool) – If True, use a visualization style suitable for paper figures.
(Matplotlib backend only).
interval (tuple) – Parameter sampling interval passed to some plotter backends.
steps (int) – Number of sampling steps used when plotting curves.
arrows_length (float) – Visual length of pose arrows in the plot.
joint_sliders_lim (float) – Limit for joint sliders in interactive widgets.
white_background (bool) – If True, use a white background for plotting.
parent_app – Optional parent application instance for GUI backends.
Returns:
object – An instance of a backend-specific plotter class.
Notes
The returned backend instance exposes .plot(obj,**kwargs) and accepts
additional runtime plotting keyword arguments. The most used kwargs are:
Common kwargs across backends
labelstr (or list of str when plotting a list)
Label for plotted object(s). For a list of objects, pass a list of
labels of matching length.
intervaltuple or 'closed'
Parameter interval used for
RationalCurve
and
RationalBezier.
If set to 'closed', the curve will
be plotted using tangent function in full scale, including t -> inf.
Color name (white, red, green, blue, yellow,
magenta, cyan, orange, lime) or RGBA tuple.
sizefloat
Marker size for point plotting.
Matplotlib-oriented kwargs
Standard Matplotlib style kwargs are forwarded to backend primitives
(ax.plot, ax.scatter, ax.quiver, ax.plot_surface), e.g.
color, linewidth/lw, linestyle, marker, alpha.
Custom Matplotlib artists
When backend='matplotlib', the returned object exposes
plotter.ax and plotter.fig. You can add your own artists
directly, for example: plotter.ax.scatter(x,y,z,c='k',s=20).
This is backend-specific and is not available in the PyQtGraph backend.
Point in projective space with homogeneous coordinates.
Homogeneous coordinates [w,x,y,z] represent points in ℙⁿ,
including points at infinity (where w=0). The coordinate vector
may have length 3 (ℙ²), 4 (ℙ³), or higher ℙⁿ for more abstract applications.
By default, all computation is performed with NumPy (float64). When
the global backend is set to "sympy" via
set_backend(), construction transparently
returns a PointHomogeneousSymbolic instance instead,
with no change to the calling code required.
Parameters:
point (Optional[Sequence[float]]) – Sequence of homogeneous coordinates [w,x,y,...]. If
None, the origin in ℙ³ [1,0,0,0] is constructed.
# Symbolic backendimportrational_linkagesrational_linkages.set_backend("sympy")fromrational_linkagesimportPointHomogeneousfromsympyimportsymbolsw,x,y,z=symbols("w x y z",real=True)p=PointHomogeneous([w,x,y,z])# transparently returns PointHomogeneousSymbolicrational_linkages.set_backend("numpy")
Symbolic point in projective space backed by SymPy expressions.
Subclass of PointHomogeneous for algebraic computation.
Typically not instantiated directly — when the global backend is set to
"sympy" via set_backend(),
PointHomogeneous transparently returns instances of this
class via its __new__ factory.
Parameters:
point (Optional[Sequence]) – Sequence of homogeneous coordinates as SymPy expressions or plain
numbers. If None, the origin [1,0,0,0] is constructed.
Quaternion representing a 4-dimensional number [w,x,y,z].
Used as the building block of DualQuaternion, where the primal and
dual parts are each a Quaternion.
By default, all computation is performed with NumPy (float64). When
the global backend is set to "sympy" via
set_backend(), construction transparently
returns a QuaternionSymbolic instance
instead, with no change to the calling code required.
Parameters:
coeffs (Optional[Sequence[float]]) – Coefficients [w,x,y,z]. If None, the identity
quaternion [1,0,0,0] is constructed.
Variables:
q (numpy.ndarray) – 4-vector of quaternion coefficients [w,x,y,z].
# Fully symbolic backend — set once at the top of your scriptimportrational_linkagesrational_linkages.set_backend("sympy")fromrational_linkagesimportQuaternionfromsympyimportsymbolsa,b=symbols("a b",real=True)q=Quaternion([a,b,0,0])# transparently returns QuaternionSymbolic
Subclass of Quaternion for algebraic
computation. Typically, not instantiated directly — when the global backend is
set to "sympy" via set_backend(),
Quaternion transparently returns instances
of this class via its __new__ factory.
All arithmetic operators return QuaternionSymbolic instances.
Products are simplified via sympy.expand() and inverses via
sympy.simplify() for clean algebraic output.
Parameters:
coeffs (Optional[Sequence]) – Coefficients [w,x,y,z] as SymPy expressions or plain
numbers. If None, the identity quaternion [1,0,0,0]
is constructed.
Variables:
q (numpy.ndarray) – Object-dtype array of SymPy expressions [w,x,y,z].
QuaternionSymbolic – New quaternion with substitutions applied.
Examples
importrational_linkagesrational_linkages.set_backend("sympy")fromrational_linkagesimportQuaternionfromsympyimportsymbolsa,b,c,d=symbols("a b c d",real=True)q1=Quaternion([a,b,c,d])subs={a:1,b:-2,c:0,d:0}q1_evaluated=q1.eval(subs)print(q1_evaluated)
Class representing rational Bezier curves in n-dimensional space.
Examples
# Create a rational Bezier curve from control points# part of Limancon of Pascalfromrational_linkagesimportRationalBezier,PointHomogeneousimportnumpycontrol_points=[PointHomogeneous(numpy.array([4.,0.,-2.,4.])),PointHomogeneous(numpy.array([0.,1.,-2.,0.])),PointHomogeneous(numpy.array([1.33333333,2.66666667,0.,1.33333333])),PointHomogeneous(numpy.array([0.,1.,2.,0.])),PointHomogeneous(numpy.array([4.,0.,2.,4.]))]bezier_curve=RationalBezier(control_points)
t_param (tuple of (bool, list of float), optional) – True if the Bezier curve is interpolation inverse part of reparameterized motion curve, False otherwise; list of two floats representing the original parameter interval of the motion curve. Default is (False, [0, 1]).
metric (AffineMetric, optional) – Metric in R12 for the mechanism, used for collision detection. Default is None.
Class representing rational Gauss-Legendre curves in n-dimensional space.
The class implements the Gauss-Legendre curves to represent curved link segments.
Gauss-Legendre curves, introduced in Moon et al.[3], have the property that
the control polygon approximates the curve closely, and therefore can be used
for collision detection, instead of using the curve polynomials.
# From symbolic equationsfromrational_linkagesimportRationalCurve,Plotterfromsympyimportsymbols,Polyt=symbols('t')c=[t**2+3,-2*t,2,0,0,1,t,0,]c=RationalCurve([Poly(p,t)forpinc])p=Plotter(backend='matplotlib',arrows_length=0.05)p.plot(c,interval='closed',with_poses=True)p.show()
# Limancon of Pascal -- from polynomial equationsimportsympyfromrational_linkagesimportRationalCurvea=1b=0.5t=sympy.Symbol('t')eq0=sympy.Poly((1+t**2)**2,t)eq1=sympy.Poly(b*(1-t**2)*(1+t**2)+a*(1-t**2)**2,t)eq2=sympy.Poly(2*b*t*(1+t**2)+2*a*t*(1-t**2),t)curve=RationalCurve([eq0,eq1,eq2,eq0])
# From coefficientsimportnumpyfromrational_linkagesimportRationalCurvecurve=RationalCurve.from_coeffs(numpy.array([[1.,0.,2.,0.,1.],[0.5,0.,-2.,0.,1.5],[0.,-1.,0.,3.,0.],[1.,0.,2.,0.,1.]]))
interval (str or tuple, optional) – Interval of the parameter t. If ‘closed’, the closed-loop curve is parametrized using tangent half-angle substitution. Default is (0, 1).
steps (int, optional) – Number of numerical steps in the interval. Default is 50.
list of float – List of t values that split the curve into equal segments.
Raises:
ValueError – If the interval is not in the form [a, b] where a < b, or if the interval values are identical, or if the number of segments is less than 2.
# Create a rational mechanism from given examplefromrational_linkagesimportRationalMechanism,Plotter,TransfMatrixfromrational_linkages.modelsimportbennett_ark24# load the model of the Bennett's linkagem=bennett_ark24()# create an interactive plotter object, with 500 discrete steps# for the input rational curves, and arrows scaled to 0.05 lengthp=Plotter(mechanism=m,steps=500,arrows_length=0.05)##### additional plotting options ###### create a pose of the identitybase=TransfMatrix()p.plot(base)# create another posep0=TransfMatrix.from_rpy_xyz([-90,0,0],[0.15,0,0],unit='deg')p.plot(p0)# show the plotp.show()
unit (str, optional) – Desired unit of the angle parameters, can be ‘deg’, ‘rad’, or
‘tanhalf’ for tangent half-angle representation. Default is ‘rad’.
scale (float, optional) – Scale of the length parameters of the linkage. Default is 1.0.
include_base (bool, optional) – If True, identity frame will be placed at the beginning of the list of frames.
Default is False.
Get the frames of a linkage that follow standard Denavit-Hartenberg convention.
It returns n+2 frames, where n is the number of joints. The first frame is the
base frame, and the last frame is an updated frame of the first joint that
follows the DH convention in respect to the last joint’s frame.
Parameters:
include_base (bool, optional) – If True, identity frame will be placed at the beginning of the list of frames.
Default is False.
Perform full-cycle collision check on the line-model linkage.
By default, the collision check is performed in non-parallel mode. This is
faster for 4-bar linkages and 6-bar lingakes with a “simpler” motion curve,
but slower for 6-bar linkages with “complex” motions.
Parameters:
parallel (bool, optional) – If True, perform collision check in parallel using multiprocessing. Default is False.
pretty_print (bool, optional) – If True, print the results in a readable form. Default is True.
only_links (bool, optional) – If True, only link-link collisions are checked. Default is False.
terminate_on_first (bool, optional) – If True, terminate the collision check when the first collision is found. Default is False.
Returns:
list of float – List of collision check colliding parameter values.
unit (str, optional) – Unit of the joint angle, can be ‘rad’, ‘deg’, or ‘t’ as
t is the parameter of the motion curve. Default is ‘rad’.
method (str, optional) – Numerically for ‘gauss-newton’ or ‘algebraic’; ‘algebraic’
requires the input pose to be “achievable” by the mechanism, i.e. the pose
must be on Study quadric and the mechanism must be able to reach it.
robust (bool, optional) – If True, use the Gauss-Newton method with
many initial guesses and more iteration steps. Default is False.
Generate point to point straight line joint space trajectory.
This method originates from book Modern Robotics [5]
by Kevin M. Lynch
and Frank C. Park, and related software package published under MIT
licence and available at: https://github.com/NxRLab/ModernRobotics
Generate smooth trajectory for the tool of the mechanism.
The mechod implements [6] and generates a
joint-space trajectory so that the tool travels with approximately constant
velocity. The arc-length reparameterization is used in the background.
Calculate the relative motion between given pair of links or joints.
The method checks if the relative motion between the two links or joints
already exists in the self.relative_motions attribute. If it does, the method
returns the relative motion. If it does not, the method calculates the relative
motion and adds it to the self.relative_motions attribute.
Represent a non-rational mechanism with a fixed number of joints.
This class is highly specialized and not intended for general use of the
Rational Linkages package. It can be used, for example, to obtain the design
(e.g., DH parameters) of a mechanism that has no rational parametrization.
The joints are assembled in a fixed loop-closure configuration and are defined
by a list of screw axes that specify the motion of the mechanism.
Parameters:
screw_axes (list of NormalizedLine) – A list of screw axes that define the kinematic structure of the mechanism.
Variables:
screws (list of NormalizedLine) – A list of screw axes that define the kinematic structure of the mechanism.
num_joints (int) – The number of joints in the mechanism.
Examples
# Define a 4-bar mechanism from pointsfromrational_linkagesimportNormalizedLinefromrational_linkages.StaticMechanismimportStaticMechanisml0=NormalizedLine.from_two_points([0.0,0.0,0.0],[18.474,30.280,54.468])l1=NormalizedLine.from_two_points([74.486,0.0,0.0],[104.321,24.725,52.188])l2=NormalizedLine.from_two_points([124.616,57.341,16.561],[142.189,91.439,69.035])l3=NormalizedLine.from_two_points([19.012,32.278,0.000],[26.852,69.978,52.367])m=StaticMechanism([l0,l1,l2,l3])m.get_design(unit='deg')
# Define 6-bar mechanism from dual quaternions ijk representationfromrational_linkages.StaticMechanismimportStaticMechanismfromsympyimportsymbolsepsilon,i,j,k=symbols('epsilon i j k')linkage=[epsilon*k+i,epsilon*i+epsilon*k+j,epsilon*i+epsilon*j+k,-epsilon*k+i,epsilon*i-epsilon*k-j,epsilon*i-epsilon*j-k]m=StaticMechanism.from_ijk_representation(linkage)m.get_design(unit='deg')
classmethodfrom_dh_parameters(theta, d, a, alpha, unit='rad')[source]
unit (str, optional) – The unit of the angles (‘rad’ or ‘deg’). Default is ‘rad’.
Returns:
StaticMechanism – A StaticMechanism object.
Warns:
UserWarning – If the DH parameters do not close the linkages by default, the created
mechanism will not be a closed loop. Double-check the last link design
parameters.
Represent a non-rational mechanism with a fixed number of discrete poses (snap points).
This class is highly specialized and not intended for general use of the
Rational Linkages package. It can be used, for example, to obtain the design
(e.g., DH parameters) of a mechanism that has no rational parametrization.
The joints are assembled in a fixed loop-closure configuration and are defined
by a list of screw axes that specify the motion of the mechanism.
Parameters:
pose (Union[TransfMatrix, DualQuaternion]) – The second pose of the mechanism to which it snaps (the first pose is identity).
points (list of PointHomogeneous) – The points on the mechanism that specify axes 2 and 3. The ordering of points
is important, as axis 2 defines axis 1, and axis 3 defines axis 0.
Rigid body transformation in 3D space, stored as a 4×4 matrix.
Follows the homogeneous-first convention: the homogeneous coordinate
occupies position [0,0], the translation vector fills column 0
(rows 1–3), and the rotation matrix fills the lower-right 3×3 block:
To convert to or from the standard convention (rotation top-left,
translation top-right), use to_standard() and
from_standard().
By default, all computation is performed with NumPy (float64). When
the global backend is set to "sympy" via
set_backend(), construction transparently
returns a TransfMatrixSymbolic instance instead.
Parameters:
matrix – 4×4 array-like. If None, the identity transformation is
constructed.
Variables:
matrix (numpy.ndarray) – 4×4 float64 array storing the full transformation.
Construct from a normal (x-axis) and approach (z-axis) vector.
The orthogonal (y-axis) vector is derived as
o=approach_z×normal_x; normal_x is then recomputed as
n=o×approach_z to guarantee det(R)=1. Both input
vectors are silently normalised if necessary.
Parameters:
normal_x (Union[list, ndarray]) – 3-vector defining the x-axis of the frame.
approach_z (Union[list, ndarray]) – 3-vector defining the z-axis of the frame.
origin (Union[list, ndarray]) – 3-vector translation. Defaults to [0,0,0].
In the standard convention the rotation matrix occupies the
top-left 3×3 block, the translation vector occupies the
top-right column, and the bottom row is [0,0,0,1]:
Symbolic rigid body transformation backed by SymPy expressions.
Subclass of TransfMatrix for algebraic computation. Typically
not instantiated directly — when the global backend is set to
"sympy" via set_backend(),
TransfMatrix transparently returns instances of this class via
its __new__ factory.
The primary attribute matrix is a sympy.Matrix rather
than a NumPy array. The n, o, a, t properties return
SymPy column slices.
Parameters:
matrix – 4×4 array-like of SymPy expressions or plain numbers. If
None, the symbolic identity transformation is constructed.
Examples
importrational_linkagesrational_linkages.set_backend("sympy")fromrational_linkages.TransfMatriximportTransfMatrixfromsympyimportsymbolstx,ty,tz=symbols("tx ty tz",real=True)mat=TransfMatrix([[1,0,0,0],[tx,1,0,0],[ty,0,1,0],[tz,0,0,1]])print(mat.t)# Matrix([tx, ty, tz])rational_linkages.set_backend("numpy")
Construct from a normal (x-axis) and approach (z-axis) vector.
The orthogonal (y-axis) vector is derived as
o=approach_z×normal_x; normal_x is then recomputed as
n=o×approach_z to guarantee det(R)=1. Both input
vectors are silently normalised if necessary.
Parameters:
normal_x (list) – 3-vector defining the x-axis of the frame.
approach_z (list) – 3-vector defining the z-axis of the frame.
origin (list) – 3-vector translation. Defaults to [0,0,0].
Create a transformation matrix from DH parameters using Sympy in rational form.
The input shall be rational numbers, including the angles which are expected
to be parameters of tangent half-angle substitution, i.e., t_theta = tan(theta/2)
and t_alpha = tan(alpha/2).
Parameters:
t_theta (sympy.Rational) – DH parameter theta in tangent half-angle form.
di (sympy.Rational) – DH parameter d, the offset along Z axis.
ai (sympy.Rational) – DH parameter a, the length along X axis.
t_alpha (sympy.Rational) – DH parameter alpha in tangent half-angle form.