Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fixes for 0.7 #451

Merged
merged 30 commits into from
Jul 9, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
30 commits
Select commit Hold shift + click to select a range
63ae8fe
Require Julia 0.7.
tkoolen Jul 3, 2018
025cb31
Fix deprecations
femtocleaner[bot] Jul 2, 2018
3ee4f87
Use nightly on travis.
tkoolen Jul 3, 2018
f05a806
Adapt to sum change.
tkoolen Jul 3, 2018
75e177c
showcompact fixes.
tkoolen Jul 3, 2018
20dc4dc
Fix broadcast usage (Ref).
tkoolen Jul 3, 2018
67b7873
expm -> exp in a test.
tkoolen Jun 29, 2018
6ed5a7b
Remove Compat usages.
tkoolen Jul 3, 2018
95d71df
Disable ForwardDiff Hessian test for now (excessive compilation time).
tkoolen Jul 3, 2018
039ab37
Adapt to mapreduce change.
tkoolen Jul 3, 2018
33f7faa
broadcastable fixes
tkoolen Jul 3, 2018
b4f2b45
full -> Matrix
tkoolen Jul 3, 2018
1932dbe
Adapt to mapslices change.
tkoolen Jul 3, 2018
964610a
Update notebook testing.
tkoolen Jul 3, 2018
4b195f8
travis updates.
tkoolen Jul 3, 2018
fb887ab
Notebook deprecation fixes.
tkoolen Jul 3, 2018
1011f3a
Stop using Nullable for RigidBody inertia field.
tkoolen Jul 3, 2018
cfe68e0
Adapt to At_mul_B change.
tkoolen Jul 3, 2018
bec8c7f
Update Pkg usage in docs.
tkoolen Jul 3, 2018
160d297
Skip notebooks that are broken due to dependencies. Rename Jacobian n…
tkoolen Jul 3, 2018
123c601
Require versions that support 0.7.
tkoolen Jul 3, 2018
2ed0a11
Use undef in benchmarks.
tkoolen Jul 3, 2018
d73754e
Fix deprecations in notebooks.
tkoolen Jul 3, 2018
b0bbea2
Use Profile in benchmarks.
tkoolen Jul 3, 2018
a0843c9
Increase tolerance a little.
tkoolen Jul 4, 2018
fe3233a
Reimplement colwise.
tkoolen Jul 4, 2018
57b0501
Update benchmark results.
tkoolen Jul 4, 2018
21e8624
Require StaticArrays 0.8.2 for hcat fix.
tkoolen Jul 9, 2018
20cb32f
Fix eye, zeros deprecations for StaticArrays.
tkoolen Jul 4, 2018
ea6c2aa
eye -> one for Quat
tkoolen Jul 9, 2018
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
11 changes: 5 additions & 6 deletions .travis.yml
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
language: julia
os:
- linux
# - osx
- osx
julia:
- 0.6
- nightly
branches:
only:
- master
Expand All @@ -13,9 +13,8 @@ notifications:
before_install:
- if [[ -a .git/shallow ]]; then git fetch --unshallow; fi
script:
- julia -e 'ENV["PYTHON"]=""; Pkg.clone(pwd()); Pkg.build("RigidBodyDynamics"); Pkg.test("RigidBodyDynamics"; coverage=true)'
# - julia -e 'ENV["PYTHON"]=""; Pkg.clone(pwd()); Pkg.build("RigidBodyDynamics"); Pkg.test("RigidBodyDynamics"; coverage=true)'
# Note: PYTHON env is to ensure that PyCall uses the Conda.jl package's Miniconda distribution within Julia. Otherwise the sympy Python module won't be installed/imported properly.
after_success:
- julia -e 'cd(Pkg.dir("RigidBodyDynamics")); Pkg.add("Coverage"); using Coverage; Codecov.submit(Codecov.process_folder())'
- julia -e 'Pkg.add("Documenter")'
- julia -e 'cd(Pkg.dir("RigidBodyDynamics")); include(joinpath("docs", "make.jl"))'
- julia -e 'import Pkg; Pkg.add("Documenter"); include("docs/make.jl")'
- julia -e 'import Pkg; Pkg.add("Coverage"); using Coverage; Codecov.submit(Codecov.process_folder())'
10 changes: 4 additions & 6 deletions REQUIRE
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
julia 0.6
StaticArrays 0.6.2
Rotations 0.6.0
TypeSortedCollections 0.4.0
julia 0.7
StaticArrays 0.8.2
Rotations 0.7.1
TypeSortedCollections 0.5.0
LightXML 0.4.0
DocStringExtensions 0.4.1
Compat 0.59 # for undef
Reexport 0.0.3
LoopThrottle 0.0.1
Nullables 0.0.5 # TODO: remove after dropping 0.6 support
46 changes: 22 additions & 24 deletions docs/src/benchmarks.md
Original file line number Diff line number Diff line change
Expand Up @@ -17,16 +17,14 @@ Note that results on Travis builds are **not at all** representative because of
Output of `versioninfo()`:

