Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
46 changes: 41 additions & 5 deletions ext/Render.jl
Original file line number Diff line number Diff line change
Expand Up @@ -791,7 +791,7 @@ function render!(scene, ::typeof(UniversalSpherical), sys, sol, t)
true
end

function render!(scene, ::Union{typeof(RollingWheelJoint), typeof(SlipWheelJoint)}, sys, sol, t)
function render!(scene, ::Union{typeof(OneDOFRollingWheelJoint), typeof(SlipWheelJoint)}, sys, sol, t)

r_0 = get_fun(sol, collect(sys.frame_a.r_0))
# framefun = get_frame_fun(sol, sys.frame_a)
Expand Down Expand Up @@ -963,9 +963,9 @@ get_trans_2d(sol, frame, t) = SVector{2}(sol(t, idxs = [frame.x, frame.y]))
get_trans_2d(sol, frame, t::AbstractArray) = sol(t, idxs = [frame.x, frame.y])

function render!(scene, ::typeof(P.Frame), sys, sol, t)
# sol(sol.t[1], idxs=sys.render)==true || return true # yes, == true
radius = 0.005f0# sol(sol.t[1], idxs=sys.radius) |> Float32
length = 0.1f0#sol(sol.t[1], idxs=sys.length) |> Float32
sol(sol.t[1], idxs=sys.render)==true || return true # yes, == true
radius = sol(sol.t[1], idxs=sys.radius) |> Float32
length = sol(sol.t[1], idxs=sys.length) |> Float32
T = get_frame_fun_2d(sol, sys)

