Hexapod API
Modeling Functions
PaceRobots.Hexapod.eqs_quat — Functioneqs_quat(A::Matrix{Rational{BigInt}}, B::Matrix{Rational{BigInt}}) -> Vector{DynamicPolynomials.Polynomial}Generate the system of polynomial equations for the Direct Kinematic Problem (DKP) of a hexapod robot using quaternion parameterization.
Arguments
A::Matrix{Rational{BigInt}}: A 6x3 matrix where each row contains the coordinates of a joint on the base platform.B::Matrix{Rational{BigInt}}: A 6x3 matrix where each row contains the coordinates of a joint on the moving platform.
Returns
Vector{DynamicPolynomials.Polynomial}: A system of 6 polynomial equations in 12 variables: (t1, t2, t3, a, b, c, l1, l2, l3, l4, l5, l6), where (t1, t2, t3) are the translation components, (a, b, c) are the quaternion-like rotation parameters, and (l1, l2, l3, l4, l5, l6) are the leg lengths.
Description
This function constructs the polynomial system for the DKP using a minimal quaternion-like parameterization of the rotation matrix. The system consists of:
- 6 equations enforcing the leg length constraints
- The rotation matrix is parameterized using a skew-symmetric matrix H = [0 a b; -a 0 c; -b -c 0]
- The final rotation matrix is computed as R = (H + I) * inv(I - H), normalized by (1 + a² + b² + c²)
To solve the DKP, you must first substitute the leg lengths using subs_lengths!, which reduces the system to 6 equations in 6 variables (t1, t2, t3, a, b, c). The resulting system can then be solved using certified numerical methods to find all possible configurations of the moving platform.
Example
julia> sys1 = Hexapod.eqs_quat(A, B)
6-element Vector{Any}:
94474738081//500000 - 3538250717//12500c - 253923821//5000b - 39008452997//62500a + ...
# ... (6 polynomial equations in 12 variables)
julia> Hexapod.subs_lengths!(sys1, lengths) # Substitute leg lengths
julia> sols = Hexapod.DKP(sys1, prec) # Solve for configurationPaceRobots.Hexapod.eqs_quat2 — Functioneqs_quat2(A::Matrix{Rational{BigInt}}, B::Matrix{Rational{BigInt}}) -> Vector{DynamicPolynomials.Polynomial}Generate an optimized system of polynomial equations for the Direct Kinematic Problem (DKP) using relative coordinates and quaternion parameterization.
Arguments
A::Matrix{Rational{BigInt}}: A 6x3 matrix where each row contains the coordinates of a joint on the base platform.B::Matrix{Rational{BigInt}}: A 6x3 matrix where each row contains the coordinates of a joint on the moving platform.
Returns
Vector{DynamicPolynomials.Polynomial}: A system of 6 polynomial equations in 12 variables: (t1, t2, t3, a, b, c, l1, l2, l3, l4, l5, l6), optimized for numerical solving.
Description
This function constructs a more efficient polynomial system for the DKP by:
- Working in relative coordinates (subtracting the first point from all others)
- Using only 6 equations instead of 16
- The first equation is: l₁² = ||t||² (squared length of first leg equals squared translation)
- The remaining 5 equations combine rotation and translation constraints: lᵢ² - l₁² = 2·dot(R·BBᵢ - AAᵢ, t) + ||R·BBᵢ - AAᵢ||²
- Uses the same quaternion parameterization as
eqs_quatbut with fewer, more coupled equations
To solve the DKP, you must first substitute the leg lengths using subs_lengths!, which reduces the system to 6 equations in 6 variables (t1, t2, t3, a, b, c). This formulation is mathematically equivalent to eqs_quat but more computationally efficient for numerical solving.
Example
julia> sys2 = Hexapod.eqs_quat2(A, B)
6-element Vector{Any}:
l1² - t3² - t2² - t1²
-162226804217//1000000 + 182912211//250000c - 26409171//62500b - 9560013//125000a + ...
# ... (6 polynomial equations in 12 variables)
julia> Hexapod.subs_lengths!(sys2, lengths) # Substitute leg lengths
julia> sols2 = Hexapod.DKP(sys2, prec) # Solve for configurationInverse and Direct Kinematics Problem
PaceRobots.Hexapod.IKP — FunctionIKP(A::Matrix{Rational{BigInt}}, B::Matrix{Rational{BigInt}}, prec::Integer) -> Vector{Rational{BigInt}}Compute the Inverse Kinematic Problem (IKP) for a hexapod robot, calculating the leg lengths given the positions of the base and moving platform joints.
Arguments
A::Matrix{Rational{BigInt}}: A 6x3 matrix where each row contains the coordinates of a joint on the base platform.B::Matrix{Rational{BigInt}}: A 6x3 matrix where each row contains the coordinates of a joint on the moving platform.prec::Integer: The precision (in bits) for rounding the computed leg lengths.
Returns
Vector{Rational{BigInt}}: A 6-element vector containing the leg lengths, rounded to the specified precision.
PaceRobots.Hexapod.DKP — FunctionDKP(sys::Vector, prec::Integer) -> Vector{Vector{BigInterval}}Solve the Direct Kinematic Problem (DKP) using certified numerical methods to find all possible configurations of the moving platform.
Arguments
sys::Vector: A system of polynomial equations (typically generated byeqs_quatoreqs_quat2).prec::Integer: The precision (in bits) for the output intervals.
Returns
Vector{Vector{BigInterval}}: A vector of solution intervals, where each solution is represented as a vector of 6 intervals containing the configuration parameters (t1, t2, t3, a, b, c).
Description
This function solves the DKP using certified numerical methods:
- Transforms the polynomial system from DynamicPolynomials to AbstractAlgebra format
- Computes a Rational Univariate Representation (RUR) of the system
- Isolates all real solutions using interval arithmetic with the specified precision
- Returns guaranteed intervals containing all real solutions
Each solution interval represents a possible configuration of the moving platform, with the first three components being translation and the last three being rotation parameters.
Path Planning and Trajectory Generation
PaceRobots.Hexapod.follow_path — Functionfollow_path(sys, old_sol::Vector{BigFloat}; alg::String="RS", input_precision::Integer=Int32(52), point_precision::Integer=Int32(52), work_precision::Integer=Int32(52), output_precision::Integer=Int32(32), max_nb_loops::Integer=Int32(10)) -> Tuple{Vector{Vector{BigFloat}}, Integer}Follow a solution path using Newton's method with different certified numerical algorithms.
Arguments
sys: A system of polynomial equations.old_sol::Vector{BigFloat}: The initial solution point to start from.alg::String="RS": The algorithm to use. Options are:"RS": RealSolving algorithm (default)"LACE-1": LACE interval Newton with classic refinement"LACE-2": LACE interval Newton with conditional intersection
input_precision::Integer=Int32(52): Input precision in bits.point_precision::Integer=Int32(52): Point precision in bits.work_precision::Integer=Int32(52): Working precision in bits.output_precision::Integer=Int32(32): Output precision in bits.max_nb_loops::Integer=Int32(10): Maximum number of Newton iterations.
Returns
Tuple{Vector{Vector{BigFloat}}, Integer}: A tuple containing:- A vector of solution points (typically 1 element)
- An integer status code indicating success/failure
follow_path(A::Matrix{T}, B::Matrix{T}, sol_init::Vector{BigFloat}, commands::Vector{Vector{Rational{BigInt}}}; alg::String="RS", input_precision::Integer=Int32(52), point_precision::Integer=Int32(52), work_precision::Integer=Int32(52), output_precision::Integer=Int32(32), max_nb_loops::Integer=Int32(10)) -> Vector{Any} where {T<:Union{AbstractFloat, BigInt, Number}}Follow a trajectory of leg length commands using path following to compute the corresponding platform configurations.
Arguments
A::Matrix{T}: A 6x3 matrix containing the coordinates of base platform joints.B::Matrix{T}: A 6x3 matrix containing the coordinates of moving platform joints.sol_init::Vector{BigFloat}: Initial solution configuration (6-element vector: [t1, t2, t3, a, b, c]).commands::Vector{Vector{Rational{BigInt}}}: A sequence of leg length commands, where each command is a 6-element vector of leg lengths.alg::String="RS": The numerical algorithm to use for path following (seefollow_pathfor options).input_precision::Integer=Int32(52): Input precision in bits.point_precision::Integer=Int32(52): Point precision in bits.work_precision::Integer=Int32(52): Working precision in bits.output_precision::Integer=Int32(32): Output precision in bits.max_nb_loops::Integer=Int32(10): Maximum number of Newton iterations.
Returns
Vector{Any}: A list of platform configurations, where each configuration is a vector of 6 points representing the positions of the moving platform joints in the base frame.
Description
This function implements trajectory following for a hexapod robot:
- Generates the polynomial system for the DKP using
eqs_quat - For each leg length command:
- Substitutes the leg lengths into the polynomial system
- Uses path following to find the new platform configuration
- Converts the configuration to joint positions using
quat_to_pos
- Returns the sequence of platform configurations
PaceRobots.Hexapod.generate_lengths — Functiongenerate_lengths(A::Matrix{T}, B::Matrix{T}, nb_points::Integer, prec::Integer) -> Vector{Vector{Rational{BigInt}}} where {T<:Union{AbstractFloat, BigInt, Number}}Generate a sequence of leg length commands for an oscillatory trajectory of the moving platform.
Arguments
A::Matrix{T}: A 6x3 matrix containing the coordinates of base platform joints.B::Matrix{T}: A 6x3 matrix containing the coordinates of moving platform joints.nb_points::Integer: The number of points to generate along the trajectory.prec::Integer: The precision (in bits) for rounding the computed leg lengths.
Returns
Vector{Vector{Rational{BigInt}}}: A sequence of leg length commands, where each command is a 6-element vector of leg lengths.
Description
This function generates leg length commands for an oscillatory trajectory by:
- Creating a sinusoidal parameter θ that varies with amplitude π/32 over one complete cycle
- Applying a rotation matrix R(θ) to the moving platform joints
- Computing the corresponding leg lengths using the IKP
- Rounding the results to the specified precision
PaceRobots.Hexapod.deform_legs — Functiondeform_legs(x::Vector{Rational{BigInt}}, m::Integer) -> Vector{Rational{BigInt}}Add random perturbations to leg lengths to simulate manufacturing tolerances or measurement errors.
Arguments
x::Vector{Rational{BigInt}}: A vector of 6 leg lengths to be perturbed.m::Integer: The maximum magnitude of the perturbation (inclusive range [-m, m]).
Returns
Vector{Rational{BigInt}}: A vector of 6 perturbed leg lengths, where each length has been modified by adding a random integer in the range [-m, m].
Example
julia> m = 1
julia> deformations = [Hexapod.deform_legs(lengths, m) for _ in 1:50]Visualization
PaceRobots.Hexapod.animate_robot — Functionanimate_robot(A::Matrix, B_list::Vector; name::String="robot_animation", path::String=pwd()) -> FigureCreate an animated visualization of a hexapod robot's motion.
Arguments
A::Matrix: A 6x3 matrix containing the coordinates of base platform joints.B_list::Vector: A list of platform configurations, where each configuration is a vector of 6 points representing the positions of the moving platform joints.name::String="robot_animation": The filename for the output video (without extension).path::String=pwd(): The directory path where the animation file will be saved.
Returns
Figure: A Makie figure object containing the 3D animation.
Description
This function creates a 3D animation of a hexapod robot showing:
- The base platform (dark grey, semi-transparent)
- The moving platform (grey, opaque) at each time step
- The six legs connecting corresponding joints (black lines)
- Joint points on both platforms (black spheres)
The animation:
- Uses stable axis limits calculated from all positions
- Records at 30 frames per second
- Saves the result as an MP4 file in the specified directory
- Uses Makie's Observable system for smooth animation
Example
julia> Hexapod.animate_robot(A, B_list, name="robot_1", path=pwd())Utility Functions
PaceRobots.Hexapod.quat_to_pos — Functionquat_to_pos(x::Vector, B::Matrix) -> Vector{Vector{BigFloat}}Compute the positions of the moving platform's joints (B_i) in the base reference frame, given a configuration vector (solution to the DKP) and the local coordinates of the joints on the moving platform.
Arguments
x::Vector: A 6-element vector representing the configuration of the moving platform. The first three elements (x[1:3]) are the translation components (position of the platform's center in the base frame), and the last three elements (x[4:6]) are the rotation parameters (a,b,c) that define the orientation of the platform using a minimal quaternion-like representation.B::Matrix: A 6x3 matrix where each row contains the coordinates of a joint on the moving platform, expressed in the moving platform's local frame.
Returns
Vector{Vector{BigFloat}}: A vector of 6 points, where each point is a 3-element vector representing the coordinates of a joint on the moving platform, transformed into the base reference frame according to the given configurationx.
quat_to_pos(x::Vector, B::Vector) -> Vector{Vector{BigFloat}}Compute the positions of the moving platform's joints (B_i) in the base reference frame, given a configuration vector (solution to the DKP) and the local coordinates of the joints on the moving platform, provided as a vector of points.
Arguments
x::Vector: A 6-element vector representing the configuration of the moving platform. The first three elements (x[1:3]) are the translation components (position of the platform's center in the base frame), and the last three elements (x[4:6]) are the rotation parameters (a,b,c) that define the orientation of the platform using a minimal quaternion-like representation.B::Vector: A vector of 6 points, where each point is a 3-element vector representing the coordinates of a joint on the moving platform, expressed in the moving platform's local frame.
Returns
Vector{Vector{BigFloat}}: A vector of 6 points, where each point is a 3-element vector representing the coordinates of a joint on the moving platform, transformed into the base reference frame according to the given configurationx.