ロボットモデル

ロボットの身体はリンクとジョイントから構成されるが、それぞれ bodyset-linkjointクラスを利用しモデル絵を作成する。ロ ボットの身体はこれらの要素を含んだcascaded-linkという,連結リン クとしてモデルを生成する.

実際にはjointは抽象クラスであり rotational-joint,linear-joint, wheel-joint,omniwheel-joint, sphere-jointを選択肢、また四肢を持つロボットの場合は cascaded-link ではなくrobot-modelクラスを利用する。




joint [クラス]


  :super   propertied-object 

:slots parent-link child-link joint-angle min-angle max-angle default-coords joint-velocity joint-acceleration joint-torque max-joint-velocity max-joint-torque joint-min-max-table joint-min-max-target





\begin{emtabbing}
{\bf :init}
\it\&key \= (name (intern (format nil joint~A (sy...
...:joint-min-max-target mm-target)) \\
\> \&allow-other-keys
\rm
\end{emtabbing}
abstract class of joint, users need to use rotational-joint, linear-joint, sphere-joint, 6dof-joint, wheel-joint or omniwheel-joint.
use :parent-link/:child-link for specifying links that this joint connect to and :min/:min for range of joint angle in degree.


:min-angle &optional v [メソッド]
If v is set, it updates min-angle of this instance. :min-angle returns minimal angle of this joint in degree.


:max-angle &optional v [メソッド]
If v is set, it updates max-angle of this instance. :max-angle returns maximum angle of this joint in degree.


:parent-link &rest args [メソッド]
Returns parent link of this joint. if any arguments is set, it is passed to the parent-link.


:child-link &rest args [メソッド]
Returns child link of this joint. if any arguments is set, it is passed to the child-link.


:calc-dav-gain dav i periodic-time [メソッド]


:joint-dof
[メソッド]


:speed-to-angle &rest args
[メソッド]


:angle-to-speed &rest args
[メソッド]


:calc-jacobian &rest args
[メソッド]


:joint-velocity &optional jv
[メソッド]


:joint-acceleration &optional ja
[メソッド]


:joint-torque &optional jt
[メソッド]


:max-joint-velocity &optional mjv
[メソッド]


:max-joint-torque &optional mjt
[メソッド]


:joint-min-max-table &optional mm-table
[メソッド]


:joint-min-max-target &optional mm-target
[メソッド]


:joint-min-max-table-angle-interpolate target-angle min-or-max
[メソッド]


:joint-min-max-table-min-angle &optional (target-angle (send joint-min-max-target :joint-angle))
[メソッド]


:joint-min-max-table-max-angle &optional (target-angle (send joint-min-max-target :joint-angle))
[メソッド]




rotational-joint [クラス]


  :super   joint 

:slots axis





\begin{emtabbing}
{\bf :init}
\it\&rest args \&key \= ((:axis ax) :z) \\lq  [metho...
...
\> ((:max-joint-torque mjt) 100) \\
\> \&allow-other-keys
\rm
\end{emtabbing}
create instance of rotational-joint. :axis is either (:x, :y, :z) or vector. :min-angle and :max-angle takes in radius, but velocity and torque are given in SI units.



\begin{emtabbing}
{\bf :joint-angle}
\it\&optional v \&key \= relative \\lq  [method]\\
\> \&allow-other-keys
\rm
\end{emtabbing}
Return joint-angle if v is not set, if v is given, set joint angle. v is rotational value in degree.


:joint-dof [メソッド]
Returns DOF of rotational joint, 1.


:calc-angle-speed-gain dav i periodic-time [メソッド]


:speed-to-angle v
[メソッド]


:angle-to-speed v
[メソッド]


:calc-jacobian &rest args
[メソッド]




linear-joint [クラス]


  :super   joint 

:slots axis





\begin{emtabbing}
{\bf :init}
\it\&rest args \&key \= ((:axis ax) :z) \\lq  [metho...
...
\> ((:max-joint-torque mjt) 100) \\
\> \&allow-other-keys
\rm
\end{emtabbing}
Create instance of linear-joint. :axis is either (:x, :y, :z) or vector. :min-angle and :max-angle takes in [mm], but velocity and torque are given in SI units.



\begin{emtabbing}
{\bf :joint-angle}
\it\&optional v \&key \= relative \\lq  [method]\\
\> \&allow-other-keys
\rm
\end{emtabbing}
return joint-angle if v is not set, if v is given, set joint angle. v is linear value in [mm].


:joint-dof [メソッド]
Returns DOF of linear joint, 1.


:calc-angle-speed-gain dav i periodic-time [メソッド]


:speed-to-angle v
[メソッド]


:angle-to-speed v
[メソッド]


:calc-jacobian &rest args
[メソッド]




wheel-joint [クラス]


  :super   joint 

:slots axis





\begin{emtabbing}
{\bf :init}
\it\&rest args \&key \= (min (float-vector \texta...
...rque mjt) (float-vector 100 100)) \\
\> \&allow-other-keys
\rm
\end{emtabbing}
Create instance of wheel-joint.



\begin{emtabbing}
{\bf :joint-angle}
\it\&optional v \&key \= relative \\lq  [method]\\
\> \&allow-other-keys
\rm
\end{emtabbing}
return joint-angle if v is not set, if v is given, set joint angle. v is joint-angle vector, which is (float-vector translation-x[mm] rotation-z[deg])


:joint-dof [メソッド]
Returns DOF of linear joint, 2.


:calc-angle-speed-gain dav i periodic-time [メソッド]


:speed-to-angle dv
[メソッド]


:angle-to-speed dv
[メソッド]


:calc-jacobian fik row column joint paxis child-link world-default-coords child-reverse move-target transform-coords rotation-axis translation-axis tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33
[メソッド]




omniwheel-joint [クラス]


  :super   joint 

:slots axis





\begin{emtabbing}
{\bf :init}
\it\&rest args \&key \= (min (float-vector \texta...
... mjt) (float-vector 100 100 100)) \\
\> \&allow-other-keys
\rm
\end{emtabbing}
create instance of omniwheel-joint.



\begin{emtabbing}
{\bf :joint-angle}
\it\&optional v \&key \= relative \\lq  [method]\\
\> \&allow-other-keys
\rm
\end{emtabbing}
return joint-angle if v is not set, if v is given, set joint angle. v is joint-angle vector, which is (float-vector translation-x[mm] translation-y[mm] rotation-z[deg])


:joint-dof [メソッド]
Returns DOF of linear joint, 3.


:calc-angle-speed-gain dav i periodic-time [メソッド]


:speed-to-angle dv
[メソッド]


:angle-to-speed dv
[メソッド]


:calc-jacobian fik row column joint paxis child-link world-default-coords child-reverse move-target transform-coords rotation-axis translation-axis tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33
[メソッド]




sphere-joint [クラス]


  :super   joint 

:slots axis





\begin{emtabbing}
{\bf :init}
\it\&rest args \&key \= (min (float-vector \texta...
... mjt) (float-vector 100 100 100)) \\
\> \&allow-other-keys
\rm
\end{emtabbing}
Create instance of sphere-joint. min/max are defiend as a region of angular velocity in degree.



\begin{emtabbing}
{\bf :joint-angle}
\it\&optional v \&key \= relative \\lq  [method]\\
\> \&allow-other-keys
\rm
\end{emtabbing}
return joint-angle if v is not set, if v is given, set joint angle.
v is joint-angle vector [deg] by axis-angle representation, i.e (scale rotation-angle-from-default-coords[deg] axis-unit-vector)


:joint-angle-rpy &optional v &key relative [メソッド]
Return joint-angle if v is not set, if v is given, set joint-angle vector by RPY representation, i.e. (float-vector yaw[deg] roll[deg] pitch[deg])


:joint-dof [メソッド]
Returns DOF of linear joint, 3.



\begin{emtabbing}
{\bf :joint-euler-angle}
\it\&key \= (axis-order '(:z :y :x)) \\lq  [method]\\
\> ((:child-rot m) (send child-link :rot))
\rm
\end{emtabbing}
Return joint-angle if v is not set, if v is given, set joint-angle vector by euler representation.


:calc-angle-speed-gain dav i periodic-time [メソッド]


:speed-to-angle dv
[メソッド]


:angle-to-speed dv
[メソッド]


:calc-jacobian fik row column joint paxis child-link world-default-coords child-reverse move-target transform-coords rotation-axis translation-axis tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33
[メソッド]




6dof-joint [クラス]


  :super   joint 

:slots axis





\begin{emtabbing}
{\bf :init}
\it\&rest args \&key \= (min (float-vector \texta...
...100 100)) \\
\> (absolute-p nil) \\
\> \&allow-other-keys
\rm
\end{emtabbing}
Create instance of 6dof-joint.



\begin{emtabbing}
{\bf :joint-angle}
\it\&optional v \&key \= relative \\lq  [method]\\
\> \&allow-other-keys
\rm
\end{emtabbing}
Return joint-angle if v is not set, if v is given, set joint angle vector, which is 6D vector of 3D translation[mm] and 3D rotation[deg], i.e. (find-if #'(lambda (x) (eq (send (car x) :name) 'sphere-joint)) (documentation :joint-angle))


:joint-angle-rpy &optional v &key relative [メソッド]
Return joint-angle if v is not set, if v is given, set joint angle. v is joint-angle vector, which is 6D vector of 3D translation[mm] and 3D rotation[deg], for rotation, please see (find-if #'(lambda (x) (eq (send (car x) :name) 'sphere-joint)) (documentation :joint-angle-rpy))


:joint-dof [メソッド]
Returns DOF of linear joint, 6.


:calc-angle-speed-gain dav i periodic-time [メソッド]


:speed-to-angle dv
[メソッド]


:angle-to-speed dv
[メソッド]


:calc-jacobian fik row column joint paxis child-link world-default-coords child-reverse move-target transform-coords rotation-axis translation-axis tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33
[メソッド]




bodyset-link [クラス]


  :super   bodyset 

:slots joint parent-link child-links analysis-level default-coords weight acentroid inertia-tensor angular-velocity angular-acceleration spacial-velocity spacial-acceleration momentum-velocity angular-momentum-velocity momentum angular-momentum force moment ext-force ext-moment





\begin{emtabbing}
{\bf :init}
\it coords \&rest args \&key \= ((:analysis-level...
...nertia-tensor i) (unit-matrix 3)) \\
\> \&allow-other-keys
\rm
\end{emtabbing}
Create instance of bodyset-link.


:worldcoords &optional (level analysis-level) [メソッド]
Returns a coordinates object which represents this coord in the world by concatenating all the cascoords from the root to this coords.


:analysis-level &optional v [メソッド]
Change analysis level :coords only changes kinematics level and :body changes geometry too.


:weight &optional w [メソッド]
Returns a weight of the link. If w is given, set weight.


:centroid &optional c [メソッド]
Returns a centroid of the link. If c is given, set new centroid.


:inertia-tensor &optional i [メソッド]
Returns a inertia tensor of the link. If c is given, set new intertia tensor.


:joint &rest args [メソッド]
Returns a joint associated with this link. If args is given, args are forward to the joint.


:add-joint j [メソッド]
Set j as joint of this link


:del-joint [メソッド]
Remove current joint of this link


:parent-link [メソッド]
Returns parent link


:child-links [メソッド]
Returns child links


:add-child-links l [メソッド]
Add l to child links


:add-parent-link l [メソッド]
Set l as parent link


:del-child-link l [メソッド]
Delete l from child links


:del-parent-link [メソッド]
Delete parent link


:default-coords &optional c [メソッド]




cascaded-link [クラス]


  :super   cascaded-coords 

:slots links joint-list bodies collision-avoidance-links end-coords-list





\begin{emtabbing}
{\bf :init}
\it\&rest args \&key \= name \\lq  [method]\\
\> \&allow-other-keys
\rm
\end{emtabbing}
Create cascaded-link.


:init-ending [メソッド]
This method is to called finalize the instantiation of the cascaded-link. This update bodies and child-link and parent link from joint-list


:links &rest args [メソッド]
Returns links, or args is passed to links


:joint-list &rest args [メソッド]
Returns joint list, or args is passed to joints


:link name [メソッド]
Return a link with given name.


:joint name [メソッド]
Return a joint with given name.


:end-coords name [メソッド]
Returns end-coords with given name


:bodies &rest args [メソッド]
Return bodies of this object. If args is given it passed to all bodies


:faces [メソッド]
Return faces of this object.


:angle-vector &optional vec (angle-vector (instantiate float-vector (calc-target-joint-dimension joint-list))) [メソッド]
Returns angle-vector of this object, if vec is given, it updates angles of all joint. If given angle-vector violate min/max range, the value is modified.


:link-list to &optional from [メソッド]
Find link list from to link to from link.


:plot-joint-min-max-table joint0 joint1 [メソッド]
Plot joint min max table on Euslisp window.



\begin{emtabbing}
{\bf :calc-jacobian-from-link-list}
\it link-list \&rest args...
...\
\> (tmp-m33 (make-matrix 3 3)) \\
\> \&allow-other-keys
\rm
\end{emtabbing}
Calculate jacobian matrix from link-list and move-target. Unit system is [m] or [rad], not [mm] or [deg].



\begin{emtabbing}
{\bf :inverse-kinematics-loop}
\it dif-pos dif-rot \&rest arg...
... \\
\> debug-view \\
\> ik-args \\
\> \&allow-other-keys
\rm
\end{emtabbing}
:inverse-kinematics-loop is one loop calculation for :inverse-kinematics.
In this method, joint position difference satisfying workspace difference (dif-pos, dif-rot) are calculated and euslisp model joint angles are updated.
Optional arguments:
:additional-check
This argument is to add optional best-effort convergence conditions.
:additional-check should be function or lambda.
best-effort =>In :inverse-kinematics-loop, 'success' is overwritten by '(and success additional-check)'
In :inverse-kinematics, 'success is not overwritten.
So, :inverse-kinematics-loop wait until ':additional-check' becomes 't' as possible,
but ':additional-check' is neglected in the final :inverse-kinematics return.
:min-loop
Minimam loop count (nil by default).
If integer is specified, :inverse-kinematics-loop does returns :ik-continues and continueing solving IK.
If min-loop is nil, do not consider loop counting for IK convergence.



\begin{emtabbing}
{\bf :inverse-kinematics}
\it target-coords \&rest args \&key...
...l-jacobi) \\
\> (additional-vel) \\
\> \&allow-other-keys
\rm
\end{emtabbing}
Move move-target to target-coords.
dump-command should be t, nil, :always, :fail-only, :always-with-debug-log, or :fail-only-with-debug-log.
Log are success/fail log and ik debug information log.
t or :always : dump log both in success and fail (for success/fail log).
:always-with-debug-log : dump log both in success and fail (for success/fail log and ik debug information log).
:fail-only : dump log only in fail (for success/fail log).
:always-with-debug-log : dump log only in fail (for success/fail log and ik debug information log).
nil : do not dump log.



\begin{emtabbing}
{\bf :calc-grasp-matrix}
\it contact-points \&key \= (ret (ma...
...pcar \char93 '(lambda (r) (unit-matrix 3)) contact-points))
\rm
\end{emtabbing}
Calc grasp matrix.
Grasp matrix is defined as
| E_3 0 E_3 0 ... |
| p1x E_3 p2x E_3 ... |
Arguments:
contact-points is list of contact points[mm].
contact-rots is list of contact coords rotation[rad].
If contact-rots is specified, grasp matrix as follow:
| R1 0 R2 0 ... |
| p1xR1 R1 p2xR2 R2 ... |



\begin{emtabbing}
{\bf :inverse-kinematics-for-closed-loop-forward-kinematics}
...
...t-angle-list) \\
\> (min-loop 2) \\
\> \&allow-other-keys
\rm
\end{emtabbing}
Solve inverse-kinematics for closed loop forward kinematics.
Move move-target to target-coords with link-list.
link-list loop should be close when move-target reachs target-coords.
constrained-joint-list is list of joints specified given joint angles in closed loop.
constrained-joint-angle-list is list of joint-angle for constrained-joint-list.


:calc-jacobian-for-interlocking-joints link-list &key (interlocking-joint-pairs (send self :interlocking-joint-pairs)) [メソッド]
Calculate jacobian to keep interlocking joint velocity same.
dtheta_0 = dtheta_1 =>[... 0 1 0 ... 0 -1 0 .... ][...dtheta_0...dtheta_1...]


:calc-vel-for-interlocking-joints link-list &key (interlocking-joint-pairs (send self :interlocking-joint-pairs)) [メソッド]
Calculate 0 velocity for keeping interlocking joint at the same joint angle.


:set-midpoint-for-interlocking-joints &key (interlocking-joint-pairs (send self :interlocking-joint-pairs)) [メソッド]
Set interlocking joints at mid point of each joint angle.


:interlocking-joint-pairs [メソッド]
Interlocking joint pairs.
pairs are (list (cons joint0 joint1) ... )
If users want to use interlocking joints, please overwrite this method.



\begin{emtabbing}
{\bf :check-interlocking-joint-angle-validity}
\it\&key \= (a...
...rlocking-joint-pairs (send self :interlocking-joint-pairs))
\rm
\end{emtabbing}
Check if all interlocking joint pairs are same values.


:update-descendants &rest args [メソッド]


:find-link-route to &optional from
[メソッド]


:make-joint-min-max-table l0 l1 joint0 joint1 &key (fat 0) (fat2 nil) (debug nil) (margin 0.0) (overwrite-collision-model nil)
[メソッド]


:make-min-max-table-using-collision-check l0 l1 joint0 joint1 joint-range0 joint-range1 min-joint0 min-joint1 fat fat2 debug margin
[メソッド]


:plot-joint-min-max-table-common joint0 joint1
[メソッド]


:calc-target-axis-dimension rotation-axis translation-axis
[メソッド]


:calc-union-link-list link-list
[メソッド]


:calc-target-joint-dimension link-list
[メソッド]


:calc-inverse-jacobian jacobi &rest args &key ((:manipulability-limit ml) 0.1) ((:manipulability-gain mg) 0.001) weight debug-view ret wmat tmat umat umat2 mat-tmp mat-tmp-rc tmp-mrr tmp-mrr2 &allow-other-keys
[メソッド]


:calc-gradh-from-link-list link-list &optional (res (instantiate float-vector (length link-list)))
[メソッド]


:calc-joint-angle-speed union-vel &rest args &key angle-speed (angle-speed-blending 0.5) jacobi jacobi# null-space i-j#j debug-view weight wmat tmp-len tmp-len2 fik-len &allow-other-keys
[メソッド]


:calc-joint-angle-speed-gain union-link-list dav periodic-time
[メソッド]


:collision-avoidance-links &optional l
[メソッド]


:collision-avoidance-link-pair-from-link-list link-lists &key obstacles ((:collision-avoidance-links collision-links) collision-avoidance-links) debug
[メソッド]


:collision-avoidance-calc-distance &rest args &key union-link-list (warnp t) ((:collision-avoidance-link-pair pair-list)) ((:collision-distance-limit distance-limit) 10) &allow-other-keys
[メソッド]


:collision-avoidance-args pair link-list
[メソッド]


:collision-avoidance &rest args &key avoid-collision-distance avoid-collision-joint-gain avoid-collision-null-gain ((:collision-avoidance-link-pair pair-list)) (union-link-list) (link-list) (weight) (fik-len (send self :calc-target-joint-dimension union-link-list)) debug-view &allow-other-keys
[メソッド]


:move-joints union-vel &rest args &key union-link-list (periodic-time 0.05) (joint-args) (debug-view nil) (move-joints-hook) &allow-other-keys
[メソッド]


:find-joint-angle-limit-weight-old-from-union-link-list union-link-list
[メソッド]


:reset-joint-angle-limit-weight-old union-link-list
[メソッド]


:calc-weight-from-joint-limit avoid-weight-gain fik-len link-list union-link-list debug-view weight tmp-weight tmp-len
[メソッド]


:calc-inverse-kinematics-weight-from-link-list link-list &key (avoid-weight-gain 1.0) (union-link-list (send self :calc-union-link-list link-list)) (fik-len (send self :calc-target-joint-dimension union-link-list)) (weight (fill (instantiate float-vector fik-len) 1)) (additional-weight-list) (debug-view) (tmp-weight (instantiate float-vector fik-len)) (tmp-len (instantiate float-vector fik-len))
[メソッド]


:calc-nspace-from-joint-limit avoid-nspace-gain union-link-list weight debug-view tmp-nspace
[メソッド]


:calc-inverse-kinematics-nspace-from-link-list link-list &key (avoid-nspace-gain 0.01) (union-link-list (send self :calc-union-link-list link-list)) (fik-len (send self :calc-target-joint-dimension union-link-list)) (null-space) (debug-view) (additional-nspace-list) (cog-gain 0.0) (target-centroid-pos) (centroid-offset-func) (cog-translation-axis :z) (cog-null-space nil) (weight (fill (instantiate float-vector fik-len) 1.0)) (update-mass-properties t) (tmp-nspace (instantiate float-vector fik-len))
[メソッド]


:move-joints-avoidance union-vel &rest args &key union-link-list link-list (fik-len (send self :calc-target-joint-dimension union-link-list)) (weight (fill (instantiate float-vector fik-len) 1)) (null-space) (avoid-nspace-gain 0.01) (avoid-weight-gain 1.0) (avoid-collision-distance 200) (avoid-collision-null-gain 1.0) (avoid-collision-joint-gain 1.0) ((:collision-avoidance-link-pair pair-list) (send self :collision-avoidance-link-pair-from-link-list link-list :obstacles (cadr (memq :obstacles args)) :debug (cadr (memq :debug-view args)))) (cog-gain 0.0) (target-centroid-pos) (centroid-offset-func) (cog-translation-axis :z) (cog-null-space nil) (additional-weight-list) (additional-nspace-list) (tmp-len (instantiate float-vector fik-len)) (tmp-len2 (instantiate float-vector fik-len)) (tmp-weight (instantiate float-vector fik-len)) (tmp-nspace (instantiate float-vector fik-len)) (tmp-mcc (make-matrix fik-len fik-len)) (tmp-mcc2 (make-matrix fik-len fik-len)) (debug-view) (jacobi) &allow-other-keys
[メソッド]


:inverse-kinematics-args &rest args &key union-link-list rotation-axis translation-axis additional-jacobi-dimension &allow-other-keys
[メソッド]


:draw-collision-debug-view
[メソッド]


:ik-convergence-check success dif-pos dif-rot rotation-axis translation-axis thre rthre centroid-thre target-centroid-pos centroid-offset-func cog-translation-axis &key (update-mass-properties t)
[メソッド]


:calc-vel-from-pos dif-pos translation-axis &rest args &key (p-limit 100.0) (tmp-v0 (instantiate float-vector 0)) (tmp-v1 (instantiate float-vector 1)) (tmp-v2 (instantiate float-vector 2)) (tmp-v3 (instantiate float-vector 3)) &allow-other-keys
[メソッド]


:calc-vel-from-rot dif-rot rotation-axis &rest args &key (r-limit 0.5) (tmp-v0 (instantiate float-vector 0)) (tmp-v1 (instantiate float-vector 1)) (tmp-v2 (instantiate float-vector 2)) (tmp-v3 (instantiate float-vector 3)) &allow-other-keys
[メソッド]


:collision-check-pairs &key ((:links ls) (cons (car links) (all-child-links (car links))))
[メソッド]


:self-collision-check &key (mode :all) (pairs (send self :collision-check-pairs)) (collision-func 'pqp-collision-check)
[メソッド]



eusmodel-validity-check robot [関数]

Check if the robot model is validate


calc-jacobian-default-rotate-vector paxis world-default-coords child-reverse transform-coords tmp-v3 tmp-m33 [関数]



calc-jacobian-rotational fik row column joint paxis child-link world-default-coords child-reverse move-target transform-coords rotation-axis translation-axis tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33 [関数]



calc-jacobian-linear fik row column joint paxis child-link world-default-coords child-reverse move-target transform-coords rotation-axis translation-axis tmp-v0 tmp-v1 tmp-v2 tmp-v3 tmp-v3a tmp-v3b tmp-m33 [関数]



calc-angle-speed-gain-scalar j dav i periodic-time [関数]



calc-angle-speed-gain-vector j dav i periodic-time [関数]



all-child-links s &optional (pred #'identity) [関数]



calc-dif-with-axis dif axis &optional tmp-v0 tmp-v1 tmp-v2 [関数]



calc-target-joint-dimension joint-list [関数]



calc-joint-angle-min-max-for-limit-calculation j kk jamm [関数]



joint-angle-limit-weight j-l &optional (res (instantiate float-vector (calc-target-joint-dimension j-l))) [関数]



joint-angle-limit-nspace j-l &optional (res (instantiate float-vector (calc-target-joint-dimension j-l))) [関数]



calc-jacobian-from-link-list-including-robot-and-obj-virtual-joint link-list move-target obj-move-target robot &key (rotation-axis '(t t)) (translation-axis '(t t)) (fik (make-matrix (send robot :calc-target-axis-dimension rotation-axis translation-axis) (send robot :calc-target-joint-dimension link-list))) [関数]



append-obj-virtual-joint link-list target-coords &key (joint-class 6dof-joint) (joint-args) (vplink) (vplink-coords) (vclink-coords) [関数]



append-multiple-obj-virtual-joint link-list target-coords &key (joint-class '(6dof-joint)) (joint-args '(nil)) (vplink) (vplink-coords) (vclink-coords) [関数]



eusmodel-validity-check-one robot [関数]






bodyset [クラス]

  :super   cascaded-coords 

:slots (geometry::bodies :type cons)





\begin{emtabbing}
{\bf :init}
\it coords \&rest args \&key \= (name (intern (fo...
...d]\\
\> ((:bodies geometry::bs)) \\
\> \&allow-other-keys
\rm
\end{emtabbing}
Create bodyset object


:bodies &rest args [メソッド]


:faces
[メソッド]


:worldcoords
[メソッド]


:draw-on &rest args
[メソッド]



midcoords geometry::p geometry::c1 geometry::c2 [関数]

Returns mid (or p) coordinates of given two cooridnates c1 and c2


orient-coords-to-axis geometry::target-coords geometry::v &optional (geometry::axis :z) [関数]
orient 'axis' in 'target-coords' to the direction specified by 'v' destructively.
'v' must be non-zero vector.


geometry::face-to-triangle-aux geometry::f [関数]
triangulate the face.


geometry::face-to-triangle geometry::f [関数]
convert face to set of triangles.


geometry::face-to-tessel-triangle geometry::f geometry::num [関数]
return polygon if triangable, return nil if it is not.


body-to-faces geometry::abody [関数]
return triangled faces of given body


make-sphere geometry::r &rest args [関数]
make sphere of given r


make-ring geometry::ring-radius geometry::pipe-radius &rest args &key (geometry::segments 16) [関数]
make ring of given ring and pipe radius



\begin{emtabbing}
{\bf make-fan-cylinder}
\it geometry::radius geometry::height...
...
\> (angle 2pi) \\
\> (geometry::mid-angle (/ angle 2.0))
\rm
\end{emtabbing}
make a cylinder whose base face is a fan. the angle of fan
is defined by :angle keyword. and, the csg of the returned body is
(:cylinder radius height segments angle)


x-of-cube geometry::cub [関数]
return x of cube.


y-of-cube geometry::cub [関数]
return y of cube.


z-of-cube geometry::cub [関数]
return z of cube.


height-of-cylinder geometry::cyl [関数]
return height of cylinder.


radius-of-cylinder geometry::cyl [関数]
return radius of cylinder.


radius-of-sphere geometry::sp [関数]
return radius of shape.


geometry::make-faceset-from-vertices geometry::vs [関数]
create faceset from vertices.


matrix-to-euler-angle geometry::m geometry::axis-order [関数]
return euler angle from matrix.


geometry::quaternion-from-two-vectors geometry::a geometry::b [関数]
Comupute quaternion which rotate vector a into b.


transform-coords geometry::c1 geometry::c2 &optional (geometry::c3 (let ((geometry::dim (send geometry::c1 :dimension))) (instance coordinates :newcoords (unit-matrix geometry::dim) (instantiate float-vector geometry::dim)))) [関数]



geometry::face-to-triangle-rest-polygon geometry::f geometry::num geometry::edgs [関数]



geometry::face-to-triangle-make-simple geometry::f [関数]



body-to-triangles geometry::abody &optional (geometry::limit 50) [関数]



geometry::triangle-to-triangle geometry::aface &optional (geometry::limit 50) [関数]






robot-model [クラス]

  :super   cascaded-link 

:slots larm-end-coords rarm-end-coords lleg-end-coords rleg-end-coords head-end-coords torso-end-coords larm-root-link rarm-root-link lleg-root-link rleg-root-link head-root-link torso-root-link larm-collision-avoidance-links rarm-collision-avoidance-links larm rarm lleg rleg torso head force-sensors imu-sensors cameras support-polygons




:camera sensor-name [メソッド]
Returns camera with given name


:force-sensor sensor-name [メソッド]
Returns force sensor with given name


:imu-sensor sensor-name [メソッド]
Returns imu sensor of given name


:force-sensors [メソッド]
Returns force sensors.


:imu-sensors [メソッド]
Returns imu sensors.


:cameras [メソッド]
Returns camera sensors.


:look-at-hand l/r [メソッド]
look at hand position, l/r supports :rarm, :larm, :arms, and '(:rarm :larm)



\begin{emtabbing}
{\bf :inverse-kinematics}
\it target-coords \&rest args \&key...
...send mt :parent))) move-target))) \\
\> \&allow-other-keys
\rm
\end{emtabbing}
solve inverse kinematics, move move-target to target-coords
look-at-target suppots t, nil, float-vector, coords, list of float-vector, list of coords
link-list is set by default based on move-target ->root link link-list



\begin{emtabbing}
{\bf :inverse-kinematics-loop}
\it dif-pos dif-rot \&rest arg...
...send mt :parent))) move-target))) \\
\> \&allow-other-keys
\rm
\end{emtabbing}
move move-target using dif-pos and dif-rot,
look-at-target suppots t, nil, float-vector, coords, list of float-vector, list of coords
link-list is set by default based on move-target ->root link link-list