thing = @lift begin
Expand Down Expand Up @@ -1023,7 +1023,7 @@ function render!(scene, ::Union{typeof(P.FixedTranslation), typeof(P.BodyShape)}
Makie.GeometryBasics.Cylinder(origin, extremity, radius)
end
mesh!(scene, thing; color, specular = Vec3f(1.5), shininess=20f0, diffuse=Vec3f(1))
true
false
end

function render!(scene, ::typeof(P.Prismatic), sys, sol, t)
Expand Down Expand Up @@ -1126,6 +1126,42 @@ function render!(scene, ::Union{typeof(P.SimpleWheel), typeof(P.SlipBasedWheelJo
true
end

function render!(scene, ::Union{typeof(P.OneDOFSlippingWheelJoint), typeof(P.OneDOFRollingWheelJoint)}, sys, sol, t)

r_0 = get_fun(sol, [sys.frame_a.x, sys.frame_a.y])
rotfun = get_rot_fun_2d(sol, sys.frame_a)
color = get_color(sys, sol, :red)

# TODO: add some form of assumetry to indicate that the wheel is rotating

radius = try
sol(sol.t[1], idxs=sys.radius)
catch
0.05f0
end |> Float32
z = try
sol(sol.t[1], idxs=sys.z)
catch
0.0
end |> Float32
r = try
sol(sol.t[1], idxs=collect(sys.r))
catch
[1, 0]
end .|> Float32
n_a = [0, 1.0] # Rotation axis
thing = @lift begin
O = [r_0($t)..., z]
n_w = [0, 0, 1.0] # Rotate to the world frame
width = radius/10
p1 = Point3f(O + width*n_w)
p2 = Point3f(O - width*n_w)
Makie.GeometryBasics.Cylinder(p1, p2, radius)
end
mesh!(scene, thing; color, specular = Vec3f(1.5), shininess=20f0, diffuse=Vec3f(1))
false
end

function perp(r)
if r[1] == 0
return [1, 0]
Expand Down
2 changes: 1 addition & 1 deletion src/Multibody.jl
Original file line number Diff line number Diff line change
Expand Up @@ -358,7 +358,7 @@ include("joints.jl")
export SphericalSpherical, UniversalSpherical, JointUSR, JointRRR, PrismaticConstraint
include("fancy_joints.jl")

export RollingWheelJoint, RollingWheel, SlipWheelJoint, SlippingWheel, RollingWheelSet, RollingWheelSetJoint, RollingConstraintVerticalWheel
export OneDOFRollingWheelJoint, RollingWheel, SlipWheelJoint, SlippingWheel, RollingWheelSet, RollingWheelSetJoint, RollingConstraintVerticalWheel
include("wheels.jl")

export Spring, Damper, SpringDamperParallel, Torque, Force, WorldForce, WorldTorque
Expand Down
2 changes: 1 addition & 1 deletion src/PlanarMechanics/PlanarMechanics.jl
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ export Frame, FrameResolve, PartialTwoFrames, ZeroPosition, ori_2d
include("utils.jl")

export Fixed, Body, BodyShape, FixedTranslation, Spring, Damper, SpringDamper
export SlipBasedWheelJoint, SimpleWheel, IdealPlanetary, DifferentialGear
export SlipBasedWheelJoint, SimpleWheel, IdealPlanetary, DifferentialGear, OneDOFSlippingWheelJoint, OneDOFRollingWheelJoint
include("components.jl")

export Revolute, Prismatic
Expand Down
242 changes: 238 additions & 4 deletions src/PlanarMechanics/components.jl
Original file line number Diff line number Diff line change
Expand Up @@ -170,11 +170,12 @@ A fixed translation between two components (rigid rod)
- `frame_b` [Frame](@ref) Coordinate system fixed to the component with one cut-force and cut-torque

"""
@component function FixedTranslation(; name, r = [1.0, 0], radius = 0.1, render = true)
@component function FixedTranslation(; name, r = [1.0, 0], radius = 0.1, render = true, color=Multibody.purple)
pars = @parameters begin
r[1:2] = r, [description = "Fixed x,y-length of the rod resolved w.r.t to body frame_a at phi = 0"]
radius = radius, [description = "Radius of the rod in animations"]
render = render, [description = "Render the rod in animations"]
color = color, [description = "Color of the rod in animations"]
end

systems = @named begin
Expand All @@ -189,8 +190,7 @@ A fixed translation between two components (rigid rod)

# Calculations from begin blocks
# r = collect(r)
R = [cos(phi) -sin(phi);
sin(phi) cos(phi)]
R = ori_2d(phi)
r0 = R * r

equations = Equation[
Expand Down Expand Up @@ -787,10 +787,244 @@ In addition there is an input `dynamicLoad` for a dynamic component of the norma
]

return System(equations, t, vars, pars; name, systems)


end


"""
OneDOFSlippingWheelJoint(;
name,
vAdhesion_min,
vSlide_min,
sAdhesion,
sSlide,
mu_A,
mu_S,
render = true,
color = [0.1, 0.1, 0.1, 1],
z = 0,
diameter = 0.1,
width = diameter * 0.6,
radius = 0.1,
phi_roll = nothing,
w_roll = nothing,
)

A simplified wheel joint that constrains motion to only the x-axis (forward/backward) with slip-dependent friction.

Unlike `SlipBasedWheelJoint` which allows motion in any direction based on the frame orientation, this joint:
- Fixes the driving direction to the global x-axis `[1, 0]`
- Constrains the y-position to equal the wheel radius (ground contact)
- Eliminates lateral velocity and forces

This makes it suitable for simplified 1-DOF models like a planar Segway where the wheel should only move forward/backward.

The slip-dependent friction model is the same as `SlipBasedWheelJoint`:
- For low velocities, a dry-friction model is used
- The normal load is determined automatically from constraint dynamics (mass and gravity of attached body)
- Friction transitions smoothly between adhesion and sliding regimes

# Parameters:
- `radius`: Wheel radius (also determines y-position constraint)
- `mu_A`: Friction coefficient at adhesion (peak traction)
- `mu_S`: Friction coefficient at sliding (saturated traction)
- `sAdhesion`: Adhesion slip ratio threshold
- `sSlide`: Sliding slip ratio threshold
- `vAdhesion_min`: Minimum adhesion velocity (for low-speed stability)
- `vSlide_min`: Minimum sliding velocity (for low-speed stability)

# Connectors:
- `frame_a` (Frame) Coordinate system fixed to the wheel. Attach a body here for mass/inertia.

# Example
```julia
wheelJoint = OneDOFSlippingWheelJoint(
radius = 0.025,
mu_A = 1,
mu_S = 0.7,
sAdhesion = 0.04,
sSlide = 0.12,
vAdhesion_min = 0.05,
vSlide_min = 0.15,
)
```
"""
@component function OneDOFSlippingWheelJoint(;
name,
vAdhesion_min,
vSlide_min,
sAdhesion,
sSlide,
mu_A,
mu_S,
render = true,
color = [0.1, 0.1, 0.1, 1],
x = nothing,
v = nothing,
z = 0,
diameter = 0.1,
width = diameter * 0.6,
radius = 0.1,
phi_roll = nothing,
w_roll = nothing,
)
systems = @named begin
frame_a = Frame()
end
pars = @parameters begin
vAdhesion_min = vAdhesion_min, [description = "Minimum adhesion velocity"]
vSlide_min = vSlide_min, [description = "Minimum sliding velocity"]
sAdhesion = sAdhesion, [description = "Adhesion slippage"]
sSlide = sSlide, [description = "Sliding slippage"]
mu_A = mu_A, [description = "Friction coefficient at adhesion"]
mu_S = mu_S, [description = "Friction coefficient at sliding"]
render = render, [description = "Render the wheel in animations"]
color[1:4] = color, [description = "Color of the wheel in animations"]
z = z, [description = "Position z of the body"]
diameter = diameter, [description = "Diameter of the rims"]
width = width, [description = "Width of the wheel"]
radius = radius, [description = "Radius of the wheel"]
end

vars = @variables begin
(phi_roll(t) = phi_roll), [guess=0, description="Wheel rolling angle"]
(w_roll(t) = w_roll), [guess=0, description="Wheel rolling velocity"]
x(t)=x, [description = "Position in x direction"]
v(t)=v, [guess=0, description="Velocity in longitudinal (x) direction"]
v_slip_long(t), [guess=0, description="Slip velocity in longitudinal direction"]
v_slip(t), [description="Slip velocity magnitude"]
f(t), [description="Total traction force magnitude"]
f_long(t), [description="Longitudinal friction force"]
f_n(t), [guess=10.0, description="Normal constraint force (determined by dynamics)"]
vAdhesion(t), [description="Adhesion velocity threshold"]
vSlide(t), [description="Sliding velocity threshold"]
end

equations = Equation[
# Velocity in x-direction (fixed driving direction along global x-axis)
x ~ frame_a.x
v ~ D(x)

# Wheel angle coupling
phi_roll ~ -frame_a.phi
w_roll ~ D(phi_roll)

# Longitudinal slip (difference between ground velocity and wheel surface velocity)
v_slip_long ~ v - radius * w_roll
v_slip ~ abs(v_slip_long) + 0.0001

# Slip-dependent friction (like 3D SlipWheelJoint)
# f_n is the normal force, determined by constraint dynamics when a body is attached
vAdhesion ~ max(vAdhesion_min, sAdhesion * abs(radius * w_roll))
vSlide ~ max(vSlide_min, sSlide * abs(radius * w_roll))
f ~ f_n * limit_S_triple(vAdhesion, vSlide, mu_A, mu_S, v_slip)
f_long ~ - f * v_slip_long / v_slip

# Frame forces from contact
frame_a.fx ~ f_long
frame_a.fy ~ f_n
frame_a.tau ~ radius * f_long

# Position constraint
frame_a.y ~ radius # Wheel center at ground level + radius
]

return System(equations, t, vars, pars; name, systems)
end


"""
OneDOFRollingWheelJoint(;
name,
radius = 0.1,
render = true,
color = [0.1, 0.1, 0.1, 1],
z = 0,
diameter = 0.1,
width = diameter * 0.6,
phi_roll = nothing,
w_roll = nothing,
)

An ideal rolling wheel joint constrained to move only along the x-axis (forward/backward) without slip.

Unlike `OneDOFSlippingWheelJoint` which uses slip-dependent friction, this joint enforces a perfect rolling constraint:
`D(x) = radius * w_roll` (ground velocity equals wheel surface velocity).

This is suitable for simplified models where:
- Tire slip can be neglected
- The kinematic relationship between wheel rotation and translation is exact
- No friction parameters need to be tuned

# Parameters:
- `radius`: Wheel radius (determines y-position constraint and rolling kinematics)

# Connectors:
- `frame_a` (Frame) Coordinate system fixed to the wheel. Attach a revolute joint and a body inertia here.

# Example
```julia
wheelJoint = OneDOFRollingWheelJoint(radius = 0.025)
```
"""
@component function OneDOFRollingWheelJoint(;
name,
radius = 0.1,
render = true,
color = [0.1, 0.1, 0.1, 1],
z = 0,
x = nothing,
x0 = 0,
v = nothing,
diameter = 0.1,
width = diameter * 0.6,
phi_roll = nothing,
w_roll = nothing,
)
systems = @named begin
frame_a = Frame()
# flange_a = Rotational.Flange()
end
pars = @parameters begin
render = render, [description = "Render the wheel in animations"]
color[1:4] = color, [description = "Color of the wheel in animations"]
z = z, [description = "Position z of the body"]
x0 = x0, [description = "x position at zero roll angle"]
diameter = diameter, [description = "Diameter of the rims"]
width = width, [description = "Width of the wheel"]
radius = radius, [description = "Radius of the wheel"]
end

vars = @variables begin
(x(t) = x), [description = "Position x of the body"]
(v(t) = v), [description = "Velocity x of the body"]
# (a(t))
(phi_roll(t) = phi_roll), [guess=0, description="Wheel rolling angle"]
(w_roll(t) = w_roll), [guess=0, description="Wheel rolling velocity"]
end

equations = Equation[
# Wheel angle coupling to flange
phi_roll ~ -frame_a.phi
w_roll ~ D(phi_roll)

x ~ frame_a.x
v ~ D(x)
# a ~ D(v)
# Ideal rolling constraint: ground velocity = wheel surface velocity
x ~ radius * phi_roll + x0
# v ~ radius * w_roll

# Force/torque relationship (from constraint)
frame_a.tau ~ radius * frame_a.fx

# 1-DOF constraints
frame_a.y ~ radius # Wheel center at ground level + radius
]

return System(equations, t, vars, pars; name, systems)
end


"""
IdealPlanetary(; name, ratio = 2)
Expand Down
Loading
Loading