```
Julia Version 0.6.2
Commit d386e40c17 (2017-12-13 18:08 UTC)
Julia Version 0.7.0-beta.133
Commit 60174a9 (2018-07-03 20:03 UTC)
Platform Info:
OS: Linux (x86_64-pc-linux-gnu)
OS: Linux (x86_64-linux-gnu)
CPU: Intel(R) Core(TM) i7-6950X CPU @ 3.00GHz
WORD_SIZE: 64
BLAS: libopenblas (USE64BITINT DYNAMIC_ARCH NO_AFFINITY Haswell)
LAPACK: libopenblas64_
LIBM: libopenlibm
LLVM: libLLVM-3.9.1 (ORCJIT, broadwell)
LLVM: libLLVM-6.0.0 (ORCJIT, broadwell)
```

Mass matrix:
Expand All @@ -35,10 +33,10 @@ Mass matrix:
memory estimate: 0 bytes
allocs estimate: 0
--------------
minimum time: 9.697 μs (0.00% GC)
median time: 10.003 μs (0.00% GC)
mean time: 10.076 μs (0.00% GC)
maximum time: 47.473 μs (0.00% GC)
minimum time: 7.577 μs (0.00% GC)
median time: 8.250 μs (0.00% GC)
mean time: 8.295 μs (0.00% GC)
maximum time: 45.776 μs (0.00% GC)
```

Mass matrix and Jacobian from left hand to right foot:
Expand All @@ -47,10 +45,10 @@ Mass matrix and Jacobian from left hand to right foot:
memory estimate: 0 bytes
allocs estimate: 0
--------------
minimum time: 10.426 μs (0.00% GC)
median time: 10.737 μs (0.00% GC)
mean time: 10.754 μs (0.00% GC)
maximum time: 49.830 μs (0.00% GC)
minimum time: 8.070 μs (0.00% GC)
median time: 8.461 μs (0.00% GC)
mean time: 8.801 μs (0.00% GC)
maximum time: 45.001 μs (0.00% GC)
```