:look-at-target look-at-target &key (target-coords) [メソッド]
move robot head to look at targets, look-at-target support t/nil float-vector coordinates, center of list of float-vector or list of coordinates


:init-pose [メソッド]
Set robot to initial posture.



\begin{emtabbing}
{\bf :torque-vector}
\it\&key \= (force-list) \\lq  [method]\\
...
...ords))) :distribute-total-wrench-to-torque-method-default))
\rm
\end{emtabbing}
Returns torque vector



\begin{emtabbing}
{\bf :calc-force-from-joint-torque}
\it limb all-torque \&key...
...(send self limb :end-coords)) \\lq  [method]\\
\> (use-torso)
\rm
\end{emtabbing}
Calculates end-effector force and moment from joint torques.



\begin{emtabbing}
{\bf :fullbody-inverse-kinematics}
\it target-coords \&rest a...
...ll-space nil) \\
\> (min-loop 2) \\
\> \&allow-other-keys
\rm
\end{emtabbing}
fullbody inverse kinematics for legged robot.
necessary args : target-coords, move-target, and link-list must include legs' (or leg's) parameters
ex. (send robot:fullbody-inverse-kinematics (list rarm-tc rleg-tc lleg-tc) :move-target (list rarm-mt rleg-mt lleg-mt) :link-list (list rarm-ll rleg-ll lleg-ll))


