Skip to content

Commit

Permalink
Fix inner constructor deprecation warnings.
Browse files Browse the repository at this point in the history
Based on JuliaArrays/StaticArrays.jl#107 (comment).

fix mistake in TreeVertex constructor
  • Loading branch information
tkoolen committed Feb 21, 2017
1 parent 1e1b494 commit 3b12c91
Show file tree
Hide file tree
Showing 10 changed files with 52 additions and 38 deletions.
2 changes: 1 addition & 1 deletion src/cache_element.jl
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
type CacheElement{T}
dirty::Bool
data::T
CacheElement() = new(true)
(::Type{CacheElement{T}}){T}() = new{T}(true)
end

@inline function update!{T}(element::CacheElement{T}, data::T)
Expand Down
4 changes: 2 additions & 2 deletions src/dynamics_result.jl
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ type DynamicsResult{M<:Number, T<:Number}
z::Vector{T}
Y::Matrix{T}

function DynamicsResult(mechanism::Mechanism{M})
function (::Type{DynamicsResult{M, T}}){M<:Number, T<:Number}(mechanism::Mechanism{M})
nq = num_positions(mechanism)
nv = num_velocities(mechanism)
nconstraints = isempty(mechanism.nonTreeEdges)? 0 : sum(num_constraints, edge.joint for edge in mechanism.nonTreeEdges)
Expand All @@ -43,7 +43,7 @@ type DynamicsResult{M<:Number, T<:Number}
z = Vector{T}(nv)
Y = Matrix{T}(nconstraints, nv)

new(massMatrix, dynamicsBias, constraintJacobian, constraintBias, v̇, λ, accelerations, jointWrenches, L, A, z, Y)
new{M, T}(massMatrix, dynamicsBias, constraintJacobian, constraintBias, v̇, λ, accelerations, jointWrenches, L, A, z, Y)
end
end

Expand Down
21 changes: 16 additions & 5 deletions src/frames.jl
Original file line number Diff line number Diff line change
Expand Up @@ -75,9 +75,17 @@ immutable Transform3D{T<:Number}
rot::RotMatrix3{T}
trans::SVector{3, T}

Transform3D(from::CartesianFrame3D, to::CartesianFrame3D, rot::Rotation{3, T}, trans::SVector{3, T}) = new(from, to, rot, trans)
Transform3D(from::CartesianFrame3D, to::CartesianFrame3D) = new(from, to, eye(RotMatrix3{T}), zeros(SVector{3, T}))
Transform3D(frame::CartesianFrame3D) = new(frame, frame, eye(RotMatrix3{T}), zeros(SVector{3, T}))
function (::Type{Transform3D{T}}){T<:Number}(from::CartesianFrame3D, to::CartesianFrame3D, rot::Rotation{3, T}, trans::SVector{3, T})
new{T}(from, to, rot, trans)
end

function (::Type{Transform3D{T}}){T<:Number}(from::CartesianFrame3D, to::CartesianFrame3D)
new{T}(from, to, eye(RotMatrix3{T}), zeros(SVector{3, T}))
end

function (::Type{Transform3D{T}}){T<:Number}(frame::CartesianFrame3D)
new{T}(frame, frame, eye(RotMatrix3{T}), zeros(SVector{3, T}))
end
end
Transform3D{T}(from::CartesianFrame3D, to::CartesianFrame3D, rot::Rotation{3, T}, trans::SVector{3, T}) = Transform3D{T}(from, to, rot, trans)
Transform3D{T}(from::CartesianFrame3D, to::CartesianFrame3D, rot::Rotation{3, T}) = Transform3D{T}(from, to, rot, zeros(SVector{3, T}))
Expand Down Expand Up @@ -121,11 +129,14 @@ end
# whereas a Point3D is also translated
for VectorType in (:FreeVector3D, :Point3D)
@eval begin
type $VectorType{V <:AbstractVector}
type $VectorType{V<:AbstractVector}
frame::CartesianFrame3D
v::V

$VectorType(frame::CartesianFrame3D, v::V) = begin @boundscheck length(v) == 3; new(frame, v) end
function (::Type{$VectorType{V}}){V<:AbstractVector}(frame::CartesianFrame3D, v::V)
@boundscheck length(v) == 3
new{V}(frame, v)
end
end

$VectorType{V}(frame::CartesianFrame3D, v::V) = $VectorType{V}(frame, v)
Expand Down
4 changes: 2 additions & 2 deletions src/joint_types.jl
Original file line number Diff line number Diff line change
Expand Up @@ -240,7 +240,7 @@ immutable Prismatic{T<:Number} <: OneDegreeOfFreedomFixedAxis{T}
axis::SVector{3, T}
rotationFromZAligned::RotMatrix{3, T}