Note the low additional cost of computing a Jacobian when the mass matrix is already computed. This is because RigidBodyDynamics.jl caches intermediate computation results.
Expand All @@ -61,20 +59,20 @@ Inverse dynamics:
memory estimate: 0 bytes
allocs estimate: 0
--------------
minimum time: 10.988 μs (0.00% GC)
median time: 11.294 μs (0.00% GC)
mean time: 11.383 μs (0.00% GC)
maximum time: 33.164 μs (0.00% GC)
minimum time: 8.907 μs (0.00% GC)
median time: 9.341 μs (0.00% GC)
mean time: 9.633 μs (0.00% GC)
maximum time: 40.387 μs (0.00% GC)
```

Forward dynamics:

```
memory estimate: 64 bytes
allocs estimate: 3
memory estimate: 0 bytes
allocs estimate: 0
--------------
minimum time: 39.481 μs (0.00% GC)
median time: 54.874 μs (0.00% GC)
mean time: 55.230 μs (0.00% GC)
maximum time: 594.235 μs (0.00% GC)
minimum time: 32.671 μs (0.00% GC)
median time: 38.204 μs (0.00% GC)
mean time: 38.177 μs (0.00% GC)
maximum time: 188.785 μs (0.00% GC)
```
6 changes: 3 additions & 3 deletions docs/src/index.md
Original file line number Diff line number Diff line change
Expand Up @@ -39,16 +39,16 @@ Download links and more detailed instructions are available on the [Julia](http:
Do **not** use `apt-get` or `brew` to install Julia, as the versions provided by these package managers tend to be out of date.

### Installing RigidBodyDynamics
To install the latest tagged release of RigidBodyDynamics, simply run
To install the latest tagged release of RigidBodyDynamics, start Julia and enter `Pkg` mode by pressing `]`, and then simply run

```julia
Pkg.add("RigidBodyDynamics") 
add RigidBodyDynamics
```

To check out the master branch and work on the bleeding edge (generally, not recommended), additionally run

```julia
Pkg.checkout("RigidBodyDynamics")
develop RigidBodyDynamics
```

## About
Expand Down
5 changes: 3 additions & 2 deletions notebooks/Derivatives and gradients using ForwardDiff.ipynb
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,8 @@
"source": [
"using RigidBodyDynamics\n",
"using ForwardDiff\n",
"using Compat.Test\n",
"using Test\n",
"using Random\n",
"srand(1);"
]
},
Expand Down Expand Up @@ -418,7 +419,7 @@
" \n",
" # compute momentum and store it in `out`\n",
" m = momentum(state)\n",
" copy!(out, [angular(m); linear(m)])\n",
" copyto!(out, [angular(m); linear(m)])\n",
"end"
]
},
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
"cell_type": "markdown",
"metadata": {},
"source": [
"We'll be using `RigidBodyDynamics` and `StaticArrays` for the simulation part."
"We'll be using `LinearAlgebra`, `RigidBodyDynamics`, and `StaticArrays` for the simulation part."
]
},
{
Expand All @@ -34,6 +34,7 @@
"metadata": {},
"outputs": [],
"source": [
"using LinearAlgebra\n",
"using RigidBodyDynamics\n",
"using StaticArrays"
]
Expand Down Expand Up @@ -160,23 +161,23 @@
"source": [
"# link1 and joint1\n",
"joint1 = Joint(\"joint1\", Revolute(axis))\n",
"inertia1 = SpatialInertia(CartesianFrame3D(\"inertia1_centroidal\"), I_1*axis*axis', zeros(SVector{3, T}), m_1)\n",
"inertia1 = SpatialInertia(CartesianFrame3D(\"inertia1_centroidal\"), I_1*axis*axis', zero(SVector{3, T}), m_1)\n",
"link1 = RigidBody(inertia1)\n",
"before_joint1_to_world = eye(Transform3D, frame_before(joint1), default_frame(world))\n",
"c1_to_joint = Transform3D(inertia1.frame, frame_after(joint1), SVector(c_1, 0, 0))\n",
"attach!(fourbar, world, link1, joint1, joint_pose = before_joint1_to_world, successor_pose = c1_to_joint)\n",
"\n",
"# link2 and joint2\n",
"joint2 = Joint(\"joint2\", Revolute(axis))\n",
"inertia2 = SpatialInertia(CartesianFrame3D(\"inertia2_centroidal\"), I_2*axis*axis', zeros(SVector{3, T}), m_2)\n",
"inertia2 = SpatialInertia(CartesianFrame3D(\"inertia2_centroidal\"), I_2*axis*axis', zero(SVector{3, T}), m_2)\n",
"link2 = RigidBody(inertia2)\n",
"before_joint2_to_after_joint1 = Transform3D(frame_before(joint2), frame_after(joint1), SVector(l_1, 0., 0.))\n",
"c2_to_joint = Transform3D(inertia2.frame, frame_after(joint2), SVector(c_2, 0, 0))\n",
"attach!(fourbar, link1, link2, joint2, joint_pose = before_joint2_to_after_joint1, successor_pose = c2_to_joint)\n",
"\n",
"# link3 and joint3\n",
"joint3 = Joint(\"joint3\", Revolute(axis))\n",
"inertia3 = SpatialInertia(CartesianFrame3D(\"inertia3_centroidal\"), I_3*axis*axis', zeros(SVector{3, T}), m_3)\n",
"inertia3 = SpatialInertia(CartesianFrame3D(\"inertia3_centroidal\"), I_3*axis*axis', zero(SVector{3, T}), m_3)\n",
"link3 = RigidBody(inertia3)\n",
"before_joint3_to_world = Transform3D(frame_before(joint3), default_frame(world), SVector(l_0, 0., 0.))\n",
"c3_to_joint = Transform3D(inertia3.frame, frame_after(joint3), SVector(c_3, 0, 0))\n",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
"using StaticArrays\n",
"\n",
"# Fix the random seed, so we get repeatable results\n",
"using Random\n",
"srand(42)"
]
},
Expand Down Expand Up @@ -337,9 +338,9 @@
"source": [
"# Choose a desired location. We'll move the tip of the arm to\n",
"# [0.5, 0, 2]\n",
"desired = Point3D(root_frame(mechanism), 0.5, 0, 2)\n",
"desired_tip_location = Point3D(root_frame(mechanism), 0.5, 0, 2)\n",
"# Run the IK, updating `state` in place\n",
"jacobian_transpose_ik!(state, body, point, desired)"
"jacobian_transpose_ik!(state, body, point, desired_tip_location)"
]
},
{
Expand Down Expand Up @@ -391,7 +392,7 @@
"qs = typeof(configuration(state))[]\n",
"\n",
"# Vary the desired x position from -1 to 1\n",
"for x in linspace(-1, 1, 100)\n",
"for x in range(-1, stop=1, length=100)\n",
" desired = Point3D(root_frame(mechanism), x, 0, 2)\n",
" jacobian_transpose_ik!(state, body, point, desired)\n",
" push!(qs, copy(configuration(state)))\n",
Expand All @@ -416,7 +417,7 @@
],
"source": [
"#NBSKIP\n",
"ts = collect(linspace(0, 1, length(qs)))\n",
"ts = collect(range(0, stop=1, length=length(qs)))\n",
"setanimation!(vis, ts, qs)"
]
},
Expand Down Expand Up @@ -482,7 +483,7 @@
"#NBSKIP\n",
"\n",
"# Draw the circle in the viewer\n",
"θ = repeat(linspace(0, 2π, 100), inner=(2,))[2:end]\n",
"θ = repeat(linspace(0, stop=2π, length=100), inner=(2,))[2:end]\n",
"cx, cy, cz = circle_origin\n",
"geometry = PointCloud(Point.(cx .+ radius .* sin.(θ), cy, cz .+ 0.5 .* cos.(θ)))\n",
"setobject!(vis[:circle], LineSegments(geometry, LineBasicMaterial()))"
Expand Down
11 changes: 6 additions & 5 deletions notebooks/Quickstart - double pendulum.ipynb
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
"outputs": [],
"source": [
"using RigidBodyDynamics\n",
"using LinearAlgebra\n",
"using StaticArrays"
]
},
Expand Down Expand Up @@ -94,7 +95,7 @@
"c_1 = -0.5 # center of mass location with respect to joint axis\n",
"m_1 = 1. # mass\n",
"frame1 = CartesianFrame3D(\"upper_link\") # the reference frame in which the spatial inertia will be expressed\n",
"inertia1 = SpatialInertia(frame1, I_1 * axis * axis.', m_1 * SVector(0, 0, c_1), m_1)"
"inertia1 = SpatialInertia(frame1, I_1 * axis * axis', m_1 * SVector(0, 0, c_1), m_1)"
]
},
{
Expand Down Expand Up @@ -255,7 +256,7 @@
"I_2 = 0.333 # moment of inertia about joint axis\n",
"c_2 = -0.5 # center of mass location with respect to joint axis\n",
"m_2 = 1. # mass\n",
"inertia2 = SpatialInertia(CartesianFrame3D(\"lower_link\"), I_2 * axis * axis.', m_2 * SVector(0, 0, c_2), m_2)\n",
"inertia2 = SpatialInertia(CartesianFrame3D(\"lower_link\"), I_2 * axis * axis', m_2 * SVector(0, 0, c_2), m_2)\n",
"lowerlink = RigidBody(inertia2)\n",
"elbow = Joint(\"elbow\", Revolute(axis))\n",
"before_elbow_to_after_shoulder = Transform3D(frame_before(elbow), frame_after(shoulder), SVector(0, 0, l_1))\n",
Expand Down Expand Up @@ -464,7 +465,7 @@
}
],
"source": [
"transform(state, Point3D(frame_after(elbow), zeros(SVector{3})), default_frame(world))"
"transform(state, Point3D(frame_after(elbow), zero(SVector{3})), default_frame(world))"
]
},
{
Expand Down Expand Up @@ -627,8 +628,8 @@
],
"source": [
"v̇ = similar(velocity(state)) # the joint acceleration vector, i.e., the time derivative of the joint velocity vector v\n",
"v̇[shoulder][:] = 1\n",
"v̇[elbow][:] = 2\n",
"v̇[shoulder][1] = 1\n",
"v̇[elbow][1] = 2\n",
"inverse_dynamics(state, v̇)"
]
},
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -252,7 +252,7 @@
}
],
"source": [
"using Compat.Test\n",
"using Test\n",
"@test (2.6 - 0.7 - 1.9) ∈ i"
]
},
Expand Down
4 changes: 2 additions & 2 deletions notebooks/Symbolic double pendulum.ipynb
Original file line number Diff line number Diff line change
Expand Up @@ -94,14 +94,14 @@
"world = root_body(double_pendulum) # the fixed 'world' rigid body\n",
"\n",
"# Attach the first (upper) link to the world via a revolute joint named 'shoulder'\n",
"inertia1 = SpatialInertia(CartesianFrame3D(\"upper_link\"), I_1 * axis * axis.', m_1 * SVector(zero(T), zero(T), c_1), m_1)\n",
"inertia1 = SpatialInertia(CartesianFrame3D(\"upper_link\"), I_1 * axis * axis', m_1 * SVector(zero(T), zero(T), c_1), m_1)\n",
"body1 = RigidBody(inertia1)\n",
"joint1 = Joint(\"shoulder\", Revolute(axis))\n",
"joint1_to_world = eye(Transform3D{T}, frame_before(joint1), default_frame(world))\n",
"attach!(double_pendulum, world, body1, joint1, joint_pose = joint1_to_world)\n",
"\n",
"# Attach the second (lower) link to the world via a revolute joint named 'elbow'\n",
"inertia2 = SpatialInertia(CartesianFrame3D(\"lower_link\"), I_2 * axis * axis.', m_2 * SVector(zero(T), zero(T), c_2), m_2)\n",
"inertia2 = SpatialInertia(CartesianFrame3D(\"lower_link\"), I_2 * axis * axis', m_2 * SVector(zero(T), zero(T), c_2), m_2)\n",
"body2 = RigidBody(inertia2)\n",
"joint2 = Joint(\"elbow\", Revolute(axis))\n",
"joint2_to_body1 = Transform3D(frame_before(joint2), default_frame(body1), SVector(zero(T), zero(T), l_1))\n",
Expand Down
7 changes: 4 additions & 3 deletions perf/runbenchmarks.jl
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
using RigidBodyDynamics
using Compat
using Compat.Random
using Random
using Profile
using BenchmarkTools

const ScalarType = Float64
Expand Down Expand Up @@ -30,7 +30,8 @@ function create_benchmark_suite()
rfoot = findbody(mechanism, "r_foot")
lhand = findbody(mechanism, "l_hand")
p = path(mechanism, rfoot, lhand)
jac = GeometricJacobian(default_frame(lhand), default_frame(rfoot), root_frame(mechanism), Matrix{ScalarType}(3, nv), Matrix{ScalarType}(3, nv))
jac = GeometricJacobian(default_frame(lhand), default_frame(rfoot), root_frame(mechanism),
Matrix{ScalarType}(undef, 3, nv), Matrix{ScalarType}(undef, 3, nv))

suite["mass_matrix"] = @benchmarkable(begin
setdirty!($state)
Expand Down
6 changes: 2 additions & 4 deletions src/RigidBodyDynamics.jl
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,8 @@ __precompile__()

module RigidBodyDynamics

using Compat
using Compat.Random
using Compat.LinearAlgebra
using Nullables
using Random
using LinearAlgebra
using StaticArrays
using Rotations
using TypeSortedCollections
Expand Down
3 changes: 1 addition & 2 deletions src/contact.jl
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
module Contact

using Compat
using Compat.LinearAlgebra
using LinearAlgebra
using RigidBodyDynamics.Spatial
using StaticArrays

Expand Down
Loading