:print-vector-for-robot-limb vec [メソッド]
Print angle vector with limb alingment and limb indent.
For example, if robot is rarm, larm, and torso, print result is:
#f(
rarm-j0 ... rarm-jN
larm-j0 ... larm-jN
torso-j0 ... torso-jN
)



\begin{emtabbing}
{\bf :calc-zmp-from-forces-moments}
\it forces moments \&key ...
...n-all-values t))) force-sensors forces moments cop-coords))
\rm
\end{emtabbing}
Calculate zmp[mm] from sensor local forces and moments
If force_z is large, zmp can be defined and returns 3D zmp.
Otherwise, zmp cannot be defined and returns nil.


:foot-midcoords &optional (mid 0.5) [メソッド]
Calculate midcoords of :rleg and :lleg end-coords.
In the following codes, leged robot is assumed.



\begin{emtabbing}
{\bf :fix-leg-to-coords}
\it fix-coords \&optional (l/r :both) \&key \= (mid 0.5) \\lq  [method]\\
\> \&allow-other-keys
\rm
\end{emtabbing}
Fix robot's legs to a coords
In the following codes, leged robot is assumed.



\begin{emtabbing}
{\bf :move-centroid-on-foot}
\it leg fix-limbs \&rest args \&...
...har93 f(0.1 0.1 0.0 0.0 0.0 0.5)) \\
\> \&allow-other-keys
\rm
\end{emtabbing}
Move robot COG to change centroid-on-foot location,
leg : legs for target of robot's centroid, which should be :both, :rleg, and :lleg.
fix-limbs : limb names which are fixed in this IK.