Prismatic(axis::SVector{3, T}) = new(axis, rotation_between(SVector(zero(T), zero(T), one(T)), axis))
(::Type{Prismatic{T}}){T<:Number}(axis::SVector{3, T}) = new{T}(axis, rotation_between(SVector(zero(T), zero(T), one(T)), axis))
end

"""
Expand Down Expand Up @@ -302,7 +302,7 @@ immutable Revolute{T<:Number} <: OneDegreeOfFreedomFixedAxis{T}
axis::SVector{3, T}
rotationFromZAligned::RotMatrix{3, T}

Revolute(axis::SVector{3, T}) = new(axis, rotation_between(SVector(zero(T), zero(T), one(T)), axis))
(::Type{Revolute{T}}){T<:Number}(axis::SVector{3, T}) = new{T}(axis, rotation_between(SVector(zero(T), zero(T), one(T)), axis))
end

"""
Expand Down
4 changes: 2 additions & 2 deletions src/mechanism.jl
Original file line number Diff line number Diff line change
Expand Up @@ -16,11 +16,11 @@ type Mechanism{T<:Number}
nonTreeEdges::Vector{NonTreeEdge{T}}
gravitationalAcceleration::FreeVector3D{SVector{3, T}} # TODO: consider removing

function Mechanism(rootBody::RigidBody{T}; gravity::SVector{3, T} = SVector(zero(T), zero(T), T(-9.81)))
function (::Type{Mechanism{T}}){T<:Number}(rootBody::RigidBody{T}; gravity::SVector{3, T} = SVector(zero(T), zero(T), T(-9.81)))
tree = Tree{RigidBody{T}, Joint{T}}(rootBody)
nonTreeEdges = Vector{NonTreeEdge{T}}()
gravitationalAcceleration = FreeVector3D(default_frame(rootBody), gravity)
new(toposort(tree), nonTreeEdges, gravitationalAcceleration)
new{T}(toposort(tree), nonTreeEdges, gravitationalAcceleration)
end
end

Expand Down
12 changes: 6 additions & 6 deletions src/mechanism_state.jl
Original file line number Diff line number Diff line change
Expand Up @@ -8,12 +8,12 @@ immutable JointState{X<:Number, M<:Number, C<:Number}
biasAcceleration::CacheElement{SpatialAcceleration{C}}
motionSubspace::CacheElement{MotionSubspace{C}}

function JointState(joint::Joint{M}, q::VectorSegment{X}, v::VectorSegment{X})
function (::Type{JointState{X, M, C}}){X<:Number, M<:Number, C<:Number}(joint::Joint{M}, q::VectorSegment{X}, v::VectorSegment{X})
jointTransform = CacheElement{Transform3D{C}}()
twist = CacheElement{Twist{C}}()
biasAcceleration = CacheElement{SpatialAcceleration{C}}()
motionSubspace = CacheElement{MotionSubspace{C}}()
new(joint, q, v, jointTransform, twist, biasAcceleration, motionSubspace)
new{X, M, C}(joint, q, v, jointTransform, twist, biasAcceleration, motionSubspace)
end
end
JointState{X, M}(joint::Joint{M}, q::VectorSegment{X}, v::VectorSegment{X}) = JointState{X, M, promote_type(M, X)}(joint, q, v)
Expand Down Expand Up @@ -46,7 +46,7 @@ immutable RigidBodyState{M<:Number, C<:Number}
inertia::CacheElement{SpatialInertia{C}}
crbInertia::CacheElement{SpatialInertia{C}}

function RigidBodyState(body::RigidBody{M}, isroot::Bool)
function (::Type{RigidBodyState{M, C}}){M<:Number, C<:Number}(body::RigidBody{M}, isroot::Bool)
transformToWorld = CacheElement{Transform3D{C}}()
twist = CacheElement{Twist{C}}()
biasAcceleration = CacheElement{SpatialAcceleration{C}}()
Expand All @@ -61,7 +61,7 @@ immutable RigidBodyState{M<:Number, C<:Number}
update!(biasAcceleration, zero(SpatialAcceleration{C}, frame, frame, frame))
end

new(body, transformToWorld, twist, biasAcceleration, motionSubspace, inertia, crbInertia)
new{M, C}(body, transformToWorld, twist, biasAcceleration, motionSubspace, inertia, crbInertia)
end
end

