Skip to content

Commit

Permalink
Support v1.0
Browse files Browse the repository at this point in the history
  • Loading branch information
baggepinnen committed Sep 24, 2018
1 parent c3e864a commit 27e6c85
Show file tree
Hide file tree
Showing 10 changed files with 35 additions and 29 deletions.
2 changes: 1 addition & 1 deletion .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,9 @@ os:
- linux
- osx
julia:
- 0.6
- 0.7
- 1.0
- nightly
matrix:
allow_failures:
- julia: nightly
Expand Down
4 changes: 2 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
[![Robotlib](http://pkg.julialang.org/badges/Robotlib_0.5.svg)](http://pkg.julialang.org/?pkg=Robotlib)
[![Robotlib](http://pkg.julialang.org/badges/Robotlib_0.6.svg)](http://pkg.julialang.org/?pkg=Robotlib)
[![Build Status](https://travis-ci.org/baggepinnen/Robotlib.jl.svg?branch=master)](https://travis-ci.org/baggepinnen/Robotlib.jl)
[![codecov](https://codecov.io/gh/baggepinnen/Robotlib.jl/branch/master/graph/badge.svg)](https://codecov.io/gh/baggepinnen/Robotlib.jl)


Update to support julia v0.7 / v1.0 is ongoing
Now supporting Julia v0.7/v1.0.
Dependency MAT.jl is currently not building on Julia v1.0 and hence all file loading functionality and some tests have been deactivated.

# Robotlib
This is a library of functions to help out in a robotics lab. At present stage, it contains functions for forward kinematics, jacobians, iterative inverse kinematics and for a few robotics related calibration problems. The library also contains a number of functions to convert from various orientation representations and other robotics related helper functions.
Expand Down
2 changes: 1 addition & 1 deletion REQUIRE
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
julia 0.7
MAT
# MAT
DataFrames
RecipesBase
StatsBase
Expand Down
6 changes: 3 additions & 3 deletions src/Frames.jl
Original file line number Diff line number Diff line change
Expand Up @@ -56,15 +56,15 @@ println("Wrote T_TAB_SEAM, T_T_SEAM, T_RB_TAB to files in \$path")
"""
module Frames

using StaticArrays, RecipesBase, LinearAlgebra

using StaticArrays, RecipesBase, LinearAlgebra, Statistics
using ..Robotlib

export Frame, Point, Plane, Points, Line, GeometricObject, add_frame_name!
export readcloud, readTmatrix, readplane, fitline, fitplane, framefromfeatures, project
export plot3Dsmart, display, show, print
export inv, *,+,-,/,\,transpose,ctranspose, dot

import Base: print, zeros, length, size, getindex, setindex!, convert, promote_rule, push!, show, display, iterate, +, *, .*, /, ./, -, \, inv
import Base: print, zeros, length, size, getindex, setindex!, convert, promote_rule, push!, show, display, +, *, .*, /, ./, -, \, inv
import LinearAlgebra: ×, transpose, ctranspose, dot, , det
# using LaTeXStrings
import Robotlib: T2R, T2t, I3, I4
Expand Down
7 changes: 4 additions & 3 deletions src/Robotlib.jl
Original file line number Diff line number Diff line change
Expand Up @@ -29,10 +29,11 @@ const I3 = SMatrix{3, 3, Float64, 9}(Matrix{Float64}(I, 3, 3))
include("DH.jl")
include("utils.jl")
include("kinematics.jl")
include("Frames.jl") # Must come before robotplot
include("robotplot.jl")
include("Frames.jl")
include("read_log.jl")
include("csv2mat.jl")
# https://github.com/JuliaIO/MAT.jl/issues/90
# include("read_log.jl")# Re-enable when MAT.jl builds under Julia v1.0. Then add MAT to require
# include("csv2mat.jl") # Re-enable when MAT.jl builds under Julia v1.0. Then add MAT to require
include("posDepFric.jl")

module Calibration
Expand Down
2 changes: 1 addition & 1 deletion src/applications/FRIDAcalibForce.jl
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ function demo_calibforce(filename = "")
h = 0.004032;
dh = DHYuMi()

if if filename != "" # Use this option if you have a textbased logfile
if filename != "" # Use this option if you have a textbased logfile
pathopen = filename
pathsave = "log.mat"
data = orcalog2mat(pathopen, pathsave)
Expand Down
1 change: 1 addition & 0 deletions src/calibLPOE.jl
Original file line number Diff line number Diff line change
Expand Up @@ -458,6 +458,7 @@ if false
ei = 0.0
ec = 0.0
for i = 1:N
global ei,ec
T1 = fkineLPOE(Tn0mod,xin,q[i,:,1])
T2 = fkineLPOE(Tn0mod,xin,q[i,:,2])
ei += norm(twistcoords(log(Ta[:,:,i]*trinv(T1))))
Expand Down
10 changes: 5 additions & 5 deletions src/calibNAXP.jl
Original file line number Diff line number Diff line change
Expand Up @@ -86,11 +86,11 @@ function get_matrices(N_RB, POSES, points_S, lines_S)
Ta = POSES[1:3,4,i]
Pi = points_S[:,i]
y[i] = norm(Ni)^2-Ni'Ta
A[i,:] = (reshape(repmat(Ni'Ra,3,1)',9,1).*[reshape(repmat(Pi[1:2],1,3)',6,1);1;1;1])' #TODO: rewrite
A[i,:] = (reshape(repeat(Ni'Ra,3,1)',9,1).*[reshape(repeat(Pi[1:2],1,3)',6,1);1;1;1])' #TODO: rewrite
# Sample one additional point along line
Pi = points_S[:,i] + 1lines_S[:,i]
y[i+N_poses] = norm(N_RB[:,i])^2-Ni'Ta
A[i+N_poses,:] = (reshape(repmat(Ni'Ra,3,1)',9,1) .*[reshape(repmat(Pi[1:2],1,3)',6,1);1;1;1])'
A[i+N_poses,:] = (reshape(repeat(Ni'Ra,3,1)',9,1) .*[reshape(repeat(Pi[1:2],1,3)',6,1);1;1;1])'
end
A,y
end
Expand All @@ -116,14 +116,14 @@ function findplanes(planes, points)
for j = 1:N_planes
ind = planes .== j
μᵢ = mean(points[1:3,ind],dims=2)[:]
μ_RB[:,ind] = repmat(μᵢ,1,sum(ind))
D,V = eig(cov(points[1:3,ind]')) # PCA
μ_RB[:,ind] = repeat(μᵢ,1,sum(ind))
D,V = eigen(cov(points[1:3,ind]')) # PCA
N_RBi = V[:,1] # Eigenvector of smalles eigval is the normal of the plane
if μᵢ'N_RBi < 0 # Make sure all normals point in same direction
N_RBi = -1*N_RBi
end
N_RBi = N_RBi*(N_RBi'μᵢ)
N_RB[:,ind] = repmat(N_RBi,1,sum(ind)) # Repeat plane normal for all planes with same ind
N_RB[:,ind] = repeat(N_RBi,1,sum(ind)) # Repeat plane normal for all planes with same ind
normals[j,:] = N_RBi
end
normals, N_RB
Expand Down
10 changes: 7 additions & 3 deletions test/runtests.jl
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
using Robotlib, LinearAlgebra, Random, Statistics
using Test
import Robotlib: ad, adi, I4
Random.seed!(1)

include("testCalibNAXP.jl")
include("testForce.jl")
Expand Down Expand Up @@ -112,6 +113,7 @@ end
# xic,et,er = Robotlib.Calibration.calibPOE(xinmod,Ta,q,maxiter=150, λ = 10000.0)
# display(norm(xin[:,1:7]-xinmod[:,1:7]))
# display(norm(xin[:,1:7]-xic[:,1:7]))

N = 100
println("===== Testing calibLPOE =====")
q, xin,Tn0,Tn0mod, Ta = simulateCalibrationLPOE(N)
Expand All @@ -129,9 +131,10 @@ end
sqrt(sum((Tn0[1:3,4,:]-Tn0mod[1:3,4,:,1]).^2+(Tn0[1:3,4,:]-Tn0mod[1:3,4,:,2]).^2)/N))
println("Error between Tn0 and Tn0c : ",
sqrt(sum((Tn0[1:3,4,:]-Tn0c[1:3,4,:,1]).^2+(Tn0[1:3,4,:]-Tn0c[1:3,4,:,2]).^2)/N))
ei = 0.0
ec = 0.0
global ei = 0.0
global ec = 0.0
for i = 1:N
global ei, ec
T1 = fkineLPOE(Tn0mod[:,:,:,1],xin[:,:,1],q[i,:,1])
T2 = fkineLPOE(Tn0mod[:,:,:,2],xin[:,:,2],q[i,:,2])
ei += norm(twistcoords(log(Ta[:,:,i]*trinv(T1))))
Expand All @@ -147,4 +150,5 @@ end


println("===== Testing frames =====")
include("testFrames.jl")
@warn("Testing of Frames is inactivated since MAT.jl didn't build. Re-enable when this is resolved https://github.com/JuliaIO/MAT.jl/issues/90")
# include("testFrames.jl")
20 changes: 10 additions & 10 deletions test/testCalibNAXP.jl
Original file line number Diff line number Diff line change
Expand Up @@ -135,9 +135,9 @@ function run_calib()
# Generate nominal transformation
T_TF_S_real = copy(T_TF_S)
if true
T_TF_S0 = Rt2T(rpy2R(60π/180*(rand(3)-0.5)),0.4*(rand(3)-0.5))*T_TF_S_real
# T_TF_S0 = Rt2T(rpy2R(10π/180*(rand(3)-0.5)),0.1*(rand(3)-0.5))*T_TF_S_real
# T_TF_S0 = rt2tr(rpy2R(2*(rand(1,3)-0.5),'deg'),0.01*(rand(3,1)-0.5))*T_TF_S_real;
T_TF_S0 = Rt2T(rpy2R(60π/180*(rand(3).-0.5)),0.4*(rand(3).-0.5))*T_TF_S_real
# T_TF_S0 = Rt2T(rpy2R(10π/180*(rand(3).-0.5)),0.1*(rand(3).-0.5))*T_TF_S_real
# T_TF_S0 = rt2tr(rpy2R(2*(rand(1,3).-0.5),'deg'),0.01*(rand(3,1).-0.5))*T_TF_S_real;
else
T_TF_S0 = copy(T_TF_S_real)
end
Expand Down Expand Up @@ -173,13 +173,13 @@ end

SSEStart, normStart, distStart, rotStart, distEnd, rotEnd, SSEMC, normMC = run_calib()

iters = size(SSEMC,2)
using StatPlots
gr(legend=false)
plot(0:iters,copy([normStart normMC]'),yscale=:log10,c=:black, xlabel="Number of iterations", layout=2, subplot=1)
hline!([sigma_n, sigma_n],l=:dash, c=:red, subplot=1)
plot!(0:iters,[SSEStart SSEMC]',yscale=:log10,c=:black, xlabel="Number of iterations",title="RMS distance from points to plane [m]", subplot=2)
hline!([sigma_n sigma_n],l=:dash,c=:red, subplot=2)
# iters = size(SSEMC,2)
# using StatPlots
# gr(legend=false)
# plot(0:iters,copy([normStart normMC]'),yscale=:log10,c=:black, xlabel="Number of iterations", layout=2, subplot=1)
# hline!([sigma_n, sigma_n],l=:dash, c=:red, subplot=1)
# plot!(0:iters,[SSEStart SSEMC]',yscale=:log10,c=:black, xlabel="Number of iterations",title="RMS distance from points to plane [m]", subplot=2)
# hline!([sigma_n sigma_n],l=:dash,c=:red, subplot=2)

# boxplot(["Before" "After"],([distStart distEnd]), title="Distance error [m]", yscale=:log10, layout=2, subplot=1)
# hline!([sigma_n sigma_n],c=:red)
Expand Down

0 comments on commit 27e6c85

Please sign in to comment.