Skip to content

Commit fb97f95

Browse files
authored
Merge pull request #451 from JuliaRobotics/tk/julia-0.7
Fixes for 0.7
2 parents 611aaf0 + ea6c2aa commit fb97f95

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

44 files changed

+254
-280
lines changed

.travis.yml

Lines changed: 5 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,9 @@
11
language: julia
22
os:
33
- linux
4-
# - osx
4+
- osx
55
julia:
6-
- 0.6
6+
- nightly
77
branches:
88
only:
99
- master
@@ -13,9 +13,8 @@ notifications:
1313
before_install:
1414
- if [[ -a .git/shallow ]]; then git fetch --unshallow; fi
1515
script:
16-
- julia -e 'ENV["PYTHON"]=""; Pkg.clone(pwd()); Pkg.build("RigidBodyDynamics"); Pkg.test("RigidBodyDynamics"; coverage=true)'
16+
# - julia -e 'ENV["PYTHON"]=""; Pkg.clone(pwd()); Pkg.build("RigidBodyDynamics"); Pkg.test("RigidBodyDynamics"; coverage=true)'
1717
# 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.
1818
after_success:
19-
- julia -e 'cd(Pkg.dir("RigidBodyDynamics")); Pkg.add("Coverage"); using Coverage; Codecov.submit(Codecov.process_folder())'
20-
- julia -e 'Pkg.add("Documenter")'
21-
- julia -e 'cd(Pkg.dir("RigidBodyDynamics")); include(joinpath("docs", "make.jl"))'
19+
- julia -e 'import Pkg; Pkg.add("Documenter"); include("docs/make.jl")'
20+
- julia -e 'import Pkg; Pkg.add("Coverage"); using Coverage; Codecov.submit(Codecov.process_folder())'

REQUIRE

Lines changed: 4 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,8 @@
1-
julia 0.6
2-
StaticArrays 0.6.2
3-
Rotations 0.6.0
4-
TypeSortedCollections 0.4.0
1+
julia 0.7
2+
StaticArrays 0.8.2
3+
Rotations 0.7.1
4+
TypeSortedCollections 0.5.0
55
LightXML 0.4.0
66
DocStringExtensions 0.4.1
7-
Compat 0.59 # for undef
87
Reexport 0.0.3
98
LoopThrottle 0.0.1
10-
Nullables 0.0.5 # TODO: remove after dropping 0.6 support

docs/src/benchmarks.md

Lines changed: 22 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -17,16 +17,14 @@ Note that results on Travis builds are **not at all** representative because of
1717
Output of `versioninfo()`:
1818

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

3230
Mass matrix:
@@ -35,10 +33,10 @@ Mass matrix:
3533
memory estimate: 0 bytes
3634
allocs estimate: 0
3735
--------------
38-
minimum time: 9.697 μs (0.00% GC)
39-
median time: 10.003 μs (0.00% GC)
40-
mean time: 10.076 μs (0.00% GC)
41-
maximum time: 47.473 μs (0.00% GC)
36+
minimum time: 7.577 μs (0.00% GC)
37+
median time: 8.250 μs (0.00% GC)
38+
mean time: 8.295 μs (0.00% GC)
39+
maximum time: 45.776 μs (0.00% GC)
4240
```
4341

4442
Mass matrix and Jacobian from left hand to right foot:
@@ -47,10 +45,10 @@ Mass matrix and Jacobian from left hand to right foot:
4745
memory estimate: 0 bytes
4846
allocs estimate: 0
4947
--------------
50-
minimum time: 10.426 μs (0.00% GC)
51-
median time: 10.737 μs (0.00% GC)
52-
mean time: 10.754 μs (0.00% GC)
53-
maximum time: 49.830 μs (0.00% GC)
48+
minimum time: 8.070 μs (0.00% GC)
49+
median time: 8.461 μs (0.00% GC)
50+
mean time: 8.801 μs (0.00% GC)
51+
maximum time: 45.001 μs (0.00% GC)
5452
```
5553