\begin{emtabbing}
{\bf :calc-walk-pattern-from-footstep-list}
\it footstep-list...
...k-thre 1) \\
\> (ik-rthre (deg2rad 1)) \\
\> (calc-zmp t)
\rm
\end{emtabbing}
Calculate walking pattern from foot step list and return pattern list as a list of angle-vector, root-coords, time, and so on.


:gen-footstep-parameter &key (ratio 1.0) [メソッド]
Generate footstep parameter



\begin{emtabbing}
{\bf :go-pos-params-\textgreater footstep-list}
\it xx yy th ...
...(assoc leg leg-translate-pos))))) (send cc :name leg) cc)))
\rm
\end{emtabbing}
Calculate foot step list from goal x position [mm], goal y position [mm], and goal yaw orientation [deg].


:go-pos-quadruped-params->footstep-list xx yy th &key (type :crawl) [メソッド]
Calculate foot step list for quadruped walking from goal x position [mm], goal y position [mm], and goal yaw orientation [deg].


:support-polygons [メソッド]
Return support polygons.


:support-polygon name [メソッド]
Return support polygon.
If name is list, return convex hull of all polygons.
Otherwise, return polygon with given name


:make-default-linear-link-joint-between-attach-coords attach-coords-0 attach-coords-1 end-coords-name linear-joint-name [メソッド]
Make default linear arctuator module such as muscle and cylinder and append lins and joint-list.
Module includes parent-link =>(j0) =>l0 =>(j1) =>l1 (linear actuator) =>(j2) =>l2 =>end-coords.
attach-coords-0 is root side coords which linear actulator is attached to.
attach-coords-1 is end side coords which linear actulator is attached to.
end-coords-name is the name of end-coords.
linear-joint-name is the name of linear actuator.