Expand Down Expand Up @@ -97,7 +97,7 @@ immutable MechanismState{X<:Number, M<:Number, C<:Number}
nonRootTopoSortedStateVertices::VectorSegment{TreeVertex{RigidBodyState{M, C}, JointState{X, M, C}}} # because of https://github.com/JuliaLang/julia/issues/14955
constraintJacobianStructure::SparseMatrixCSC{Int64,Int64} # TODO: consider just using a Vector{Vector{Pair{Int64, Int64}}}

function MechanismState(::Type{X}, mechanism::Mechanism{M})
function (::Type{MechanismState{X, M, C}}){X<:Number, M<:Number, C<:Number}(arg)
q = Vector{X}(num_positions(mechanism))
v = zeros(X, num_velocities(mechanism))
rootBodyState = RigidBodyState(root_body(mechanism), X, true)
Expand Down Expand Up @@ -125,7 +125,7 @@ immutable MechanismState{X<:Number, M<:Number, C<:Number}
end
vertices = toposort(tree)
constraintJacobianStructure = constraint_jacobian_structure(mechanism)
new(mechanism, q, v, vertices, view(vertices, 2 : length(vertices)), constraintJacobianStructure)
new{X, M, C}(mechanism, q, v, vertices, view(vertices, 2 : length(vertices)), constraintJacobianStructure)
end
end
MechanismState{X, M}(t::Type{X}, mechanism::Mechanism{M}) = MechanismState{X, M, promote_type(X, M)}(t, mechanism)
Expand Down
20 changes: 10 additions & 10 deletions src/ode_integrators.jl
Original file line number Diff line number Diff line change
Expand Up @@ -27,14 +27,14 @@ immutable ButcherTableau{N, T<:Number, L}
c::SVector{N, T}
explicit::Bool

function ButcherTableau(a::AbstractMatrix{T}, b::AbstractVector{T})
function (::Type{ButcherTableau{N, T, L}}){N, T<:Number, L}(a::AbstractMatrix{T}, b::AbstractVector{T})
@assert N > 0
@assert size(a, 1) == N
@assert size(a, 2) == N
@assert length(b) == N
c = vec(sum(a, 2))
explicit = all(triu(a) .== 0)
new(SMatrix{N, N}(a), SVector{N}(b), SVector{N}(c), explicit)
new{N, T, L}(SMatrix{N, N}(a), SVector{N}(b), SVector{N}(c), explicit)
end
end
ButcherTableau{T}(a::Matrix{T}, b::Vector{T}) = ButcherTableau{length(b), T, length(b)^2}(a, b)
Expand Down Expand Up @@ -79,11 +79,11 @@ type RingBufferStorage{T} <: OdeResultsSink
vs::Vector{Vector{T}}
lastIndex::Int64

function RingBufferStorage(n::Int64)
function (::Type{RingBufferStorage{T}}){T}(n::Int64)
ts = Vector{T}(n)
qs = [Vector{T}() for i in 1 : n]
vs = [Vector{T}() for i in 1 : n]
new(ts, qs, vs, 0)
new{T}(ts, qs, vs, 0)
end
end
Base.eltype{T}(storage::RingBufferStorage{T}) = T
Expand Down Expand Up @@ -117,11 +117,11 @@ type ExpandingStorage{T} <: OdeResultsSink
qs::Vector{Vector{T}}
vs::Vector{Vector{T}}

function ExpandingStorage(n::Int64)
function (::Type{ExpandingStorage{T}}){T}(n::Int64)
ts = Vector{T}(); sizehint!(ts, n)
qs = Vector{T}[]; sizehint!(qs, n)
vs = Vector{T}[]; sizehint!(vs, n)
new(ts, qs, vs)
new{T}(ts, qs, vs)
end
end
Base.eltype{T}(storage::ExpandingStorage{T}) = T
Expand All @@ -145,15 +145,15 @@ type MuntheKaasStageCache{N, T<:Number}
ϕstep::Vector{T} # local coordinates around q0 after complete step
vstep::Vector{T} # velocity after complete step

function MuntheKaasStageCache()
function (::Type{MuntheKaasStageCache{N, T}}){N, T<:Number}()
q0 = Vector{T}()
vs = SVector{N, Vector{T}}((Vector{T}() for i in 1 : N)...)
vds = SVector{N, Vector{T}}((Vector{T}() for i in 1 : N)...)
ϕs = SVector{N, Vector{T}}((Vector{T}() for i in 1 : N)...)
ϕds = SVector{N, Vector{T}}((Vector{T}() for i in 1 : N)...)
ϕstep = Vector{T}()
vstep = Vector{T}()
new(q0, vs, vds, ϕs, ϕds, ϕstep, vstep)
new{N, T}(q0, vs, vds, ϕs, ϕds, ϕstep, vstep)
end
end
set_num_positions!(cache::MuntheKaasStageCache, n::Int64) = resize!(cache.q0, n)
Expand Down Expand Up @@ -193,10 +193,10 @@ immutable MuntheKaasIntegrator{N, T<:Number, F, S<:OdeResultsSink, L}
sink::S
stages::MuntheKaasStageCache{N, T}