5654
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.
@@ -61,20 +59,20 @@ Inverse dynamics:
6159
memory estimate: 0 bytes
6260
allocs estimate: 0
6361
--------------
64-
minimum time: 10.988 μs (0.00% GC)
65-
median time: 11.294 μs (0.00% GC)
66-
mean time: 11.383 μs (0.00% GC)
67-
maximum time: 33.164 μs (0.00% GC)
62+
minimum time: 8.907 μs (0.00% GC)
63+
median time: 9.341 μs (0.00% GC)
64+
mean time: 9.633 μs (0.00% GC)
65+
maximum time: 40.387 μs (0.00% GC)
6866
```
6967

7068
Forward dynamics:
7169

7270
```
73-
memory estimate: 64 bytes
74-
allocs estimate: 3
71+
memory estimate: 0 bytes
72+
allocs estimate: 0
7573
--------------
76-
minimum time: 39.481 μs (0.00% GC)
77-
median time: 54.874 μs (0.00% GC)
78-
mean time: 55.230 μs (0.00% GC)
79-
maximum time: 594.235 μs (0.00% GC)
74+
minimum time: 32.671 μs (0.00% GC)
75+
median time: 38.204 μs (0.00% GC)
76+
mean time: 38.177 μs (0.00% GC)
77+
maximum time: 188.785 μs (0.00% GC)
8078
```

docs/src/index.md

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -39,16 +39,16 @@ Download links and more detailed instructions are available on the [Julia](http:
3939
Do **not** use `apt-get` or `brew` to install Julia, as the versions provided by these package managers tend to be out of date.
4040

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

4444
```julia
45-
Pkg.add("RigidBodyDynamics"
45+
add RigidBodyDynamics
4646
```
4747

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

5050
```julia
51-
Pkg.checkout("RigidBodyDynamics")
51+
develop RigidBodyDynamics
5252
```
5353

5454
## About

notebooks/Derivatives and gradients using ForwardDiff.ipynb

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,8 @@
1515
"source": [
1616
"using RigidBodyDynamics\n",
1717
"using ForwardDiff\n",
18-
"using Compat.Test\n",
18+
"using Test\n",
19+
"using Random\n",
1920
"srand(1);"
2021
]
2122
},
@@ -418,7 +419,7 @@
418419
" \n",
419420
" # compute momentum and store it in `out`\n",
420421
" m = momentum(state)\n",
421-
" copy!(out, [angular(m); linear(m)])\n",
422+
" copyto!(out, [angular(m); linear(m)])\n",
422423
"end"
423424
]
424425
},

notebooks/Four-bar linkage - simulation and visualization.ipynb

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@
2525
"cell_type": "markdown",
2626
"metadata": {},
2727
"source": [
28-
"We'll be using `RigidBodyDynamics` and `StaticArrays` for the simulation part."
28+
"We'll be using `LinearAlgebra`, `RigidBodyDynamics`, and `StaticArrays` for the simulation part."
2929
]
3030
},
3131
{
@@ -34,6 +34,7 @@
3434
"metadata": {},
3535
"outputs": [],
3636
"source": [
37+
"using LinearAlgebra\n",
3738
"using RigidBodyDynamics\n",
3839
"using StaticArrays"
3940
]
@@ -160,23 +161,23 @@
160161
"source": [
161162
"# link1 and joint1\n",
162163
"joint1 = Joint(\"joint1\", Revolute(axis))\n",
163-
"inertia1 = SpatialInertia(CartesianFrame3D(\"inertia1_centroidal\"), I_1*axis*axis', zeros(SVector{3, T}), m_1)\n",
164+
"inertia1 = SpatialInertia(CartesianFrame3D(\"inertia1_centroidal\"), I_1*axis*axis', zero(SVector{3, T}), m_1)\n",
164165
"link1 = RigidBody(inertia1)\n",
165166
"before_joint1_to_world = eye(Transform3D, frame_before(joint1), default_frame(world))\n",
166167
"c1_to_joint = Transform3D(inertia1.frame, frame_after(joint1), SVector(c_1, 0, 0))\n",
167168
"attach!(fourbar, world, link1, joint1, joint_pose = before_joint1_to_world, successor_pose = c1_to_joint)\n",
168169
"\n",
169170
"# link2 and joint2\n",
170171
"joint2 = Joint(\"joint2\", Revolute(axis))\n",
171-
"inertia2 = SpatialInertia(CartesianFrame3D(\"inertia2_centroidal\"), I_2*axis*axis', zeros(SVector{3, T}), m_2)\n",
172+
"inertia2 = SpatialInertia(CartesianFrame3D(\"inertia2_centroidal\"), I_2*axis*axis', zero(SVector{3, T}), m_2)\n",
172173
"link2 = RigidBody(inertia2)\n",
173174
"before_joint2_to_after_joint1 = Transform3D(frame_before(joint2), frame_after(joint1), SVector(l_1, 0., 0.))\n",
174175
"c2_to_joint = Transform3D(inertia2.frame, frame_after(joint2), SVector(c_2, 0, 0))\n",
175176
"attach!(fourbar, link1, link2, joint2, joint_pose = before_joint2_to_after_joint1, successor_pose = c2_to_joint)\n",
176177
"\n",
177178
"# link3 and joint3\n",
178179
"joint3 = Joint(\"joint3\", Revolute(axis))\n",
179-
"inertia3 = SpatialInertia(CartesianFrame3D(\"inertia3_centroidal\"), I_3*axis*axis', zeros(SVector{3, T}), m_3)\n",
180+
"inertia3 = SpatialInertia(CartesianFrame3D(\"inertia3_centroidal\"), I_3*axis*axis', zero(SVector{3, T}), m_3)\n",
180181
"link3 = RigidBody(inertia3)\n",
181182
"before_joint3_to_world = Transform3D(frame_before(joint3), default_frame(world), SVector(l_0, 0., 0.))\n",
182183
"c3_to_joint = Transform3D(inertia3.frame, frame_after(joint3), SVector(c_3, 0, 0))\n",

notebooks/Jacobian_IK_and_Control.ipynb renamed to notebooks/Jacobian IK and Control.ipynb

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@
3232
"using StaticArrays\n",
3333
"\n",
3434
"# Fix the random seed, so we get repeatable results\n",
35+
"using Random\n",
3536
"srand(42)"
3637
]
3738
},
@@ -337,9 +338,9 @@
337338
"source": [
338339
"# Choose a desired location. We'll move the tip of the arm to\n",
339340
"# [0.5, 0, 2]\n",
340-
"desired = Point3D(root_frame(mechanism), 0.5, 0, 2)\n",
341+
"desired_tip_location = Point3D(root_frame(mechanism), 0.5, 0, 2)\n",
341342
"# Run the IK, updating `state` in place\n",
342-
"jacobian_transpose_ik!(state, body, point, desired)"
343+
"jacobian_transpose_ik!(state, body, point, desired_tip_location)"
343344
]
344345
},
345346
{
@@ -391,7 +392,7 @@
391392
"qs = typeof(configuration(state))[]\n",
392393
"\n",
393394
"# Vary the desired x position from -1 to 1\n",
394-
"for x in linspace(-1, 1, 100)\n",
395+
"for x in range(-1, stop=1, length=100)\n",
395396
" desired = Point3D(root_frame(mechanism), x, 0, 2)\n",
396397
" jacobian_transpose_ik!(state, body, point, desired)\n",
397398
" push!(qs, copy(configuration(state)))\n",
@@ -416,7 +417,7 @@
416417
],
417418
"source": [
418419
"#NBSKIP\n",
419-
"ts = collect(linspace(0, 1, length(qs)))\n",
420+
"ts = collect(range(0, stop=1, length=length(qs)))\n",
420421
"setanimation!(vis, ts, qs)"
421422
]
422423
},
@@ -482,7 +483,7 @@
482483
"#NBSKIP\n",
483484
"\n",
484485
"# Draw the circle in the viewer\n",
485-
"θ = repeat(linspace(0, 2π, 100), inner=(2,))[2:end]\n",
486+
"θ = repeat(linspace(0, stop=2π, length=100), inner=(2,))[2:end]\n",
486487
"cx, cy, cz = circle_origin\n",
487488
"geometry = PointCloud(Point.(cx .+ radius .* sin.(θ), cy, cz .+ 0.5 .* cos.(θ)))\n",
488489
"setobject!(vis[:circle], LineSegments(geometry, LineBasicMaterial()))"

notebooks/Quickstart - double pendulum.ipynb

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
"outputs": [],
2222
"source": [
2323
"using RigidBodyDynamics\n",
24+
"using LinearAlgebra\n",
2425
"using StaticArrays"
2526
]
2627
},
@@ -94,7 +95,7 @@
9495
"c_1 = -0.5 # center of mass location with respect to joint axis\n",
9596
"m_1 = 1. # mass\n",
9697
"frame1 = CartesianFrame3D(\"upper_link\") # the reference frame in which the spatial inertia will be expressed\n",
97-
"inertia1 = SpatialInertia(frame1, I_1 * axis * axis.', m_1 * SVector(0, 0, c_1), m_1)"
98+
"inertia1 = SpatialInertia(frame1, I_1 * axis * axis', m_1 * SVector(0, 0, c_1), m_1)"
9899
]
99100
},
100101
{
@@ -255,7 +256,7 @@
255256
"I_2 = 0.333 # moment of inertia about joint axis\n",
256257
"c_2 = -0.5 # center of mass location with respect to joint axis\n",
257258
"m_2 = 1. # mass\n",
258-
"inertia2 = SpatialInertia(CartesianFrame3D(\"lower_link\"), I_2 * axis * axis.', m_2 * SVector(0, 0, c_2), m_2)\n",
259+
"inertia2 = SpatialInertia(CartesianFrame3D(\"lower_link\"), I_2 * axis * axis', m_2 * SVector(0, 0, c_2), m_2)\n",
259260
"lowerlink = RigidBody(inertia2)\n",
260261
"elbow = Joint(\"elbow\", Revolute(axis))\n",
261262
"before_elbow_to_after_shoulder = Transform3D(frame_before(elbow), frame_after(shoulder), SVector(0, 0, l_1))\n",
@@ -464,7 +465,7 @@
464465
}
465466
],
466467
"source": [
467-
"transform(state, Point3D(frame_after(elbow), zeros(SVector{3})), default_frame(world))"
468+
"transform(state, Point3D(frame_after(elbow), zero(SVector{3})), default_frame(world))"
468469
]
469470
},
470471
{
@@ -627,8 +628,8 @@
627628
],
628629
"source": [
629630
"v̇ = similar(velocity(state)) # the joint acceleration vector, i.e., the time derivative of the joint velocity vector v\n",
630-
"v̇[shoulder][:] = 1\n",
631-
"v̇[elbow][:] = 2\n",
631+
"v̇[shoulder][1] = 1\n",
632+
"v̇[elbow][1] = 2\n",
632633
"inverse_dynamics(state, v̇)"
633634
]
634635
},

notebooks/Rigorous error bounds using IntervalArithmetic.ipynb

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -252,7 +252,7 @@
252252
}
253253
],
254254
"source": [
255-
"using Compat.Test\n",
255+
"using Test\n",
256256
"@test (2.6 - 0.7 - 1.9) ∈ i"
257257
]
258258
},

notebooks/Symbolic double pendulum.ipynb

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -94,14 +94,14 @@
9494
"world = root_body(double_pendulum) # the fixed 'world' rigid body\n",
9595
"\n",
9696
"# Attach the first (upper) link to the world via a revolute joint named 'shoulder'\n",
97-
"inertia1 = SpatialInertia(CartesianFrame3D(\"upper_link\"), I_1 * axis * axis.', m_1 * SVector(zero(T), zero(T), c_1), m_1)\n",
97+
"inertia1 = SpatialInertia(CartesianFrame3D(\"upper_link\"), I_1 * axis * axis', m_1 * SVector(zero(T), zero(T), c_1), m_1)\n",
9898
"body1 = RigidBody(inertia1)\n",
9999
"joint1 = Joint(\"shoulder\", Revolute(axis))\n",
100100
"joint1_to_world = eye(Transform3D{T}, frame_before(joint1), default_frame(world))\n",
101101
"attach!(double_pendulum, world, body1, joint1, joint_pose = joint1_to_world)\n",
102102
"\n",
103103
"# Attach the second (lower) link to the world via a revolute joint named 'elbow'\n",
104-
"inertia2 = SpatialInertia(CartesianFrame3D(\"lower_link\"), I_2 * axis * axis.', m_2 * SVector(zero(T), zero(T), c_2), m_2)\n",
104+
"inertia2 = SpatialInertia(CartesianFrame3D(\"lower_link\"), I_2 * axis * axis', m_2 * SVector(zero(T), zero(T), c_2), m_2)\n",
105105
"body2 = RigidBody(inertia2)\n",
106106
"joint2 = Joint(\"elbow\", Revolute(axis))\n",
107107
"joint2_to_body1 = Transform3D(frame_before(joint2), default_frame(body1), SVector(zero(T), zero(T), l_1))\n",

0 commit comments

Comments
 (0)