\begin{emtabbing}
{\bf :calc-static-balance-point}
\it\&key \= (target-points (...
...nd-coords :worldpos)) 2)) \\
\> (update-mass-properties t)
\rm
\end{emtabbing}
Calculate static balance point which is equivalent to static extended ZMP.
target-points are end-effector points on which force-list and moment-list apply.
force-list [N] and moment-list [Nm] are list of force and moment at target-points.
static-balance-point-height is height of static balance point [mm].


:init-ending [メソッド]


:rarm-end-coords
[メソッド]


:larm-end-coords
[メソッド]


:rleg-end-coords
[メソッド]


:lleg-end-coords
[メソッド]


:head-end-coords
[メソッド]


:torso-end-coords
[メソッド]


:rarm-root-link
[メソッド]


:larm-root-link
[メソッド]


:rleg-root-link
[メソッド]


:lleg-root-link
[メソッド]


:head-root-link
[メソッド]


:torso-root-link
[メソッド]


:limb limb method &rest args
[メソッド]


:inverse-kinematics-loop-for-look-at limb &rest args
[メソッド]


:gripper limb &rest args
[メソッド]


:get-sensor-method sensor-type sensor-name
[メソッド]


:get-sensors-method-by-limb sensors-type limb
[メソッド]


:larm &rest args
[メソッド]


:rarm &rest args
[メソッド]


:lleg &rest args
[メソッド]


:rleg &rest args
[メソッド]


:head &rest args
[メソッド]


:torso &rest args
[メソッド]


:arms &rest args
[メソッド]


:legs &rest args
[メソッド]


:distribute-total-wrench-to-torque-method-default
[メソッド]


:joint-angle-limit-nspace-for-6dof &key (avoid-nspace-gain 0.01) (limbs '(:rleg :lleg))
[メソッド]


:joint-order limb &optional jname-list
[メソッド]


:draw-gg-debug-view end-coords-list contact-state rz cog pz czmp dt
[メソッド]


:footstep-parameter
[メソッド]


:make-support-polygons
[メソッド]


:make-sole-polygon name
[メソッド]



make-default-robot-link len radius axis name &optional extbody [関数]




2016-04-05