function MuntheKaasIntegrator(dynamics!::F, tableau::ButcherTableau{N, T, L}, sink::S)
function (::Type{MuntheKaasIntegrator{N, T, F, S, L}}){N, T<:Number, F, S<:OdeResultsSink, L}(dynamics!::F, tableau::ButcherTableau{N, T, L}, sink::S)
@assert isexplicit(tableau)
stages = MuntheKaasStageCache{N, T}()
new(dynamics!, tableau, sink, stages)
new{N, T, F, S, L}(dynamics!, tableau, sink, stages)
end
end

Expand Down
8 changes: 4 additions & 4 deletions src/rigid_body.jl
Original file line number Diff line number Diff line change
Expand Up @@ -13,14 +13,14 @@ type RigidBody{T<:Number}
frameDefinitions::Set{Transform3D{T}}

# inertia undefined; can be used for the root of a kinematic tree
function RigidBody(name::String)
function (::Type{RigidBody{T}}){T<:Number}(name::String)
frame = CartesianFrame3D(name)
new(name, Nullable{SpatialInertia{T}}(), Set([Transform3D{T}(frame)]))
new{T}(name, Nullable{SpatialInertia{T}}(), Set([Transform3D{T}(frame)]))
end

# other bodies
function RigidBody(name::String, inertia::SpatialInertia{T})
new(name, Nullable(inertia), Set([Transform3D{T}(inertia.frame)]))
function (::Type{RigidBody{T}}){T<:Number}(name::String, inertia::SpatialInertia{T})
new{T}(name, Nullable(inertia), Set([Transform3D{T}(inertia.frame)]))
end
end

Expand Down
8 changes: 4 additions & 4 deletions src/spatial.jl
Original file line number Diff line number Diff line change
Expand Up @@ -143,11 +143,11 @@ immutable GeometricJacobian{A<:AbstractMatrix}
angular::A
linear::A

function GeometricJacobian(body::CartesianFrame3D, base::CartesianFrame3D, frame::CartesianFrame3D, angular::A, linear::A)
function (::Type{GeometricJacobian{A}}){A<:AbstractMatrix}(body::CartesianFrame3D, base::CartesianFrame3D, frame::CartesianFrame3D, angular::A, linear::A)
@boundscheck size(angular, 1) == 3 || error("size mismatch")
@boundscheck size(linear, 1) == 3 || error("size mismatch")
@boundscheck size(angular, 2) == size(linear, 2) || error("size mismatch")
new(body, base, frame, angular, linear)
new{A}(body, base, frame, angular, linear)
end
end

Expand All @@ -157,11 +157,11 @@ for ForceSpaceMatrix in (:MomentumMatrix, :WrenchMatrix)
angular::A
linear::A

function $ForceSpaceMatrix(frame::CartesianFrame3D, angular::A, linear::A)
function (::Type{$ForceSpaceMatrix{A}}){A<:AbstractMatrix}(frame::CartesianFrame3D, angular::A, linear::A)
@assert size(angular, 1) == 3
@assert size(linear, 1) == 3
@assert size(angular, 2) == size(linear, 2)
new(frame, angular, linear)
new{A}(frame, angular, linear)
end
end
end
Expand Down
7 changes: 5 additions & 2 deletions src/tree.jl
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,11 @@ type TreeVertex{V, E}
children::Vector{TreeVertex{V, E}}
parentAndEdgeData::Nullable{Pair{TreeVertex{V, E}, E}}

TreeVertex(vertexData::V) = new(vertexData, [], Nullable{Pair{TreeVertex{V, E}, E}}())
TreeVertex{V, E}(vertexData::V, parent::TreeVertex{V, E}, edgeData::E) = new(vertexData, [], parent => edgeData)
(::Type{TreeVertex{V, E}}){V, E}(vertexData::V) = new{V, E}(vertexData, [], Nullable{Pair{TreeVertex{V, E}, E}}())

function (::Type{TreeVertex{V, E}}){V, E}(vertexData::V, parent::TreeVertex{V, E}, edgeData::E)
new{V, E}(vertexData, [], parent => edgeData)
end
end
TreeVertex{V, E}(vertexData::V, parent::TreeVertex{V, E}, edgeData::E) = TreeVertex{V, E}(vertexData, parent, edgeData)

Expand Down

0 comments on commit 3b12c91

Please sign in to comment.