You can subscribe to this list here.
2011 |
Jan
|
Feb
|
Mar
|
Apr
|
May
|
Jun
(9) |
Jul
(31) |
Aug
|
Sep
(15) |
Oct
(11) |
Nov
(15) |
Dec
(10) |
---|---|---|---|---|---|---|---|---|---|---|---|---|
2012 |
Jan
(11) |
Feb
(15) |
Mar
(36) |
Apr
(8) |
May
(11) |
Jun
(14) |
Jul
(16) |
Aug
(1) |
Sep
(8) |
Oct
(37) |
Nov
(4) |
Dec
(3) |
2013 |
Jan
(1) |
Feb
(7) |
Mar
(17) |
Apr
(29) |
May
(23) |
Jun
(45) |
Jul
(8) |
Aug
(13) |
Sep
(7) |
Oct
(11) |
Nov
(25) |
Dec
(40) |
2014 |
Jan
(23) |
Feb
(34) |
Mar
(1) |
Apr
(8) |
May
(50) |
Jun
|
Jul
(2) |
Aug
|
Sep
(7) |
Oct
|
Nov
|
Dec
|
2015 |
Jan
(6) |
Feb
|
Mar
|
Apr
|
May
|
Jun
|
Jul
|
Aug
|
Sep
|
Oct
|
Nov
|
Dec
|
From: <ky...@us...> - 2014-02-25 06:52:36
|
Revision: 1076 http://sourceforge.net/p/jskeus/code/1076 Author: kyouhei Date: 2014-02-25 06:52:31 +0000 (Tue, 25 Feb 2014) Log Message: ----------- update generate-histogram-hs Modified Paths: -------------- trunk/irteus/irtpointcloud.l Modified: trunk/irteus/irtpointcloud.l =================================================================== --- trunk/irteus/irtpointcloud.l 2014-02-20 17:23:15 UTC (rev 1075) +++ trunk/irteus/irtpointcloud.l 2014-02-25 06:52:31 UTC (rev 1076) @@ -397,10 +397,17 @@ ret))) ))) ;;(:remove-outlier ()) - (:generate-color-histogram-hs (&key (h-step 3) (s-step 3)) - (flet ((get-bin (d step max-num) + (:generate-color-histogram-hs + (&key (h-step 9) (s-step 7) + (hlimits (cons 360.0 0.0)) + (vlimits (cons 1.0 0.15)) + (slimits (cons 1.0 0.25)) + (rotate-hue) (color-scale 255.0) + (sizelimits 1)) + (flet ((get-bin (d step max-num min-num) (if (>= d max-num) (- step 1) - (let ((ret (floor (/ d (/ (- max-num 0.0) step))))) + (let ((ret (floor (/ (- d min-num) + (/ (- max-num min-num) step))))) (if (>= ret step) (- step 1) (if (<= ret 0) 0 ret)))))) (let* ((col (send self :colors)) @@ -408,16 +415,35 @@ (list h-step s-step) :element-type float-vector)) (hvec (array-entity hist)) - (cinst (instantiate float-vector 3))) + (cinst (instantiate float-vector 3)) + (cntr 0)) (dotimes (i (send self :size)) (c-matrix-row col i cinst) - (let* ((his (rgb2his cinst)) - (h-bin (get-bin (elt his 0) h-step 360.0)) - (s-bin (get-bin (elt his 2) s-step 1.0))) - (setf (elt hvec (+ (* h-bin s-step) s-bin)) - (+ 1 (elt hvec (+ (* h-bin s-step) s-bin)))) + (if color-scale (scale color-scale cinst cinst)) + (let ((his (rgb2his cinst))) + (when rotate-hue ;; rotate color ring + (let* ((tmp-h (elt his 0))) + (if (>= (+ tmp-h rotate-hue) 360.0) + (setf (elt his 0) (+ tmp-h rotate-hue -360.0)) + (if (<= (+ tmp-h rotate-hue) 0.0) + (setf (elt his 0) (+ tmp-h rotate-hue 360.0)) + (setf (elt his 0) (+ tmp-h rotate-hue)))))) + (when (and (>= (car hlimits) (elt his 0) (cdr hlimits)) + (>= (car vlimits) (elt his 1) (cdr vlimits)) + (>= (car slimits) (elt his 2) (cdr slimits))) + (incf cntr) + (let ((h-bin (get-bin (elt his 0) h-step (car hlimits) (cdr hlimits))) + (s-bin (get-bin (elt his 2) s-step (car slimits) (cdr slimits)))) + (setf (elt hvec (+ (* h-bin s-step) s-bin)) + (+ 1 (elt hvec (+ (* h-bin s-step) s-bin)))) + )) )) - (scale-matrix (/ 1.0 (send self :size)) hist)) + (if (or (not sizelimits) + (>= cntr sizelimits)) + (scale-matrix (/ 1.0 cntr) hist hist) + (setq hist nil)) + ;; (format t "~A/~A~%" cntr (send self :size)) + hist) )) ;; (:copy-from (pc) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <sn...@us...> - 2014-02-20 17:23:18
|
Revision: 1075 http://sourceforge.net/p/jskeus/code/1075 Author: snozawa Date: 2014-02-20 17:23:15 +0000 (Thu, 20 Feb 2014) Log Message: ----------- update ;; reduce duplicate codes in difference-cog-position Modified Paths: -------------- trunk/irteus/irtdyna.l Modified: trunk/irteus/irtdyna.l =================================================================== --- trunk/irteus/irtdyna.l 2014-02-19 20:52:18 UTC (rev 1074) +++ trunk/irteus/irtdyna.l 2014-02-20 17:23:15 UTC (rev 1075) @@ -457,26 +457,22 @@ target-centroid-pos centroid-offset-func) (scale (* 0.001 cog-gain) ;; [mm] -> [m] - (calc-dif-with-axis - (let ((current-centroid-pos - (if (functionp centroid-offset-func) - (funcall centroid-offset-func) - (send self :centroid nil)))) - (send self :put :ik-draw-on-params - (append (send self :get :ik-draw-on-params) - (list (list target-centroid-pos :color #f(0 0 1)) - (list (float-vector (elt current-centroid-pos 0) (elt current-centroid-pos 1) (elt target-centroid-pos 2)) :size 100 :color #f(0 1 0))))) - (v- target-centroid-pos current-centroid-pos)) - translation-axis) - )) + (send self :difference-cog-position + target-centroid-pos centroid-offset-func translation-axis t))) (:difference-cog-position - (target-centroid-pos &optional (centroid-offset-func) (translation-axis :z)) - (calc-dif-with-axis - (v- target-centroid-pos - (if (functionp centroid-offset-func) - (funcall centroid-offset-func) - (send self :centroid))) - translation-axis)) + (target-centroid-pos &optional (centroid-offset-func) (translation-axis :z) (add-draw-on-param)) + (let ((current-centroid-pos + (if (functionp centroid-offset-func) + (funcall centroid-offset-func) + (send self :centroid)))) + (if add-draw-on-param + (send self :put :ik-draw-on-params + (append (send self :get :ik-draw-on-params) + (list (list target-centroid-pos :color #f(0 0 1)) + (list (float-vector (elt current-centroid-pos 0) (elt current-centroid-pos 1) (elt target-centroid-pos 2)) :size 100 :color #f(0 1 0)))))) + (calc-dif-with-axis + (v- target-centroid-pos current-centroid-pos) + translation-axis))) (:cog-convergence-check (centroid-thre target-centroid-pos &optional centroid-offset-func) (let ((cdiff This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <ky...@us...> - 2014-02-19 20:52:21
|
Revision: 1074 http://sourceforge.net/p/jskeus/code/1074 Author: kyouhei Date: 2014-02-19 20:52:18 +0000 (Wed, 19 Feb 2014) Log Message: ----------- fix wrong size of indices on :convert-to-faces Modified Paths: -------------- trunk/irteus/irtgl.l Modified: trunk/irteus/irtgl.l =================================================================== --- trunk/irteus/irtgl.l 2014-02-19 11:32:14 UTC (rev 1073) +++ trunk/irteus/irtgl.l 2014-02-19 20:52:18 UTC (rev 1074) @@ -729,22 +729,24 @@ (:convert-to-faces (&rest args &key (wrt :local) &allow-other-keys) ;; check-normal <-> check-vertices-order, add face-color (let (ret) (dolist (mesh mesh-list) - (let ((vlst (cadr (assoc :vertices mesh))) - (nlst (cadr (assoc :normals mesh))) - (idces (cadr (assoc :indices mesh))) - (tp (cadr (assoc :type mesh))) - mesh-size lst) + (let* ((vlst (cadr (assoc :vertices mesh))) + (nlst (cadr (assoc :normals mesh))) + (idces (cadr (assoc :indices mesh))) + (idlen (length idces)) + (tp (cadr (assoc :type mesh))) + mesh-size lst) (case tp (:triangles (setq mesh-size 3)) (:quads (setq mesh-size 4)) (t (warn ";; not supported mesh type -> ~A" tp) (return-from :convert-to-faces))) + (setq idlen (* (/ idlen mesh-size) mesh-size)) ;; convert from self coords (cond (idces (do ((i 0 (+ i 1)) (v 0 (+ v mesh-size))) - ((>= v (length idces))) + ((>= v idlen)) (let (vs ns) (dotimes (j mesh-size) (push (user::c-matrix-row vlst (elt idces (+ v j))) vs) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <sn...@us...> - 2014-02-19 11:32:18
|
Revision: 1073 http://sourceforge.net/p/jskeus/code/1073 Author: snozawa Date: 2014-02-19 11:32:14 +0000 (Wed, 19 Feb 2014) Log Message: ----------- fix to use eps ;; use 1.0e-5 which is previous version's value Modified Paths: -------------- trunk/irteus/irtmath.l Modified: trunk/irteus/irtmath.l =================================================================== --- trunk/irteus/irtmath.l 2014-02-19 09:57:31 UTC (rev 1072) +++ trunk/irteus/irtmath.l 2014-02-19 11:32:14 UTC (rev 1073) @@ -292,9 +292,9 @@ (remprop 'normalize-vector 'compiler::builtin-function-entry) (setf (symbol-function 'normalize-vector-org) (symbol-function 'normalize-vector)) (comp::def-builtin-entry 'NORMALIZE-VECTOR-ORG "VNORMALIZE")) -(defun normalize-vector (v &optional r (eps *epsilon*)) +(defun normalize-vector (v &optional r (eps 1.0e-5)) "normalize-vector #f(0 0 0)->#f(0 0 0)." - (if (< (norm v) *epsilon*) + (if (< (norm v) eps) (if r (fill r 0) (instantiate float-vector (length v))) (if r (normalize-vector-org v r) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <sn...@us...> - 2014-02-19 09:57:33
|
Revision: 1072 http://sourceforge.net/p/jskeus/code/1072 Author: snozawa Date: 2014-02-19 09:57:31 +0000 (Wed, 19 Feb 2014) Log Message: ----------- enable to set normalize vector zero division check ;; reduce normalize-vector torellance in matrix-log because default threshold 1e-5 is too large for radian representation Modified Paths: -------------- trunk/irteus/irtmath.l Modified: trunk/irteus/irtmath.l =================================================================== --- trunk/irteus/irtmath.l 2014-02-19 09:43:44 UTC (rev 1071) +++ trunk/irteus/irtmath.l 2014-02-19 09:57:31 UTC (rev 1072) @@ -156,7 +156,7 @@ (setq th (- th 2pi))) ((< th -pi) (setq th (+ th 2pi)))) - (scale th (normalize-vector q)))) + (scale th (normalize-vector q nil 1e-20)))) (defun matrix-exponent (omega &optional (p 1.0)) (let (w amat) @@ -292,9 +292,9 @@ (remprop 'normalize-vector 'compiler::builtin-function-entry) (setf (symbol-function 'normalize-vector-org) (symbol-function 'normalize-vector)) (comp::def-builtin-entry 'NORMALIZE-VECTOR-ORG "VNORMALIZE")) -(defun normalize-vector (v &optional r) +(defun normalize-vector (v &optional r (eps *epsilon*)) "normalize-vector #f(0 0 0)->#f(0 0 0)." - (if (< (norm v) 1.0e-5) + (if (< (norm v) *epsilon*) (if r (fill r 0) (instantiate float-vector (length v))) (if r (normalize-vector-org v r) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <sn...@us...> - 2014-02-19 09:43:48
|
Revision: 1071 http://sourceforge.net/p/jskeus/code/1071 Author: snozawa Date: 2014-02-19 09:43:44 +0000 (Wed, 19 Feb 2014) Log Message: ----------- check 0 division reported by kuroiwa Modified Paths: -------------- trunk/irteus/irtrobot.l Modified: trunk/irteus/irtrobot.l =================================================================== --- trunk/irteus/irtrobot.l 2014-02-19 09:39:39 UTC (rev 1070) +++ trunk/irteus/irtrobot.l 2014-02-19 09:43:44 UTC (rev 1071) @@ -464,24 +464,26 @@ (limbs '(:rleg :lleg)) (force-sensors (mapcar #'(lambda (l) (send self :force-sensor l)) limbs)) (cop-coords (mapcar #'(lambda (l) (send self l :end-coords)) limbs)) - (fz-thre 50) ;; [N] + (fz-thre 1e-3) ;; [N] (limb-cop-fz-list (mapcar #'(lambda (fs f m cc) (let ((fsp (scale 1e-3 (send fs :worldpos))) ;; [mm]->[m] (nf (send fs :rotate-vector f)) (nm (send fs :rotate-vector m))) (send self :calc-cop-from-force-moment - nf nm fs cc :fz-thre 0 :return-all-values t))) + nf nm fs cc :fz-thre fz-thre :return-all-values t))) force-sensors forces moments cop-coords))) (let* ((limb-cop-fz-list2 (remove nil limb-cop-fz-list)) - (limb-fz (reduce #'+ (mapcar #'(lambda (x) (cadr (memq :fz x))) limb-cop-fz-list2) :initial-value 0)) - (tmpzmp (scale (/ 1.0 limb-fz) (reduce #'v+ (mapcar #'(lambda (x) (scale (cadr (memq :fz x)) (cadr (memq :cop x)))) limb-cop-fz-list2))))) - (cond - ((< limb-fz fz-thre) nil) - ((eq wrt :world) tmpzmp) - ((eq wrt :local) (send (car (send self :links)) :inverse-transform-vector tmpzmp)) - (t ) - ))) + (limb-fz (reduce #'+ (mapcar #'(lambda (x) (cadr (memq :fz x))) limb-cop-fz-list2) :initial-value 0))) + (if (< limb-fz fz-thre) + nil + (let ((tmpzmp (scale (/ 1.0 limb-fz) (reduce #'v+ (mapcar #'(lambda (x) (scale (cadr (memq :fz x)) (cadr (memq :cop x)))) limb-cop-fz-list2))))) + (cond + ((eq wrt :world) tmpzmp) + ((eq wrt :local) (send (car (send self :links)) :inverse-transform-vector tmpzmp)) + (t ) + ))) + )) ) ;;; moved from rbrarin libraries This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <sn...@us...> - 2014-02-19 09:39:43
|
Revision: 1070 http://sourceforge.net/p/jskeus/code/1070 Author: snozawa Date: 2014-02-19 09:39:39 +0000 (Wed, 19 Feb 2014) Log Message: ----------- use limb-cop-fz-list2 instead of limb-cop-fz-list reported by kuroiwa Modified Paths: -------------- trunk/irteus/irtrobot.l Modified: trunk/irteus/irtrobot.l =================================================================== --- trunk/irteus/irtrobot.l 2014-02-19 09:14:04 UTC (rev 1069) +++ trunk/irteus/irtrobot.l 2014-02-19 09:39:39 UTC (rev 1070) @@ -474,8 +474,8 @@ nf nm fs cc :fz-thre 0 :return-all-values t))) force-sensors forces moments cop-coords))) (let* ((limb-cop-fz-list2 (remove nil limb-cop-fz-list)) - (limb-fz (reduce #'+ (mapcar #'(lambda (x) (cadr (memq :fz x))) limb-cop-fz-list) :initial-value 0)) - (tmpzmp (scale (/ 1.0 limb-fz) (reduce #'v+ (mapcar #'(lambda (x) (scale (cadr (memq :fz x)) (cadr (memq :cop x)))) limb-cop-fz-list))))) + (limb-fz (reduce #'+ (mapcar #'(lambda (x) (cadr (memq :fz x))) limb-cop-fz-list2) :initial-value 0)) + (tmpzmp (scale (/ 1.0 limb-fz) (reduce #'v+ (mapcar #'(lambda (x) (scale (cadr (memq :fz x)) (cadr (memq :cop x)))) limb-cop-fz-list2))))) (cond ((< limb-fz fz-thre) nil) ((eq wrt :world) tmpzmp) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <sn...@us...> - 2014-02-19 09:14:07
|
Revision: 1069 http://sourceforge.net/p/jskeus/code/1069 Author: snozawa Date: 2014-02-19 09:14:04 +0000 (Wed, 19 Feb 2014) Log Message: ----------- merge reference zmp list to robot state list Modified Paths: -------------- trunk/irteus/demo/walk-motion.l trunk/irteus/irtdyna.l Modified: trunk/irteus/demo/walk-motion.l =================================================================== --- trunk/irteus/demo/walk-motion.l 2014-02-19 09:05:20 UTC (rev 1068) +++ trunk/irteus/demo/walk-motion.l 2014-02-19 09:14:04 UTC (rev 1069) @@ -216,8 +216,8 @@ ;; input motion : control ZMP at 0 based on COG model ;; output motion : control ZMP at 0 based on multi-body model (defun test-preview-control-dynamics-filter - (robot &key reference-zmp-list (preview-class preview-control) (cog-method :move-base-pos) (dt 0.025)) - (let ((dt 0.025) (avs)) + (robot &key (preview-class preview-control) (cog-method :move-base-pos) (dt 0.025)) + (let ((avs)) (objects (list robot)) ;; generate input motion control ZMP at 0, which corresponds to COG at 0 in this case (send robot :reset-pose) @@ -226,7 +226,9 @@ (send robot :arms :shoulder-p :joint-angle (+ -20 (* -45 (sin (* 6 (deg2rad i)))))) (send robot :move-centroid-on-foot :both '(:lleg :rleg)) (push (list :angle-vector (send robot :angle-vector) - :root-coords (send (car (send robot :links)) :copy-worldcoords)) avs)) + :root-coords (send (car (send robot :links)) :copy-worldcoords) + :refzmp (apply #'midpoint 0.5 (send robot :legs :end-coords :worldpos))) + avs)) (setq avs (reverse avs)) ;; filtering (let ((data (subseq (send robot :preview-control-dynamics-filter dt avs) 4))) Modified: trunk/irteus/irtdyna.l =================================================================== --- trunk/irteus/irtdyna.l 2014-02-19 09:05:20 UTC (rev 1068) +++ trunk/irteus/irtdyna.l 2014-02-19 09:14:04 UTC (rev 1069) @@ -1048,8 +1048,7 @@ (:preview-control-dynamics-filter (dt ;; [s] avs ;; input motion : (list (list :angle-vector av :root-coords rc) ....) - &key reference-zmp-list - (preview-class preview-control) + &key (preview-class preview-control) (cog-method :move-base-pos) (delay 0.8)) ;; [s] ;; generate av-list @@ -1063,7 +1062,7 @@ (r)) (dotimes (i 2) (send self :calc-zmp)) (let ((ret-list) (last-av) (ret-avs) (last-zmp) (av) - (avs (copy-object avs)) (reference-zmp-list (copy-object reference-zmp-list))) + (avs (copy-object avs))) (while (not (send df :finishedp)) (setq av (pop avs)) (if av @@ -1075,13 +1074,7 @@ (send self :angle-vector) (send self :copy-worldcoords) :dt dt)) - (rzmp (let ((tmp-zmp - (cond - (reference-zmp-list (pop reference-zmp-list)) - ((find-method :calc-target-centroid-pos self) - (send self :calc-target-centroid-pos :both '(:rleg :lleg))) - (t (apply #'midpoint 0.5 (send self :legs :end-coords :worldpos)))) - )) + (rzmp (let ((tmp-zmp (cadr (memq :refzmp av)))) (if tmp-zmp (setq last-zmp tmp-zmp) last-zmp))) (dzmp (v- zmp rzmp))) (setq r (send df :update (list av zmp (copy-object (send self :centroid)) rzmp) (if av dzmp nil))) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <sn...@us...> - 2014-02-19 09:05:27
|
Revision: 1068 http://sourceforge.net/p/jskeus/code/1068 Author: snozawa Date: 2014-02-19 09:05:20 +0000 (Wed, 19 Feb 2014) Log Message: ----------- update robot state list Modified Paths: -------------- trunk/irteus/demo/walk-motion.l trunk/irteus/irtdyna.l Modified: trunk/irteus/demo/walk-motion.l =================================================================== --- trunk/irteus/demo/walk-motion.l 2014-02-19 08:52:18 UTC (rev 1067) +++ trunk/irteus/demo/walk-motion.l 2014-02-19 09:05:20 UTC (rev 1068) @@ -212,19 +212,24 @@ tm-list (reverse zmp-list) (reverse cog-list) (reverse ref-zmp-list2)) )) +;; dynamics filter by using preview control +;; input motion : control ZMP at 0 based on COG model +;; output motion : control ZMP at 0 based on multi-body model (defun test-preview-control-dynamics-filter (robot &key reference-zmp-list (preview-class preview-control) (cog-method :move-base-pos) (dt 0.025)) (let ((dt 0.025) (avs)) (objects (list robot)) - ;; generate av-list + ;; generate input motion control ZMP at 0, which corresponds to COG at 0 in this case (send robot :reset-pose) (send robot :fix-leg-to-coords (make-coords) '(:rleg :lleg)) (dotimes (i 180) (send robot :arms :shoulder-p :joint-angle (+ -20 (* -45 (sin (* 6 (deg2rad i)))))) (send robot :move-centroid-on-foot :both '(:lleg :rleg)) - (push (list (send robot :angle-vector) (send (car (send robot :links)) :copy-worldcoords)) avs)) + (push (list :angle-vector (send robot :angle-vector) + :root-coords (send (car (send robot :links)) :copy-worldcoords)) avs)) (setq avs (reverse avs)) - (let ((data (send robot :preview-control-dynamics-filter dt avs))) + ;; filtering + (let ((data (subseq (send robot :preview-control-dynamics-filter dt avs) 4))) (with-open-file (f "/tmp/test-preview-control-data-2.dat" :direction :output) (mapcar #'(lambda (tm ozmp-x izmp-x ocog-x icog-x ozmp-y izmp-y ocog-y icog-y) Modified: trunk/irteus/irtdyna.l =================================================================== --- trunk/irteus/irtdyna.l 2014-02-19 08:52:18 UTC (rev 1067) +++ trunk/irteus/irtdyna.l 2014-02-19 09:05:20 UTC (rev 1068) @@ -1046,7 +1046,8 @@ ;; preview filter (:preview-control-dynamics-filter - (dt avs + (dt ;; [s] + avs ;; input motion : (list (list :angle-vector av :root-coords rc) ....) &key reference-zmp-list (preview-class preview-control) (cog-method :move-base-pos) @@ -1054,8 +1055,8 @@ ;; generate av-list (labels ((update-robot-state (av) - (send self :angle-vector (car av)) - (send self :newcoords (cadr av)))) + (send self :angle-vector (cadr (memq :angle-vector av))) + (send self :move-coords (cadr (memq :root-coords av)) (car (send self :links))))) (update-robot-state (car avs)) (let ((df (instance preview-dynamics-filter :init dt (elt (send self :centroid) 2) preview-class :delay delay)) @@ -1086,7 +1087,8 @@ (setq r (send df :update (list av zmp (copy-object (send self :centroid)) rzmp) (if av dzmp nil))) (when r (push (list (send df :av) r) ret-list) - (let ((pav (send self :angle-vector)) (prc (send self :copy-worldcoords))) + (let ((pav (send self :angle-vector)) + (prc (send self :copy-worldcoords))) (update-robot-state (car (send df :av))) (case cog-method (:move-centroid-on-foot @@ -1098,12 +1100,11 @@ (send self :translate (float-vector (- (elt (send df :refcog) 0)) (- (elt (send df :refcog) 1)) 0) :world) (mapcar #'(lambda (l ttc) (send self l :inverse-kinematics ttc :thre 0.1 :rthre (deg2rad 0.1))) - '(:rleg :lleg) tc)) - ;; (send self :move-base-pos - ;; (float-vector (- (elt (send df :refcog) 0)) (- (elt (send df :refcog) 1)) 0) '(:rleg :lleg)) - ) + '(:rleg :lleg) tc))) ) - (push (list (send self :angle-vector) (send self :copy-worldcoords)) ret-avs) + (push (list :angle-vector (send self :angle-vector) + :root-coords (send (car (send self :links)) :copy-worldcoords)) + ret-avs) (send self :angle-vector pav) (send self :newcoords prc) ) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <sn...@us...> - 2014-02-19 08:52:21
|
Revision: 1067 http://sourceforge.net/p/jskeus/code/1067 Author: snozawa Date: 2014-02-19 08:52:18 +0000 (Wed, 19 Feb 2014) Log Message: ----------- add example for preview control dynamics filter Modified Paths: -------------- trunk/irteus/demo/walk-motion.l trunk/irteus/irtdyna.l Modified: trunk/irteus/demo/walk-motion.l =================================================================== --- trunk/irteus/demo/walk-motion.l 2014-02-19 08:50:48 UTC (rev 1066) +++ trunk/irteus/demo/walk-motion.l 2014-02-19 08:52:18 UTC (rev 1067) @@ -207,8 +207,53 @@ ;; gnuplot> plot '/tmp/test-preview-control-data.dat' using 1:2 title "cart zmp" with lines ;; gnuplot> replot '/tmp/test-preview-control-data.dat' using 1:3 title "cog" with lines ;; gnuplot> replot '/tmp/test-preview-control-data.dat' using 1:4 title "refzmp" with lines - (list :time-list - tm-list - :data-list - (list (reverse zmp-list) (reverse cog-list) (reverse ref-zmp-list2))) + (mapcar #'(lambda (tm zmp cog refzmp) + (list :time tm :zmp zmp :cog cog :refzmp refzmp)) + tm-list (reverse zmp-list) (reverse cog-list) (reverse ref-zmp-list2)) )) + +(defun test-preview-control-dynamics-filter + (robot &key reference-zmp-list (preview-class preview-control) (cog-method :move-base-pos) (dt 0.025)) + (let ((dt 0.025) (avs)) + (objects (list robot)) + ;; generate av-list + (send robot :reset-pose) + (send robot :fix-leg-to-coords (make-coords) '(:rleg :lleg)) + (dotimes (i 180) + (send robot :arms :shoulder-p :joint-angle (+ -20 (* -45 (sin (* 6 (deg2rad i)))))) + (send robot :move-centroid-on-foot :both '(:lleg :rleg)) + (push (list (send robot :angle-vector) (send (car (send robot :links)) :copy-worldcoords)) avs)) + (setq avs (reverse avs)) + (let ((data (send robot :preview-control-dynamics-filter dt avs))) + (with-open-file + (f "/tmp/test-preview-control-data-2.dat" :direction :output) + (mapcar #'(lambda (tm ozmp-x izmp-x ocog-x icog-x ozmp-y izmp-y ocog-y icog-y) + (format f "~A ~A ~A ~A ~A ~A ~A ~A ~A~%" tm ozmp-x izmp-x ocog-x icog-x ozmp-y izmp-y ocog-y icog-y)) + (mapcar #'(lambda (x) (cadr (memq :time x))) data) + (mapcar #'(lambda (x) (elt (cadr (memq :output-zmp x)) 0)) data) + (mapcar #'(lambda (x) (elt (cadr (memq :input-zmp x)) 0)) data) + (mapcar #'(lambda (x) (elt (cadr (memq :output-cog x)) 0)) data) + (mapcar #'(lambda (x) (elt (cadr (memq :input-cog x)) 0)) data) + (mapcar #'(lambda (x) (elt (cadr (memq :output-zmp x)) 1)) data) + (mapcar #'(lambda (x) (elt (cadr (memq :input-zmp x)) 1)) data) + (mapcar #'(lambda (x) (elt (cadr (memq :output-cog x)) 1)) data) + (mapcar #'(lambda (x) (elt (cadr (memq :input-cog x)) 1)) data) + )) + ;; gnuplot sample + ;; $ gnuplot + ;; gnuplot> set xlabel "Time [s]" + ;; gnuplot> set ylabel "ZMP X [mm]" + ;; gnuplot> plot '/tmp/test-preview-control-data-2.dat' using 1:2 title "output zmp" with lines + ;; gnuplot> replot '/tmp/test-preview-control-data-2.dat' using 1:3 title "input zmp" with lines + ;; gnuplot> replot '/tmp/test-preview-control-data-2.dat' using 1:4 title "output cog" with lines + ;; gnuplot> replot '/tmp/test-preview-control-data-2.dat' using 1:5 title "input cog" with lines + data + ))) + +(defun test-preview-control-dynamics-filter-for-sample-robot + () + (unless (boundp '*robot*) + (setq *robot* (instance sample-robot :init))) + (test-preview-control-dynamics-filter *robot*) + ) + Modified: trunk/irteus/irtdyna.l =================================================================== --- trunk/irteus/irtdyna.l 2014-02-19 08:50:48 UTC (rev 1066) +++ trunk/irteus/irtdyna.l 2014-02-19 08:52:18 UTC (rev 1067) @@ -1043,6 +1043,99 @@ (&optional (update-mass-properties t)) (if update-mass-properties (send self :update-mass-properties)) (send (car (send self :links)) :get :c-til)) + + ;; preview filter + (:preview-control-dynamics-filter + (dt avs + &key reference-zmp-list + (preview-class preview-control) + (cog-method :move-base-pos) + (delay 0.8)) ;; [s] + ;; generate av-list + (labels ((update-robot-state + (av) + (send self :angle-vector (car av)) + (send self :newcoords (cadr av)))) + (update-robot-state (car avs)) + (let ((df (instance preview-dynamics-filter + :init dt (elt (send self :centroid) 2) preview-class :delay delay)) + (r)) + (dotimes (i 2) (send self :calc-zmp)) + (let ((ret-list) (last-av) (ret-avs) (last-zmp) (av) + (avs (copy-object avs)) (reference-zmp-list (copy-object reference-zmp-list))) + (while (not (send df :finishedp)) + (setq av (pop avs)) + (if av + (progn + (update-robot-state av) + (setq last-av av)) + (update-robot-state last-av)) + (let* ((zmp (send self :calc-zmp + (send self :angle-vector) + (send self :copy-worldcoords) + :dt dt)) + (rzmp (let ((tmp-zmp + (cond + (reference-zmp-list (pop reference-zmp-list)) + ((find-method :calc-target-centroid-pos self) + (send self :calc-target-centroid-pos :both '(:rleg :lleg))) + (t (apply #'midpoint 0.5 (send self :legs :end-coords :worldpos)))) + )) + (if tmp-zmp (setq last-zmp tmp-zmp) last-zmp))) + (dzmp (v- zmp rzmp))) + (setq r (send df :update (list av zmp (copy-object (send self :centroid)) rzmp) (if av dzmp nil))) + (when r + (push (list (send df :av) r) ret-list) + (let ((pav (send self :angle-vector)) (prc (send self :copy-worldcoords))) + (update-robot-state (car (send df :av))) + (case cog-method + (:move-centroid-on-foot + (send self :move-centroid-on-foot :both '(:lleg :rleg) + :centroid-thre 0.1 + :target-centroid-pos (v- (send self :centroid) (send df :refcog)))) + (:move-base-pos + (let ((tc (mapcar #'(lambda (l) (send self l :end-coords :copy-worldcoords)) '(:rleg :lleg)))) + (send self :translate (float-vector (- (elt (send df :refcog) 0)) (- (elt (send df :refcog) 1)) 0) :world) + (mapcar #'(lambda (l ttc) + (send self l :inverse-kinematics ttc :thre 0.1 :rthre (deg2rad 0.1))) + '(:rleg :lleg) tc)) + ;; (send self :move-base-pos + ;; (float-vector (- (elt (send df :refcog) 0)) (- (elt (send df :refcog) 1)) 0) '(:rleg :lleg)) + ) + ) + (push (list (send self :angle-vector) (send self :copy-worldcoords)) ret-avs) + (send self :angle-vector pav) + (send self :newcoords prc) + ) + ) + )) + (setq ret-avs (reverse ret-avs) ret-list (reverse ret-list)) + (update-robot-state (car ret-avs)) + (dotimes (i 2) (send self :calc-zmp)) + (objects (list self)) + (let* ((tm (- dt)) + (data + (mapcar + #'(lambda (av ret) + (update-robot-state av) + (let ((zmp (send self :calc-zmp + (send self :angle-vector) + (send self :copy-worldcoords) + :dt dt))) + (send *viewer* :draw-objects :flush nil) + (send (caddr (car ret)) :draw-on :flush nil :size 400) + (send (send self :centroid) :draw-on :flush nil :size 300 :color #f(1 0 0)) + (send (cadr (car ret)) :draw-on :flush nil :size 400) + (send zmp :draw-on :flush t :size 300 :color #f(1 0 0)) + (unix:usleep 10000) + (setq tm (+ tm dt)) + (list :time tm :output-zmp zmp :input-zmp (cadr (car ret)) + :output-cog (send self :centroid nil) + :input-cog (cadddr (car ret))) + )) + ret-avs ret-list))) + (mapcar #'(lambda (x y) (append x y)) ret-avs data) + ))))) ) ;;; This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <sn...@us...> - 2014-02-19 08:50:51
|
Revision: 1066 http://sourceforge.net/p/jskeus/code/1066 Author: snozawa Date: 2014-02-19 08:50:48 +0000 (Wed, 19 Feb 2014) Log Message: ----------- fix calculation of torellance Modified Paths: -------------- trunk/irteus/irtmodel.l Modified: trunk/irteus/irtmodel.l =================================================================== --- trunk/irteus/irtmodel.l 2014-02-18 10:20:10 UTC (rev 1065) +++ trunk/irteus/irtmodel.l 2014-02-19 08:50:48 UTC (rev 1066) @@ -413,7 +413,7 @@ ;; if relative t ;; v is calculated from difference-rotation or jacobian (let ((vec (map float-vector #'deg2rad v))) - (unless (eps= (rad2deg (norm vec)) 0.0 1e-20) + (unless (eps= (norm vec) 0.0 1e-20) (m* (rotation-matrix (norm vec) (normalize-vector vec)) drot drot)))) ;; min max check (let* ((dr (map float-vector #'rad2deg (matrix-log drot)))) @@ -553,7 +553,7 @@ (setq drot (matrix-exponent (map float-vector #'deg2rad (subseq joint-angle 3 6)))) (if relative (let ((vec (map float-vector #'deg2rad (subseq v 3 6)))) - (unless (eps= (rad2deg (norm vec)) 0.0 1e-20) + (unless (eps= (norm vec) 0.0 1e-20) (m* (rotation-matrix (norm vec) (normalize-vector vec)) drot drot)))) ;; min max check (let* ((dr (map float-vector #'rad2deg (matrix-log drot)))) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <ky...@us...> - 2014-02-18 10:20:14
|
Revision: 1065 http://sourceforge.net/p/jskeus/code/1065 Author: kyouhei Date: 2014-02-18 10:20:10 +0000 (Tue, 18 Feb 2014) Log Message: ----------- fix generate histogram function Modified Paths: -------------- trunk/irteus/irtpointcloud.l Modified: trunk/irteus/irtpointcloud.l =================================================================== --- trunk/irteus/irtpointcloud.l 2014-02-17 01:11:36 UTC (rev 1064) +++ trunk/irteus/irtpointcloud.l 2014-02-18 10:20:10 UTC (rev 1065) @@ -398,16 +398,27 @@ ))) ;;(:remove-outlier ()) (:generate-color-histogram-hs (&key (h-step 3) (s-step 3)) - (let ((col (send self :colors)) - (hist (make-array - (list h-step s-step) - :element-type float-vector))) - (dotimes (i (send self :size)) - (let* ((his (rgb2his (matrix-row col i))) - (h-bin (get-bin (elt his 0) :step h-step :max-num 360.0)) - (s-bin (get-bin (elt his 2) :step s-step))) - (incf (aref hist h-bin s-bin)))) - (scale-matrix (/ 1.0 (send self :size)) hist))) + (flet ((get-bin (d step max-num) + (if (>= d max-num) (- step 1) + (let ((ret (floor (/ d (/ (- max-num 0.0) step))))) + (if (>= ret step) (- step 1) + (if (<= ret 0) 0 ret)))))) + (let* ((col (send self :colors)) + (hist (make-array + (list h-step s-step) + :element-type float-vector)) + (hvec (array-entity hist)) + (cinst (instantiate float-vector 3))) + (dotimes (i (send self :size)) + (c-matrix-row col i cinst) + (let* ((his (rgb2his cinst)) + (h-bin (get-bin (elt his 0) h-step 360.0)) + (s-bin (get-bin (elt his 2) s-step 1.0))) + (setf (elt hvec (+ (* h-bin s-step) s-bin)) + (+ 1 (elt hvec (+ (* h-bin s-step) s-bin)))) + )) + (scale-matrix (/ 1.0 (send self :size)) hist)) + )) ;; (:copy-from (pc) (send self :points (send pc :points)) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <sn...@us...> - 2014-02-17 01:11:40
|
Revision: 1064 http://sourceforge.net/p/jskeus/code/1064 Author: snozawa Date: 2014-02-17 01:11:36 +0000 (Mon, 17 Feb 2014) Log Message: ----------- reduce torelance of eps= for rotation of sphere-joint and 6dof-joint Modified Paths: -------------- trunk/irteus/irtmodel.l Modified: trunk/irteus/irtmodel.l =================================================================== --- trunk/irteus/irtmodel.l 2014-02-14 01:13:38 UTC (rev 1063) +++ trunk/irteus/irtmodel.l 2014-02-17 01:11:36 UTC (rev 1064) @@ -413,7 +413,7 @@ ;; if relative t ;; v is calculated from difference-rotation or jacobian (let ((vec (map float-vector #'deg2rad v))) - (unless (eps= (rad2deg (norm vec)) 0.0) + (unless (eps= (rad2deg (norm vec)) 0.0 1e-20) (m* (rotation-matrix (norm vec) (normalize-vector vec)) drot drot)))) ;; min max check (let* ((dr (map float-vector #'rad2deg (matrix-log drot)))) @@ -553,7 +553,7 @@ (setq drot (matrix-exponent (map float-vector #'deg2rad (subseq joint-angle 3 6)))) (if relative (let ((vec (map float-vector #'deg2rad (subseq v 3 6)))) - (unless (eps= (rad2deg (norm vec)) 0.0) + (unless (eps= (rad2deg (norm vec)) 0.0 1e-20) (m* (rotation-matrix (norm vec) (normalize-vector vec)) drot drot)))) ;; min max check (let* ((dr (map float-vector #'rad2deg (matrix-log drot)))) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <ky...@us...> - 2014-02-14 01:13:41
|
Revision: 1063 http://sourceforge.net/p/jskeus/code/1063 Author: kyouhei Date: 2014-02-14 01:13:38 +0000 (Fri, 14 Feb 2014) Log Message: ----------- add generate-histogram method to irtpointcloud Modified Paths: -------------- trunk/irteus/irtpointcloud.l Modified: trunk/irteus/irtpointcloud.l =================================================================== --- trunk/irteus/irtpointcloud.l 2014-02-12 19:34:29 UTC (rev 1062) +++ trunk/irteus/irtpointcloud.l 2014-02-14 01:13:38 UTC (rev 1063) @@ -397,6 +397,18 @@ ret))) ))) ;;(:remove-outlier ()) + (:generate-color-histogram-hs (&key (h-step 3) (s-step 3)) + (let ((col (send self :colors)) + (hist (make-array + (list h-step s-step) + :element-type float-vector))) + (dotimes (i (send self :size)) + (let* ((his (rgb2his (matrix-row col i))) + (h-bin (get-bin (elt his 0) :step h-step :max-num 360.0)) + (s-bin (get-bin (elt his 2) :step s-step))) + (incf (aref hist h-bin s-bin)))) + (scale-matrix (/ 1.0 (send self :size)) hist))) + ;; (:copy-from (pc) (send self :points (send pc :points)) (send self :colors (send pc :colors)) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <sn...@us...> - 2014-02-12 19:34:31
|
Revision: 1062 http://sourceforge.net/p/jskeus/code/1062 Author: snozawa Date: 2014-02-12 19:34:29 +0000 (Wed, 12 Feb 2014) Log Message: ----------- support linear-joint in joint vel acc calculation Modified Paths: -------------- trunk/irteus/irtdyna.l Modified: trunk/irteus/irtdyna.l =================================================================== --- trunk/irteus/irtdyna.l 2014-02-12 19:33:59 UTC (rev 1061) +++ trunk/irteus/irtdyna.l 2014-02-12 19:34:29 UTC (rev 1062) @@ -846,7 +846,10 @@ (pav (if (send self :get :prev-av) (send self :get :prev-av) av)) - (jvv (scale dt-1 (map float-vector #'deg2rad (v- av pav)))) ;; [rad/s] + (jvv (let ((jr (instantiate float-vector (length av)))) + (dotimes (i (length joint-list)) + (setf (elt jr i) (* dt-1 (send (elt joint-list i) :angle-to-speed (- (elt av i) (elt pav i)))))) + jr)) (pjvv (if (send self :get :prev-jvv) (send self :get :prev-jvv) jvv)) ;; [rad/s] This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <sn...@us...> - 2014-02-12 19:34:02
|
Revision: 1061 http://sourceforge.net/p/jskeus/code/1061 Author: snozawa Date: 2014-02-12 19:33:59 +0000 (Wed, 12 Feb 2014) Log Message: ----------- fix rotation difference ;; reduce threshold of rotation difference ;; this should be implemented in :difference-rotation Modified Paths: -------------- trunk/irteus/irtdyna.l Modified: trunk/irteus/irtdyna.l =================================================================== --- trunk/irteus/irtdyna.l 2014-02-12 16:44:37 UTC (rev 1060) +++ trunk/irteus/irtdyna.l 2014-02-12 19:33:59 UTC (rev 1061) @@ -781,15 +781,32 @@ (:calc-root-coords-vel-acc-from-pos (dt root-coords) ;; set spacial-acceleration and angular-acceleration of root-link + (labels ((omegafromrot + (rot) + (let ((alpha (* 0.5 (+ (aref rot 0 0) (aref rot 1 1) (aref rot 2 2) -1)))) + (if (eps= (abs (- alpha 1)) 0.0 1e-20) + (float-vector 0 0 0) + (let* ((th (acos alpha)) (s (sin th))) + (if (< s 1e-20) + (float-vector (sqrt (* th (* 0.5 (+ (aref rot 0 0) 1)))) + (sqrt (* th (* 0.5 (+ (aref rot 1 1) 1)))) + (sqrt (* th (* 0.5 (+ (aref rot 2 2) 1))))) + (let ((k (/ (* -0.5 th) s))) + (float-vector (* k (- (aref rot 1 2) (aref rot 2 1))) + (* k (- (aref rot 2 0) (aref rot 0 2))) + (* k (- (aref rot 0 1) (aref rot 1 0)))) + )) + ))))) (let* ((dt-1 (/ 1.0 dt)) (proot-coords (if (send self :get :prev-root-coords) (send self :get :prev-root-coords) root-coords)) - (rw (scale dt-1 (send proot-coords :rotate-vector (send proot-coords :difference-rotation root-coords)))) ;; [rad/s] + ;;(rw (scale dt-1 (send proot-coords :rotate-vector (send proot-coords :difference-rotation root-coords)))) ;; [rad/s] + (rw (scale dt-1 (send proot-coords :rotate-vector (omegafromrot (m* (transpose (send proot-coords :worldrot)) (send root-coords :worldrot)))))) ;; [rad/s] (rp (scale 1e-3 (send root-coords :worldpos))) (prp (scale 1e-3 (send proot-coords :worldpos))) - (rv (if (eps= (norm rw) 0.0) + (rv (if (eps= (norm rw) 0.0 5e-3) (scale dt-1 (v- rp prp)) ;; [m/s] (v+ (v* rw rp) @@ -812,6 +829,7 @@ ;; first order approximation (sp-rva (v- (scale dt-1 (v- rv (transform (matrix-exponent (scale dt rw)) prv))) (v* rwa rp))) + ;;(sp-rva (v- (v- (scale dt-1 (v- rv prv)) (v* rwa rp)) (v* rw rv))) ) ;; [m/s^2] (send self :put :prev-root-coords (send root-coords :copy-worldcoords)) (send self :put :prev-root-v rv) @@ -820,7 +838,7 @@ :root-angular-velocity rw ;; [rad/s] :root-spacial-acceleration sp-rva ;; [m/s^2] :root-angular-acceleration rwa) ;; [rad/s^2] - )) + ))) (:calc-av-vel-acc-from-pos (dt av) ;; set joint velocities and joint accelerations This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <sn...@us...> - 2014-02-12 16:44:40
|
Revision: 1060 http://sourceforge.net/p/jskeus/code/1060 Author: snozawa Date: 2014-02-12 16:44:37 +0000 (Wed, 12 Feb 2014) Log Message: ----------- calc root link velocity and acceleration considring spatial velocity formulation Modified Paths: -------------- trunk/irteus/irtdyna.l Modified: trunk/irteus/irtdyna.l =================================================================== --- trunk/irteus/irtdyna.l 2014-02-04 18:21:11 UTC (rev 1059) +++ trunk/irteus/irtdyna.l 2014-02-12 16:44:37 UTC (rev 1060) @@ -786,24 +786,39 @@ (if (send self :get :prev-root-coords) (send self :get :prev-root-coords) root-coords)) - (rv (scale (* 1e-3 dt-1) (v- (send root-coords :worldpos) (send proot-coords :worldpos)))) ;; [m/s] (rw (scale dt-1 (send proot-coords :rotate-vector (send proot-coords :difference-rotation root-coords)))) ;; [rad/s] + (rp (scale 1e-3 (send root-coords :worldpos))) + (prp (scale 1e-3 (send proot-coords :worldpos))) + (rv (if (eps= (norm rw) 0.0) + (scale dt-1 (v- rp prp)) ;; [m/s] + (v+ + (v* rw rp) + (scale (norm rw) + (transform + (inverse-matrix + (m+ (m* (m- (unit-matrix 3) (matrix-exponent (scale dt rw))) (outer-product-matrix (normalize-vector rw))) + (scale-matrix (/ dt (norm rw)) + (m* + (transpose (make-matrix 1 3 (list rw))) + (make-matrix 1 3 (list rw)))))) + (v- rp (transform (matrix-exponent (scale dt rw)) prp))))))) (prv (if (send self :get :prev-root-v) (send self :get :prev-root-v) rv)) ;; [m/s] (prw (if (send self :get :prev-root-w) (send self :get :prev-root-w) rw)) ;; [rad/s] - (rva (scale dt-1 (v- rv prv))) ;; [m/s^2] - (rwa (scale dt-1 (v- rw prw)))) ;; [rad/s^2] - (send self :put :prev-root-coords root-coords) + (rwa (scale dt-1 (v- rw prw))) ;; [rad/s^2] + ;; first order approximation + (sp-rva (v- (scale dt-1 (v- rv (transform (matrix-exponent (scale dt rw)) prv))) + (v* rwa rp))) + ) ;; [m/s^2] + (send self :put :prev-root-coords (send root-coords :copy-worldcoords)) (send self :put :prev-root-v rv) (send self :put :prev-root-w rw) (list :root-spacial-velocity (v- rv (v* rw (scale 1e-3 (send root-coords :worldpos)))) ;; [m/s] :root-angular-velocity rw ;; [rad/s] - :root-spacial-acceleration ;; [m/s^2] - (v- rva (v+ (v* rwa (scale 1e-3 (send root-coords :worldpos))) ;; [rad/s^2] * [m] - (v* rw rv))) ;; [rad/s] * [m/s] + :root-spacial-acceleration sp-rva ;; [m/s^2] :root-angular-acceleration rwa) ;; [rad/s^2] )) (:calc-av-vel-acc-from-pos This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <je...@js...> - 2014-02-07 03:31:57
|
See <http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/207/> |
From: <je...@js...> - 2014-02-07 03:22:21
|
See <http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/206/> ------------------------------------------ [...truncated 1295 lines...] Unpacking libc6-dev (from .../libc6-dev_2.15-0ubuntu10.5_amd64.deb) ... Selecting previously unselected package libstdc++6-4.6-dev. Unpacking libstdc++6-4.6-dev (from .../libstdc++6-4.6-dev_4.6.3-1ubuntu5_amd64.deb) ... Selecting previously unselected package g++-4.6. Unpacking g++-4.6 (from .../g++-4.6_4.6.3-1ubuntu5_amd64.deb) ... Selecting previously unselected package g++. Unpacking g++ (from .../g++_4%3a4.6.3-1ubuntu5_amd64.deb) ... Selecting previously unselected package comerr-dev. Unpacking comerr-dev (from .../comerr-dev_2.1-1.42-1ubuntu2_amd64.deb) ... Selecting previously unselected package krb5-multidev. Unpacking krb5-multidev (from .../krb5-multidev_1.10+dfsg~beta1-2ubuntu0.3_amd64.deb) ... Selecting previously unselected package libdrm-dev. Unpacking libdrm-dev (from .../libdrm-dev_2.4.46-1ubuntu0.0.0.1_amd64.deb) ... Selecting previously unselected package xorg-sgml-doctools. Unpacking xorg-sgml-doctools (from .../xorg-sgml-doctools_1%3a1.10-1_all.deb) ... Selecting previously unselected package x11proto-core-dev. Unpacking x11proto-core-dev (from .../x11proto-core-dev_7.0.22-1ubuntu0.1_all.deb) ... Selecting previously unselected package libxau-dev. Unpacking libxau-dev (from .../libxau-dev_1%3a1.0.6-4_amd64.deb) ... Selecting previously unselected package libxdmcp-dev. Unpacking libxdmcp-dev (from .../libxdmcp-dev_1%3a1.1.0-4_amd64.deb) ... Selecting previously unselected package x11proto-input-dev. Unpacking x11proto-input-dev (from .../x11proto-input-dev_2.3-1~precise1_all.deb) ... Selecting previously unselected package x11proto-kb-dev. Unpacking x11proto-kb-dev (from .../x11proto-kb-dev_1.0.5-2_all.deb) ... Selecting previously unselected package xtrans-dev. Unpacking xtrans-dev (from .../xtrans-dev_1.2.6-2_all.deb) ... Selecting previously unselected package libpthread-stubs0. Unpacking libpthread-stubs0 (from .../libpthread-stubs0_0.3-3_amd64.deb) ... Selecting previously unselected package libpthread-stubs0-dev. Unpacking libpthread-stubs0-dev (from .../libpthread-stubs0-dev_0.3-3_amd64.deb) ... Selecting previously unselected package libxcb1-dev. Unpacking libxcb1-dev (from .../libxcb1-dev_1.8.1-1ubuntu0.2_amd64.deb) ... Selecting previously unselected package libx11-dev. Unpacking libx11-dev (from .../libx11-dev_2%3a1.4.99.1-0ubuntu2.2_amd64.deb) ... Selecting previously unselected package mesa-common-dev. Unpacking mesa-common-dev (from .../mesa-common-dev_8.0.4-0ubuntu0.7_amd64.deb) ... Selecting previously unselected package x11proto-xext-dev. Unpacking x11proto-xext-dev (from .../x11proto-xext-dev_7.2.0-3_all.deb) ... Selecting previously unselected package libxext-dev. Unpacking libxext-dev (from .../libxext-dev_2%3a1.3.0-3ubuntu0.1_amd64.deb) ... Selecting previously unselected package libgl1-mesa-dev. Unpacking libgl1-mesa-dev (from .../libgl1-mesa-dev_8.0.4-0ubuntu0.7_amd64.deb) ... Selecting previously unselected package libglu1-mesa-dev. Unpacking libglu1-mesa-dev (from .../libglu1-mesa-dev_8.0.4-0ubuntu0.7_amd64.deb) ... Selecting previously unselected package libjpeg-turbo8-dev. Unpacking libjpeg-turbo8-dev (from .../libjpeg-turbo8-dev_1.1.90+svn733-0ubuntu4.3_amd64.deb) ... Selecting previously unselected package libjpeg8-dev. Unpacking libjpeg8-dev (from .../libjpeg8-dev_8c-2ubuntu7_amd64.deb) ... Selecting previously unselected package libjpeg-dev. Unpacking libjpeg-dev (from .../libjpeg-dev_8c-2ubuntu7_all.deb) ... Selecting previously unselected package zlib1g-dev. Unpacking zlib1g-dev (from .../zlib1g-dev_1%3a1.2.3.4.dfsg-3ubuntu4_amd64.deb) ... Selecting previously unselected package libpng12-dev. Unpacking libpng12-dev (from .../libpng12-dev_1.2.46-3ubuntu4_amd64.deb) ... Selecting previously unselected package libpq5. Unpacking libpq5 (from .../libpq5_9.1.11-0ubuntu0.12.04_amd64.deb) ... Selecting previously unselected package libssl-dev. Unpacking libssl-dev (from .../libssl-dev_1.0.1-4ubuntu5.11_amd64.deb) ... Selecting previously unselected package libkrb5-dev. Unpacking libkrb5-dev (from .../libkrb5-dev_1.10+dfsg~beta1-2ubuntu0.3_amd64.deb) ... Selecting previously unselected package libpq-dev. Unpacking libpq-dev (from .../libpq-dev_9.1.11-0ubuntu0.12.04_amd64.deb) ... Selecting previously unselected package libssl-doc. Unpacking libssl-doc (from .../libssl-doc_1.0.1-4ubuntu5.11_all.deb) ... Selecting previously unselected package libx11-doc. Unpacking libx11-doc (from .../libx11-doc_2%3a1.4.99.1-0ubuntu2.2_all.deb) ... Selecting previously unselected package libxfont1. Unpacking libxfont1 (from .../libxfont1_1%3a1.4.4-1ubuntu0.1_amd64.deb) ... Selecting previously unselected package manpages-dev. Unpacking manpages-dev (from .../manpages-dev_3.35-0.1ubuntu1_all.deb) ... Selecting previously unselected package subversion. Unpacking subversion (from .../subversion_1.6.17dfsg-3ubuntu3.3_amd64.deb) ... Selecting previously unselected package xfonts-encodings. Unpacking xfonts-encodings (from .../xfonts-encodings_1%3a1.0.4-1ubuntu1_all.deb) ... Selecting previously unselected package xfonts-utils. Unpacking xfonts-utils (from .../xfonts-utils_1%3a7.6+1_amd64.deb) ... Selecting previously unselected package xfonts-100dpi. Unpacking xfonts-100dpi (from .../xfonts-100dpi_1%3a1.0.3_all.deb) ... Selecting previously unselected package xfonts-75dpi. Unpacking xfonts-75dpi (from .../xfonts-75dpi_1%3a1.0.3_all.deb) ... Processing triggers for man-db ... debconf: unable to initialize frontend: Dialog debconf: (Dialog frontend will not work on a dumb terminal, an emacs shell buffer, or without a controlling terminal.) debconf: falling back to frontend: Readline debconf: unable to initialize frontend: Readline debconf: (This frontend requires a controlling tty.) debconf: falling back to frontend: Teletype Processing triggers for install-info ... Processing triggers for fontconfig ... Setting up libdrm2 (2.4.46-1ubuntu0.0.0.1) ... Setting up libdrm-intel1 (2.4.46-1ubuntu0.0.0.1) ... Setting up libdrm-nouveau1a (2.4.46-1ubuntu0.0.0.1) ... Setting up libdrm-radeon1 (2.4.46-1ubuntu0.0.0.1) ... Setting up libgssrpc4 (1.10+dfsg~beta1-2ubuntu0.3) ... Setting up libkadm5clnt-mit8 (1.10+dfsg~beta1-2ubuntu0.3) ... Setting up libkdb5-6 (1.10+dfsg~beta1-2ubuntu0.3) ... Setting up libkadm5srv-mit8 (1.10+dfsg~beta1-2ubuntu0.3) ... Setting up libdb4.8 (4.8.30-11ubuntu1) ... Setting up libdrm-nouveau2 (2.4.46-1ubuntu0.0.0.1) ... Setting up libgomp1 (4.6.3-1ubuntu5) ... Setting up libkms1 (2.4.46-1ubuntu0.0.0.1) ... Setting up libquadmath0 (4.6.3-1ubuntu5) ... Setting up libapr1 (1.4.6-1) ... Setting up libaprutil1 (1.3.12+dfsg-3) ... Setting up libneon27-gnutls (0.29.6-1ubuntu1) ... Setting up libsvn1 (1.6.17dfsg-3ubuntu3.3) ... Setting up libglu1-mesa (8.0.4-0ubuntu0.7) ... Setting up binutils (2.22-6ubuntu1.1) ... Setting up gcc-4.6 (4.6.3-1ubuntu5) ... Setting up gcc (4:4.6.3-1ubuntu5) ... Setting up libc-dev-bin (2.15-0ubuntu10.5) ... Setting up linux-libc-dev (3.2.0-58.88) ... Setting up libc6-dev (2.15-0ubuntu10.5) ... Setting up comerr-dev (2.1-1.42-1ubuntu2) ... Setting up krb5-multidev (1.10+dfsg~beta1-2ubuntu0.3) ... Setting up libdrm-dev (2.4.46-1ubuntu0.0.0.1) ... Setting up xorg-sgml-doctools (1:1.10-1) ... Setting up x11proto-core-dev (7.0.22-1ubuntu0.1) ... Setting up libxau-dev (1:1.0.6-4) ... Setting up libxdmcp-dev (1:1.1.0-4) ... Setting up x11proto-input-dev (2.3-1~precise1) ... Setting up x11proto-kb-dev (1.0.5-2) ... Setting up xtrans-dev (1.2.6-2) ... Setting up libpthread-stubs0 (0.3-3) ... Setting up libpthread-stubs0-dev (0.3-3) ... Setting up libxcb1-dev (1.8.1-1ubuntu0.2) ... Setting up libx11-dev (2:1.4.99.1-0ubuntu2.2) ... Setting up mesa-common-dev (8.0.4-0ubuntu0.7) ... Setting up x11proto-xext-dev (7.2.0-3) ... Setting up libxext-dev (2:1.3.0-3ubuntu0.1) ... Setting up libgl1-mesa-dev (8.0.4-0ubuntu0.7) ... Setting up libglu1-mesa-dev (8.0.4-0ubuntu0.7) ... Setting up libjpeg-turbo8-dev (1.1.90+svn733-0ubuntu4.3) ... Setting up libjpeg8-dev (8c-2ubuntu7) ... Setting up libjpeg-dev (8c-2ubuntu7) ... Setting up zlib1g-dev (1:1.2.3.4.dfsg-3ubuntu4) ... Setting up libpng12-dev (1.2.46-3ubuntu4) ... Setting up libpq5 (9.1.11-0ubuntu0.12.04) ... Setting up libssl-dev (1.0.1-4ubuntu5.11) ... Setting up libkrb5-dev (1.10+dfsg~beta1-2ubuntu0.3) ... Setting up libpq-dev (9.1.11-0ubuntu0.12.04) ... Setting up libssl-doc (1.0.1-4ubuntu5.11) ... Setting up libx11-doc (2:1.4.99.1-0ubuntu2.2) ... Setting up libxfont1 (1:1.4.4-1ubuntu0.1) ... Setting up manpages-dev (3.35-0.1ubuntu1) ... Setting up subversion (1.6.17dfsg-3ubuntu3.3) ... Setting up xfonts-encodings (1:1.0.4-1ubuntu1) ... Setting up xfonts-utils (1:7.6+1) ... Setting up xfonts-100dpi (1:1.0.3) ... Setting up xfonts-75dpi (1:1.0.3) ... Setting up g++-4.6 (4.6.3-1ubuntu5) ... Setting up g++ (4:4.6.3-1ubuntu5) ... update-alternatives: using /usr/bin/g++ to provide /usr/bin/c++ (c++) in auto mode. Setting up libstdc++6-4.6-dev (4.6.3-1ubuntu5) ... Processing triggers for libc-bin ... ldconfig deferred processing now taking place + cd jskeus + svn up Fetching external item into 'eus/lisp' External at revision 670. Fetching external item into 'eus/lib' External at revision 670. Fetching external item into 'eus/models' External at revision 670. Fetching external item into 'eus/doc/latex' External at revision 670. Fetching external item into 'eus/doc/jlatex' External at revision 670. At revision 1059. + svn up Fetching external item into 'eus/lisp' External at revision 670. Fetching external item into 'eus/lib' External at revision 670. Fetching external item into 'eus/models' External at revision 670. Fetching external item into 'eus/doc/latex' External at revision 670. Fetching external item into 'eus/doc/jlatex' External at revision 670. At revision 1059. + svn up Fetching external item into 'eus/lisp' External at revision 670. Fetching external item into 'eus/lib' External at revision 670. Fetching external item into 'eus/models' External at revision 670. Fetching external item into 'eus/doc/latex' External at revision 670. Fetching external item into 'eus/doc/jlatex' External at revision 670. At revision 1059. + svn up Fetching external item into 'eus/lisp' External at revision 670. Fetching external item into 'eus/lib' External at revision 670. Fetching external item into 'eus/models' External at revision 670. Fetching external item into 'eus/doc/latex' External at revision 670. Fetching external item into 'eus/doc/jlatex' External at revision 670. At revision 1059. + make /tmp/hudson5072176090162726818.sh: 5: /tmp/hudson5072176090162726818.sh: make: not found Build step 'Execute shell' marked build as failure |
From: <je...@js...> - 2014-02-07 03:17:52
|
See <http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/205/> ------------------------------------------ [...truncated 853 lines...] A eus/models/coffee-cup-saucer-object.l A eus/models/room73b2-desk-1-object.l A eus/models/dining-table-object.l AU eus/models/akihabara-floor-tex.jpg AU eus/models/azuma-short-broom.jpg AU eus/models/wheelchair-seat1.jpg A eus/models/coe-800-shelf-object.l A eus/models/hrp2-shelf-object.l A eus/models/room73b2-bariera-1200-middle3-1-object.l A eus/models/toyama-1800-sidetable-object.l A eus/models/darkgoldenrod-stairs-object.l A eus/models/room610-shelf2-object.l A eus/models/room73b2-panelwall-0-object.l A eus/models/room73b2-door-right-object.l A eus/models/room602-bariera-1200-right6-object.l A eus/models/kettle-object.l A eus/models/elevator_inside_panel-object.l AU eus/models/elevator_inside_panel_eng2.png A eus/models/room602-door-left-object.l A eus/models/room73b2-kitchen-object.l A eus/models/room83b1-askul-1400-desk-3-object.l A eus/models/zero-robot.l A eus/models/room73a3-bariera-1400-middle-7-object.l A eus/models/bariera-1200-right-object.l A eus/models/bariera-1200-middle2-object.l A eus/models/room73b2-foldable-desk-object.l A eus/models/gifuplastic-900-cart-object.l A eus/models/room602-askul-1200x700-desk-7-object.l A eus/models/room73b2-locker1-object.l A eus/models/toshiba-clacio-refrigerator-object.l A eus/models/room73b2-askul-1200x700-desk-4-object.l A eus/models/room73a3-village-chair-0-object.l A eus/models/room73b2-unknown-1200-desk-4-object.l A eus/models/room602-chair5-object.l A eus/models/sushi-cup-object.l A eus/models/room83b1-83b1-ground-object.l A eus/models/room602-wall4-object.l A eus/models/coe-1200-shelf-object.l A eus/models/room73b2-uchida-shelf-1300-object.l A eus/models/kaz2-robot.l A eus/models/uchida-monitor-leg-object.l A eus/models/room73a3-bariera-1400-middle-0-object.l A eus/models/room602-tableware-shelf2-object.l A eus/models/room73a3-askul-1400-desk-0-object.l A eus/models/arrow-object.l A eus/models/square-600-closet-object.l A eus/models/room73b2-askul-1400-desk-object.l A eus/models/room602-askul-1200x700-desk-0-object.l A eus/models/room83b1-scene.l A eus/models/akira-robot.l A eus/models/bariera-900-middle-object.l A eus/models/room73b2-sharp-52-aquostv-object.l A eus/models/single-arrow-object.l A eus/models/room602-trashbox0-object.l A eus/models/askul-gdh-cupboard-object.l A eus/models/room73b2-coe-450-shelf-object.l A eus/models/tot-robot.l A eus/models/room602-3t-600-clean-locker-object.l A eus/models/askul-corner-desk-object.l A eus/models/trashbox-object.l A eus/models/room83b1-askul-1600-desk-1-object.l A eus/models/room602-bariera-1200-corner1-object.l A eus/models/uchida-1000-desk-object.l A eus/models/coffee-cup-cup-object.l AU eus/models/elevator_call_panel_eng8.png A eus/models/room73a3-bariera-1400-middle-9-object.l A eus/models/room73b2-bottle-object.l A eus/models/room73a3-clock-object.l A eus/models/coe-demospace-object.l A eus/models/kokuyo-450-locker-object.l A eus/models/uchida-1500-desk-object.l A eus/models/room602-bariera-1200-middle3-object.l A eus/models/uchida-1800-desk-object.l A eus/models/room602-aquos1-object.l A eus/models/bariera-1200-corner-object.l A eus/models/room73b2-bariera-900-left-object.l A eus/models/itoki-900-closet-object.l A eus/models/askul-ntr-cupboard-object.l A eus/models/room73b2-askul-1200x700-desk-6-object.l A eus/models/broom-object.l A eus/models/room73a3-village-chair-2-object.l A eus/models/sakae-900-desk-object.l A eus/models/maruman-55-analog-clock-object.l A eus/models/room83b1-door-right-object.l A eus/models/room602-wall6-object.l A eus/models/room73b2-bariera-1200-middle-1-object.l A eus/models/akira3-robot.l A eus/models/room73a3-bariera-1400-middle-2-object.l A eus/models/book-object.l A eus/models/room602-tableware-shelf4-object.l A eus/models/room73a3-askul-1400-desk-2-object.l A eus/models/knife-object.l A eus/models/room73b2-cup-object.l A eus/models/sharp-52-aquostv-object.l A eus/models/white-bread-salad-dish-object.l A eus/models/room610-610-ground-object.l A eus/models/room602-askul-1200x700-desk-2-object.l A eus/models/room73b2-door-left-object.l A eus/models/uchida-2400-desk-object.l A eus/models/room602-door-object.l A eus/models/ape3-robot.l A eus/models/room73a3-officeprinter-object.l A eus/models/room73a3-shelf-1-object.l AU eus/models/wheelchair-seat2.jpg A eus/models/coe-stairs-object.l A eus/models/ball-object.l A eus/models/room73b2-sushi-cup2-object.l A eus/models/hitachi-fiesta-refrigerator-object.l A eus/models/h3s-robot.l A eus/models/plus-1800-pdesk-object.l A eus/models/room602-trashbox2-object.l A eus/models/room83b1-uchida-1800-desk-object.l Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/models' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/models'> At revision 670 A eus/doc/latex/opengl.tex A eus/doc/latex/mars-pre.tex A eus/doc/latex/symbols.tex A eus/doc/latex/sysfunc.tex A eus/doc/latex/mytabbing.sty A eus/doc/latex/contact.tex AU eus/doc/latex/intro.tex A eus/doc/latex/sequences.tex A eus/doc/latex/voronoi.tex A eus/doc/latex/datetime.tex A eus/doc/latex/manual.ps A eus/doc/latex/man.idx A eus/doc/latex/generals.tex A eus/doc/latex/graphics.tex A eus/doc/latex/types.tex A eus/doc/latex/preface.tex A eus/doc/latex/fig A eus/doc/latex/fig/textviewpanel.ps A eus/doc/latex/fig/simst.ps A eus/doc/latex/fig/filepanel.ps A eus/doc/latex/fig/eta3colavo.ps A eus/doc/latex/fig/threadpool.ps A eus/doc/latex/fig/threadobj.ps A eus/doc/latex/fig/mars.eps A eus/doc/latex/fig/synchports.ps A eus/doc/latex/fig/robot-ui2.ps A eus/doc/latex/fig/eta3hiru.ps A eus/doc/latex/fig/viewcoords.ps A eus/doc/latex/fig/xdraw.ps A eus/doc/latex/fig/fig-peg-naname-m2.ps A eus/doc/latex/fig/threadmodel.ps A eus/doc/latex/fig/fig-peg-in-hole1.ps A eus/doc/latex/fig/fig-peg-naname-m4.ps A eus/doc/latex/fig/fig-peg-in-hole3.ps A eus/doc/latex/fig/robot-st2.ps A eus/doc/latex/fig/parathreads.ps A eus/doc/latex/fig/beam.ps A eus/doc/latex/fig/eta3coords.ps A eus/doc/latex/fig/object.ps A eus/doc/latex/fig/block1.edg.ps A eus/doc/latex/fig/loop.ps A eus/doc/latex/fig/torus.ps A eus/doc/latex/fig/panelitem.ps A eus/doc/latex/fig/pointer.ps A eus/doc/latex/fig/simwindow.ps A eus/doc/latex/fig/fig1.ps A eus/doc/latex/fig/fig-peg-naname-m1.ps A eus/doc/latex/fig/cup.ps A eus/doc/latex/fig/fig-peg-naname-m3.ps A eus/doc/latex/fig/fig-peg-in-hole2.ps A eus/doc/latex/fig/fig-peg-in-hole4.ps A eus/doc/latex/fig/threadfig.ps A eus/doc/latex/fig/panellayout.ps A eus/doc/latex/evaluation.tex A eus/doc/latex/io.tex A eus/doc/latex/hyph.tex A eus/doc/latex/man-title.ps A eus/doc/latex/xtoolkit.tex A eus/doc/latex/manual.tex A eus/doc/latex/Makefile A eus/doc/latex/http.tex A eus/doc/latex/image.tex A eus/doc/latex/text.tex A eus/doc/latex/mthread.tex AU eus/doc/latex/manual.pdf A eus/doc/latex/loadforeign.tex A eus/doc/latex/objects.tex A eus/doc/latex/manipulator.tex A eus/doc/latex/geometry.tex AU eus/doc/latex/manual.dvi A eus/doc/latex/xwindow.tex A eus/doc/latex/manual.idx A eus/doc/latex/methods.tex A eus/doc/latex/controls.tex A eus/doc/latex/matrix.tex A eus/doc/latex/database.tex A eus/doc/latex/arith.tex A eus/doc/latex/euslisp.hlp Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/latex' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/doc/latex'> At revision 670 A eus/doc/jlatex/jevaluation.tex A eus/doc/jlatex/jio.tex A eus/doc/jlatex/jxtoolkit.tex A eus/doc/jlatex/jmanual.tex A eus/doc/jlatex/tape.tex A eus/doc/jlatex/mytabbing.sty A eus/doc/jlatex/jimage.tex A eus/doc/jlatex/jmthread.tex AU eus/doc/jlatex/jmanual.pdf AU eus/doc/jlatex/test.dvi A eus/doc/jlatex/jobjects.tex A eus/doc/jlatex/jgeometry.tex A eus/doc/jlatex/jmanipulator.tex AU eus/doc/jlatex/fig A eus/doc/jlatex/jxwindow.tex AU eus/doc/jlatex/jmanual.dvi A eus/doc/jlatex/jmanual.idx A eus/doc/jlatex/jcontrols.tex AU eus/doc/jlatex/Makefile A eus/doc/jlatex/jmatrix.tex A eus/doc/jlatex/jarith.tex A eus/doc/jlatex/jvxw.tex A eus/doc/jlatex/jmars-pre.tex A eus/doc/jlatex/test.ps A eus/doc/jlatex/jsymbols.tex A eus/doc/jlatex/jsysfunc.tex A eus/doc/jlatex/jintro.tex A eus/doc/jlatex/jcontact.tex A eus/doc/jlatex/jsequences.tex A eus/doc/jlatex/jvoronoi.tex A eus/doc/jlatex/server.tex A eus/doc/jlatex/euslisp.hlp A eus/doc/jlatex/jgenerals.tex A eus/doc/jlatex/jgraphics.tex A eus/doc/jlatex/test.tex Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/jlatex' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/doc/jlatex'> At revision 670 At revision 1059 no change for http://svn.code.sf.net/p/jskeus/code/trunk since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/lisp since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/lib since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/models since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/latex since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/jlatex since the previous build [jskeus] $ /bin/sh -xe /tmp/hudson2779051700694366421.sh + sudo apt-get install -y subversion gcc g++ libjpeg-dev libxext-dev libx11-dev libgl1-mesa-dev libglu1-mesa-dev libpq-dev libpng12-dev xfonts-100dpi xfonts-75dpi msttcorefonts Reading package lists... Building dependency tree... Reading state information... Package msttcorefonts is not available, but is referred to by another package. This may mean that the package is missing, has been obsoleted, or is only available from another source E: Package 'msttcorefonts' has no installation candidate Build step 'Execute shell' marked build as failure |
From: <je...@js...> - 2014-02-07 03:17:26
|
See <http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/204/> ------------------------------------------ [...truncated 852 lines...] A eus/models/coffee-cup-saucer-object.l A eus/models/room73b2-desk-1-object.l A eus/models/dining-table-object.l AU eus/models/akihabara-floor-tex.jpg AU eus/models/azuma-short-broom.jpg AU eus/models/wheelchair-seat1.jpg A eus/models/coe-800-shelf-object.l A eus/models/hrp2-shelf-object.l A eus/models/room73b2-bariera-1200-middle3-1-object.l A eus/models/toyama-1800-sidetable-object.l A eus/models/darkgoldenrod-stairs-object.l A eus/models/room610-shelf2-object.l A eus/models/room73b2-panelwall-0-object.l A eus/models/room73b2-door-right-object.l A eus/models/room602-bariera-1200-right6-object.l A eus/models/kettle-object.l A eus/models/elevator_inside_panel-object.l AU eus/models/elevator_inside_panel_eng2.png A eus/models/room602-door-left-object.l A eus/models/room73b2-kitchen-object.l A eus/models/room83b1-askul-1400-desk-3-object.l A eus/models/zero-robot.l A eus/models/room73a3-bariera-1400-middle-7-object.l A eus/models/bariera-1200-right-object.l A eus/models/bariera-1200-middle2-object.l A eus/models/room73b2-foldable-desk-object.l A eus/models/gifuplastic-900-cart-object.l A eus/models/room602-askul-1200x700-desk-7-object.l A eus/models/room73b2-locker1-object.l A eus/models/toshiba-clacio-refrigerator-object.l A eus/models/room73b2-askul-1200x700-desk-4-object.l A eus/models/room73a3-village-chair-0-object.l A eus/models/room73b2-unknown-1200-desk-4-object.l A eus/models/room602-chair5-object.l A eus/models/sushi-cup-object.l A eus/models/room83b1-83b1-ground-object.l A eus/models/room602-wall4-object.l A eus/models/coe-1200-shelf-object.l A eus/models/room73b2-uchida-shelf-1300-object.l A eus/models/kaz2-robot.l A eus/models/uchida-monitor-leg-object.l A eus/models/room73a3-bariera-1400-middle-0-object.l A eus/models/room602-tableware-shelf2-object.l A eus/models/room73a3-askul-1400-desk-0-object.l A eus/models/arrow-object.l A eus/models/square-600-closet-object.l A eus/models/room73b2-askul-1400-desk-object.l A eus/models/room602-askul-1200x700-desk-0-object.l A eus/models/room83b1-scene.l A eus/models/akira-robot.l A eus/models/bariera-900-middle-object.l A eus/models/room73b2-sharp-52-aquostv-object.l A eus/models/single-arrow-object.l A eus/models/room602-trashbox0-object.l A eus/models/askul-gdh-cupboard-object.l A eus/models/room73b2-coe-450-shelf-object.l A eus/models/tot-robot.l A eus/models/room602-3t-600-clean-locker-object.l A eus/models/askul-corner-desk-object.l A eus/models/trashbox-object.l A eus/models/room83b1-askul-1600-desk-1-object.l A eus/models/room602-bariera-1200-corner1-object.l A eus/models/uchida-1000-desk-object.l A eus/models/coffee-cup-cup-object.l AU eus/models/elevator_call_panel_eng8.png A eus/models/room73a3-bariera-1400-middle-9-object.l A eus/models/room73b2-bottle-object.l A eus/models/room73a3-clock-object.l A eus/models/coe-demospace-object.l A eus/models/kokuyo-450-locker-object.l A eus/models/uchida-1500-desk-object.l A eus/models/room602-bariera-1200-middle3-object.l A eus/models/uchida-1800-desk-object.l A eus/models/room602-aquos1-object.l A eus/models/bariera-1200-corner-object.l A eus/models/room73b2-bariera-900-left-object.l A eus/models/itoki-900-closet-object.l A eus/models/askul-ntr-cupboard-object.l A eus/models/room73b2-askul-1200x700-desk-6-object.l A eus/models/broom-object.l A eus/models/room73a3-village-chair-2-object.l A eus/models/sakae-900-desk-object.l A eus/models/maruman-55-analog-clock-object.l A eus/models/room83b1-door-right-object.l A eus/models/room602-wall6-object.l A eus/models/room73b2-bariera-1200-middle-1-object.l A eus/models/akira3-robot.l A eus/models/room73a3-bariera-1400-middle-2-object.l A eus/models/book-object.l A eus/models/room602-tableware-shelf4-object.l A eus/models/room73a3-askul-1400-desk-2-object.l A eus/models/knife-object.l A eus/models/room73b2-cup-object.l A eus/models/sharp-52-aquostv-object.l A eus/models/white-bread-salad-dish-object.l A eus/models/room610-610-ground-object.l A eus/models/room602-askul-1200x700-desk-2-object.l A eus/models/room73b2-door-left-object.l A eus/models/uchida-2400-desk-object.l A eus/models/room602-door-object.l A eus/models/ape3-robot.l A eus/models/room73a3-officeprinter-object.l A eus/models/room73a3-shelf-1-object.l AU eus/models/wheelchair-seat2.jpg A eus/models/coe-stairs-object.l A eus/models/ball-object.l A eus/models/room73b2-sushi-cup2-object.l A eus/models/hitachi-fiesta-refrigerator-object.l A eus/models/h3s-robot.l A eus/models/plus-1800-pdesk-object.l A eus/models/room602-trashbox2-object.l A eus/models/room83b1-uchida-1800-desk-object.l Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/models' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/models'> At revision 670 A eus/doc/latex/opengl.tex A eus/doc/latex/mars-pre.tex A eus/doc/latex/symbols.tex A eus/doc/latex/sysfunc.tex A eus/doc/latex/mytabbing.sty A eus/doc/latex/contact.tex AU eus/doc/latex/intro.tex A eus/doc/latex/sequences.tex A eus/doc/latex/voronoi.tex A eus/doc/latex/datetime.tex A eus/doc/latex/manual.ps A eus/doc/latex/man.idx A eus/doc/latex/generals.tex A eus/doc/latex/graphics.tex A eus/doc/latex/types.tex A eus/doc/latex/preface.tex A eus/doc/latex/fig A eus/doc/latex/fig/textviewpanel.ps A eus/doc/latex/fig/simst.ps A eus/doc/latex/fig/filepanel.ps A eus/doc/latex/fig/eta3colavo.ps A eus/doc/latex/fig/threadpool.ps A eus/doc/latex/fig/threadobj.ps A eus/doc/latex/fig/mars.eps A eus/doc/latex/fig/synchports.ps A eus/doc/latex/fig/robot-ui2.ps A eus/doc/latex/fig/eta3hiru.ps A eus/doc/latex/fig/viewcoords.ps A eus/doc/latex/fig/xdraw.ps A eus/doc/latex/fig/fig-peg-naname-m2.ps A eus/doc/latex/fig/threadmodel.ps A eus/doc/latex/fig/fig-peg-in-hole1.ps A eus/doc/latex/fig/fig-peg-naname-m4.ps A eus/doc/latex/fig/fig-peg-in-hole3.ps A eus/doc/latex/fig/robot-st2.ps A eus/doc/latex/fig/parathreads.ps A eus/doc/latex/fig/beam.ps A eus/doc/latex/fig/eta3coords.ps A eus/doc/latex/fig/object.ps A eus/doc/latex/fig/block1.edg.ps A eus/doc/latex/fig/loop.ps A eus/doc/latex/fig/torus.ps A eus/doc/latex/fig/panelitem.ps A eus/doc/latex/fig/pointer.ps A eus/doc/latex/fig/simwindow.ps A eus/doc/latex/fig/fig1.ps A eus/doc/latex/fig/fig-peg-naname-m1.ps A eus/doc/latex/fig/cup.ps A eus/doc/latex/fig/fig-peg-naname-m3.ps A eus/doc/latex/fig/fig-peg-in-hole2.ps A eus/doc/latex/fig/fig-peg-in-hole4.ps A eus/doc/latex/fig/threadfig.ps A eus/doc/latex/fig/panellayout.ps A eus/doc/latex/evaluation.tex A eus/doc/latex/io.tex A eus/doc/latex/hyph.tex A eus/doc/latex/man-title.ps A eus/doc/latex/xtoolkit.tex A eus/doc/latex/manual.tex A eus/doc/latex/Makefile A eus/doc/latex/http.tex A eus/doc/latex/image.tex A eus/doc/latex/text.tex A eus/doc/latex/mthread.tex AU eus/doc/latex/manual.pdf A eus/doc/latex/loadforeign.tex A eus/doc/latex/objects.tex A eus/doc/latex/manipulator.tex A eus/doc/latex/geometry.tex AU eus/doc/latex/manual.dvi A eus/doc/latex/xwindow.tex A eus/doc/latex/manual.idx A eus/doc/latex/methods.tex A eus/doc/latex/controls.tex A eus/doc/latex/matrix.tex A eus/doc/latex/database.tex A eus/doc/latex/arith.tex A eus/doc/latex/euslisp.hlp Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/latex' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/doc/latex'> At revision 670 A eus/doc/jlatex/jevaluation.tex A eus/doc/jlatex/jio.tex A eus/doc/jlatex/jxtoolkit.tex A eus/doc/jlatex/jmanual.tex A eus/doc/jlatex/tape.tex A eus/doc/jlatex/mytabbing.sty A eus/doc/jlatex/jimage.tex A eus/doc/jlatex/jmthread.tex AU eus/doc/jlatex/jmanual.pdf AU eus/doc/jlatex/test.dvi A eus/doc/jlatex/jobjects.tex A eus/doc/jlatex/jgeometry.tex A eus/doc/jlatex/jmanipulator.tex AU eus/doc/jlatex/fig A eus/doc/jlatex/jxwindow.tex AU eus/doc/jlatex/jmanual.dvi A eus/doc/jlatex/jmanual.idx A eus/doc/jlatex/jcontrols.tex AU eus/doc/jlatex/Makefile A eus/doc/jlatex/jmatrix.tex A eus/doc/jlatex/jarith.tex A eus/doc/jlatex/jvxw.tex A eus/doc/jlatex/jmars-pre.tex A eus/doc/jlatex/test.ps A eus/doc/jlatex/jsymbols.tex A eus/doc/jlatex/jsysfunc.tex A eus/doc/jlatex/jintro.tex A eus/doc/jlatex/jcontact.tex A eus/doc/jlatex/jsequences.tex A eus/doc/jlatex/jvoronoi.tex A eus/doc/jlatex/server.tex A eus/doc/jlatex/euslisp.hlp A eus/doc/jlatex/jgenerals.tex A eus/doc/jlatex/jgraphics.tex A eus/doc/jlatex/test.tex Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/jlatex' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/doc/jlatex'> At revision 670 At revision 1059 no change for http://svn.code.sf.net/p/jskeus/code/trunk since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/lisp since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/lib since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/models since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/latex since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/jlatex since the previous build [jskeus] $ /bin/sh -xe /tmp/hudson4848944483915124852.sh + sudo apt-get install -y subversion gcc g++ libjpeg-dev libxext-dev libx11-dev libgl1-mesa-dev libglu1-mesa-dev libpq-dev libpng12-dev xfonts-100dpi xfonts-75dpi msttcorefonts Reading package lists... Building dependency tree... Reading state information... Package msttcorefonts is not available, but is referred to by another package. This may mean that the package is missing, has been obsoleted, or is only available from another source E: Package 'msttcorefonts' has no installation candidate Build step 'Execute shell' marked build as failure |
From: <je...@js...> - 2014-02-07 02:50:18
|
See <http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/203/> ------------------------------------------ [...truncated 846 lines...] A eus/models/room602-wall2-object.l A eus/models/bariera-1400-middle-object.l A eus/models/room73b2-mug-cup-object.l A eus/models/room73a3-door-right-object.l A eus/models/plus-7000-desk-object.l A eus/models/sponge-object.l A eus/models/coffee-cup-saucer-object.l A eus/models/room73b2-desk-1-object.l A eus/models/dining-table-object.l AU eus/models/akihabara-floor-tex.jpg AU eus/models/azuma-short-broom.jpg AU eus/models/wheelchair-seat1.jpg A eus/models/coe-800-shelf-object.l A eus/models/hrp2-shelf-object.l A eus/models/room73b2-bariera-1200-middle3-1-object.l A eus/models/toyama-1800-sidetable-object.l A eus/models/darkgoldenrod-stairs-object.l A eus/models/room610-shelf2-object.l A eus/models/room73b2-panelwall-0-object.l A eus/models/room73b2-door-right-object.l A eus/models/room602-bariera-1200-right6-object.l A eus/models/kettle-object.l A eus/models/elevator_inside_panel-object.l AU eus/models/elevator_inside_panel_eng2.png A eus/models/room602-door-left-object.l A eus/models/room73b2-kitchen-object.l A eus/models/room83b1-askul-1400-desk-3-object.l A eus/models/zero-robot.l A eus/models/room73a3-bariera-1400-middle-7-object.l A eus/models/bariera-1200-right-object.l A eus/models/bariera-1200-middle2-object.l A eus/models/room73b2-foldable-desk-object.l A eus/models/gifuplastic-900-cart-object.l A eus/models/room602-askul-1200x700-desk-7-object.l A eus/models/room73b2-locker1-object.l A eus/models/toshiba-clacio-refrigerator-object.l A eus/models/room73b2-askul-1200x700-desk-4-object.l A eus/models/room73a3-village-chair-0-object.l A eus/models/room73b2-unknown-1200-desk-4-object.l A eus/models/room602-chair5-object.l A eus/models/sushi-cup-object.l A eus/models/room83b1-83b1-ground-object.l A eus/models/room602-wall4-object.l A eus/models/coe-1200-shelf-object.l A eus/models/room73b2-uchida-shelf-1300-object.l A eus/models/kaz2-robot.l A eus/models/uchida-monitor-leg-object.l A eus/models/room73a3-bariera-1400-middle-0-object.l A eus/models/room602-tableware-shelf2-object.l A eus/models/room73a3-askul-1400-desk-0-object.l A eus/models/arrow-object.l A eus/models/square-600-closet-object.l A eus/models/room73b2-askul-1400-desk-object.l A eus/models/room602-askul-1200x700-desk-0-object.l A eus/models/room83b1-scene.l A eus/models/akira-robot.l A eus/models/bariera-900-middle-object.l A eus/models/room73b2-sharp-52-aquostv-object.l A eus/models/single-arrow-object.l A eus/models/room602-trashbox0-object.l A eus/models/askul-gdh-cupboard-object.l A eus/models/room73b2-coe-450-shelf-object.l A eus/models/tot-robot.l A eus/models/room602-3t-600-clean-locker-object.l A eus/models/askul-corner-desk-object.l A eus/models/trashbox-object.l A eus/models/room83b1-askul-1600-desk-1-object.l A eus/models/room602-bariera-1200-corner1-object.l A eus/models/uchida-1000-desk-object.l A eus/models/coffee-cup-cup-object.l AU eus/models/elevator_call_panel_eng8.png A eus/models/room73a3-bariera-1400-middle-9-object.l A eus/models/room73b2-bottle-object.l A eus/models/room73a3-clock-object.l A eus/models/coe-demospace-object.l A eus/models/kokuyo-450-locker-object.l A eus/models/uchida-1500-desk-object.l A eus/models/room602-bariera-1200-middle3-object.l A eus/models/uchida-1800-desk-object.l A eus/models/room602-aquos1-object.l A eus/models/bariera-1200-corner-object.l A eus/models/room73b2-bariera-900-left-object.l A eus/models/itoki-900-closet-object.l A eus/models/askul-ntr-cupboard-object.l A eus/models/room73b2-askul-1200x700-desk-6-object.l A eus/models/broom-object.l A eus/models/room73a3-village-chair-2-object.l A eus/models/sakae-900-desk-object.l A eus/models/maruman-55-analog-clock-object.l A eus/models/room83b1-door-right-object.l A eus/models/room602-wall6-object.l A eus/models/room73b2-bariera-1200-middle-1-object.l A eus/models/akira3-robot.l A eus/models/room73a3-bariera-1400-middle-2-object.l A eus/models/book-object.l A eus/models/room602-tableware-shelf4-object.l A eus/models/room73a3-askul-1400-desk-2-object.l A eus/models/knife-object.l A eus/models/room73b2-cup-object.l A eus/models/sharp-52-aquostv-object.l A eus/models/white-bread-salad-dish-object.l A eus/models/room610-610-ground-object.l A eus/models/room602-askul-1200x700-desk-2-object.l A eus/models/room73b2-door-left-object.l A eus/models/uchida-2400-desk-object.l A eus/models/room602-door-object.l A eus/models/ape3-robot.l A eus/models/room73a3-officeprinter-object.l A eus/models/room73a3-shelf-1-object.l AU eus/models/wheelchair-seat2.jpg A eus/models/coe-stairs-object.l A eus/models/ball-object.l A eus/models/room73b2-sushi-cup2-object.l A eus/models/hitachi-fiesta-refrigerator-object.l A eus/models/h3s-robot.l A eus/models/plus-1800-pdesk-object.l A eus/models/room602-trashbox2-object.l A eus/models/room83b1-uchida-1800-desk-object.l Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/models' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/models'> At revision 670 A eus/doc/latex/opengl.tex A eus/doc/latex/mars-pre.tex A eus/doc/latex/symbols.tex A eus/doc/latex/sysfunc.tex A eus/doc/latex/mytabbing.sty A eus/doc/latex/contact.tex AU eus/doc/latex/intro.tex A eus/doc/latex/sequences.tex A eus/doc/latex/voronoi.tex A eus/doc/latex/datetime.tex A eus/doc/latex/manual.ps A eus/doc/latex/man.idx A eus/doc/latex/generals.tex A eus/doc/latex/graphics.tex A eus/doc/latex/types.tex A eus/doc/latex/preface.tex A eus/doc/latex/fig A eus/doc/latex/fig/textviewpanel.ps A eus/doc/latex/fig/simst.ps A eus/doc/latex/fig/filepanel.ps A eus/doc/latex/fig/eta3colavo.ps A eus/doc/latex/fig/threadpool.ps A eus/doc/latex/fig/threadobj.ps A eus/doc/latex/fig/mars.eps A eus/doc/latex/fig/synchports.ps A eus/doc/latex/fig/robot-ui2.ps A eus/doc/latex/fig/eta3hiru.ps A eus/doc/latex/fig/viewcoords.ps A eus/doc/latex/fig/xdraw.ps A eus/doc/latex/fig/fig-peg-naname-m2.ps A eus/doc/latex/fig/threadmodel.ps A eus/doc/latex/fig/fig-peg-in-hole1.ps A eus/doc/latex/fig/fig-peg-naname-m4.ps A eus/doc/latex/fig/fig-peg-in-hole3.ps A eus/doc/latex/fig/robot-st2.ps A eus/doc/latex/fig/parathreads.ps A eus/doc/latex/fig/beam.ps A eus/doc/latex/fig/eta3coords.ps A eus/doc/latex/fig/object.ps A eus/doc/latex/fig/block1.edg.ps A eus/doc/latex/fig/loop.ps A eus/doc/latex/fig/torus.ps A eus/doc/latex/fig/panelitem.ps A eus/doc/latex/fig/pointer.ps A eus/doc/latex/fig/simwindow.ps A eus/doc/latex/fig/fig1.ps A eus/doc/latex/fig/fig-peg-naname-m1.ps A eus/doc/latex/fig/cup.ps A eus/doc/latex/fig/fig-peg-naname-m3.ps A eus/doc/latex/fig/fig-peg-in-hole2.ps A eus/doc/latex/fig/fig-peg-in-hole4.ps A eus/doc/latex/fig/threadfig.ps A eus/doc/latex/fig/panellayout.ps A eus/doc/latex/evaluation.tex A eus/doc/latex/io.tex A eus/doc/latex/hyph.tex A eus/doc/latex/man-title.ps A eus/doc/latex/xtoolkit.tex A eus/doc/latex/manual.tex A eus/doc/latex/Makefile A eus/doc/latex/http.tex A eus/doc/latex/image.tex A eus/doc/latex/text.tex A eus/doc/latex/mthread.tex AU eus/doc/latex/manual.pdf A eus/doc/latex/loadforeign.tex A eus/doc/latex/objects.tex A eus/doc/latex/manipulator.tex A eus/doc/latex/geometry.tex AU eus/doc/latex/manual.dvi A eus/doc/latex/xwindow.tex A eus/doc/latex/manual.idx A eus/doc/latex/methods.tex A eus/doc/latex/controls.tex A eus/doc/latex/matrix.tex A eus/doc/latex/database.tex A eus/doc/latex/arith.tex A eus/doc/latex/euslisp.hlp Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/latex' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/doc/latex'> At revision 670 A eus/doc/jlatex/jevaluation.tex A eus/doc/jlatex/jio.tex A eus/doc/jlatex/jxtoolkit.tex A eus/doc/jlatex/jmanual.tex A eus/doc/jlatex/tape.tex A eus/doc/jlatex/mytabbing.sty A eus/doc/jlatex/jimage.tex A eus/doc/jlatex/jmthread.tex AU eus/doc/jlatex/jmanual.pdf AU eus/doc/jlatex/test.dvi A eus/doc/jlatex/jobjects.tex A eus/doc/jlatex/jgeometry.tex A eus/doc/jlatex/jmanipulator.tex AU eus/doc/jlatex/fig A eus/doc/jlatex/jxwindow.tex AU eus/doc/jlatex/jmanual.dvi A eus/doc/jlatex/jmanual.idx A eus/doc/jlatex/jcontrols.tex AU eus/doc/jlatex/Makefile A eus/doc/jlatex/jmatrix.tex A eus/doc/jlatex/jarith.tex A eus/doc/jlatex/jvxw.tex A eus/doc/jlatex/jmars-pre.tex A eus/doc/jlatex/test.ps A eus/doc/jlatex/jsymbols.tex A eus/doc/jlatex/jsysfunc.tex A eus/doc/jlatex/jintro.tex A eus/doc/jlatex/jcontact.tex A eus/doc/jlatex/jsequences.tex A eus/doc/jlatex/jvoronoi.tex A eus/doc/jlatex/server.tex A eus/doc/jlatex/euslisp.hlp A eus/doc/jlatex/jgenerals.tex A eus/doc/jlatex/jgraphics.tex A eus/doc/jlatex/test.tex Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/jlatex' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/doc/jlatex'> At revision 670 At revision 1059 no change for http://svn.code.sf.net/p/jskeus/code/trunk since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/lisp since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/lib since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/models since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/latex since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/jlatex since the previous build [jskeus] $ /bin/sh -xe /tmp/hudson9156668358824710770.sh + sudo -t apt-get install -y subversion gcc g++ libjpeg-dev libxext-dev libx11-dev libgl1-mesa-dev libglu1-mesa-dev libpq-dev libpng12-dev xfonts-100dpi xfonts-75dpi msttcorefonts install: invalid option -- 'y' Try `install --help' for more information. Build step 'Execute shell' marked build as failure |
From: <je...@js...> - 2014-02-07 02:48:32
|
See <http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/202/> ------------------------------------------ [...truncated 845 lines...] A eus/models/room610-laundry-machine-object.l A eus/models/room602-wall2-object.l A eus/models/bariera-1400-middle-object.l A eus/models/room73b2-mug-cup-object.l A eus/models/room73a3-door-right-object.l A eus/models/plus-7000-desk-object.l A eus/models/sponge-object.l A eus/models/coffee-cup-saucer-object.l A eus/models/room73b2-desk-1-object.l A eus/models/dining-table-object.l AU eus/models/akihabara-floor-tex.jpg AU eus/models/azuma-short-broom.jpg AU eus/models/wheelchair-seat1.jpg A eus/models/coe-800-shelf-object.l A eus/models/hrp2-shelf-object.l A eus/models/room73b2-bariera-1200-middle3-1-object.l A eus/models/toyama-1800-sidetable-object.l A eus/models/darkgoldenrod-stairs-object.l A eus/models/room610-shelf2-object.l A eus/models/room73b2-panelwall-0-object.l A eus/models/room73b2-door-right-object.l A eus/models/room602-bariera-1200-right6-object.l A eus/models/kettle-object.l A eus/models/elevator_inside_panel-object.l AU eus/models/elevator_inside_panel_eng2.png A eus/models/room602-door-left-object.l A eus/models/room73b2-kitchen-object.l A eus/models/room83b1-askul-1400-desk-3-object.l A eus/models/zero-robot.l A eus/models/room73a3-bariera-1400-middle-7-object.l A eus/models/bariera-1200-right-object.l A eus/models/bariera-1200-middle2-object.l A eus/models/room73b2-foldable-desk-object.l A eus/models/gifuplastic-900-cart-object.l A eus/models/room602-askul-1200x700-desk-7-object.l A eus/models/room73b2-locker1-object.l A eus/models/toshiba-clacio-refrigerator-object.l A eus/models/room73b2-askul-1200x700-desk-4-object.l A eus/models/room73a3-village-chair-0-object.l A eus/models/room73b2-unknown-1200-desk-4-object.l A eus/models/room602-chair5-object.l A eus/models/sushi-cup-object.l A eus/models/room83b1-83b1-ground-object.l A eus/models/room602-wall4-object.l A eus/models/coe-1200-shelf-object.l A eus/models/room73b2-uchida-shelf-1300-object.l A eus/models/kaz2-robot.l A eus/models/uchida-monitor-leg-object.l A eus/models/room73a3-bariera-1400-middle-0-object.l A eus/models/room602-tableware-shelf2-object.l A eus/models/room73a3-askul-1400-desk-0-object.l A eus/models/arrow-object.l A eus/models/square-600-closet-object.l A eus/models/room73b2-askul-1400-desk-object.l A eus/models/room602-askul-1200x700-desk-0-object.l A eus/models/room83b1-scene.l A eus/models/akira-robot.l A eus/models/bariera-900-middle-object.l A eus/models/room73b2-sharp-52-aquostv-object.l A eus/models/single-arrow-object.l A eus/models/room602-trashbox0-object.l A eus/models/askul-gdh-cupboard-object.l A eus/models/room73b2-coe-450-shelf-object.l A eus/models/tot-robot.l A eus/models/room602-3t-600-clean-locker-object.l A eus/models/askul-corner-desk-object.l A eus/models/trashbox-object.l A eus/models/room83b1-askul-1600-desk-1-object.l A eus/models/room602-bariera-1200-corner1-object.l A eus/models/uchida-1000-desk-object.l A eus/models/coffee-cup-cup-object.l AU eus/models/elevator_call_panel_eng8.png A eus/models/room73a3-bariera-1400-middle-9-object.l A eus/models/room73b2-bottle-object.l A eus/models/room73a3-clock-object.l A eus/models/coe-demospace-object.l A eus/models/kokuyo-450-locker-object.l A eus/models/uchida-1500-desk-object.l A eus/models/room602-bariera-1200-middle3-object.l A eus/models/uchida-1800-desk-object.l A eus/models/room602-aquos1-object.l A eus/models/bariera-1200-corner-object.l A eus/models/room73b2-bariera-900-left-object.l A eus/models/itoki-900-closet-object.l A eus/models/askul-ntr-cupboard-object.l A eus/models/room73b2-askul-1200x700-desk-6-object.l A eus/models/broom-object.l A eus/models/room73a3-village-chair-2-object.l A eus/models/sakae-900-desk-object.l A eus/models/maruman-55-analog-clock-object.l A eus/models/room83b1-door-right-object.l A eus/models/room602-wall6-object.l A eus/models/room73b2-bariera-1200-middle-1-object.l A eus/models/akira3-robot.l A eus/models/room73a3-bariera-1400-middle-2-object.l A eus/models/book-object.l A eus/models/room602-tableware-shelf4-object.l A eus/models/room73a3-askul-1400-desk-2-object.l A eus/models/knife-object.l A eus/models/room73b2-cup-object.l A eus/models/sharp-52-aquostv-object.l A eus/models/white-bread-salad-dish-object.l A eus/models/room610-610-ground-object.l A eus/models/room602-askul-1200x700-desk-2-object.l A eus/models/room73b2-door-left-object.l A eus/models/uchida-2400-desk-object.l A eus/models/room602-door-object.l A eus/models/ape3-robot.l A eus/models/room73a3-officeprinter-object.l A eus/models/room73a3-shelf-1-object.l AU eus/models/wheelchair-seat2.jpg A eus/models/coe-stairs-object.l A eus/models/ball-object.l A eus/models/room73b2-sushi-cup2-object.l A eus/models/hitachi-fiesta-refrigerator-object.l A eus/models/h3s-robot.l A eus/models/plus-1800-pdesk-object.l A eus/models/room602-trashbox2-object.l A eus/models/room83b1-uchida-1800-desk-object.l Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/models' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/models'> At revision 670 A eus/doc/latex/opengl.tex A eus/doc/latex/mars-pre.tex A eus/doc/latex/symbols.tex A eus/doc/latex/sysfunc.tex A eus/doc/latex/mytabbing.sty A eus/doc/latex/contact.tex AU eus/doc/latex/intro.tex A eus/doc/latex/sequences.tex A eus/doc/latex/voronoi.tex A eus/doc/latex/datetime.tex A eus/doc/latex/manual.ps A eus/doc/latex/man.idx A eus/doc/latex/generals.tex A eus/doc/latex/graphics.tex A eus/doc/latex/types.tex A eus/doc/latex/preface.tex A eus/doc/latex/fig A eus/doc/latex/fig/textviewpanel.ps A eus/doc/latex/fig/simst.ps A eus/doc/latex/fig/filepanel.ps A eus/doc/latex/fig/eta3colavo.ps A eus/doc/latex/fig/threadpool.ps A eus/doc/latex/fig/threadobj.ps A eus/doc/latex/fig/mars.eps A eus/doc/latex/fig/synchports.ps A eus/doc/latex/fig/robot-ui2.ps A eus/doc/latex/fig/eta3hiru.ps A eus/doc/latex/fig/viewcoords.ps A eus/doc/latex/fig/xdraw.ps A eus/doc/latex/fig/fig-peg-naname-m2.ps A eus/doc/latex/fig/threadmodel.ps A eus/doc/latex/fig/fig-peg-in-hole1.ps A eus/doc/latex/fig/fig-peg-naname-m4.ps A eus/doc/latex/fig/fig-peg-in-hole3.ps A eus/doc/latex/fig/robot-st2.ps A eus/doc/latex/fig/parathreads.ps A eus/doc/latex/fig/beam.ps A eus/doc/latex/fig/eta3coords.ps A eus/doc/latex/fig/object.ps A eus/doc/latex/fig/block1.edg.ps A eus/doc/latex/fig/loop.ps A eus/doc/latex/fig/torus.ps A eus/doc/latex/fig/panelitem.ps A eus/doc/latex/fig/pointer.ps A eus/doc/latex/fig/simwindow.ps A eus/doc/latex/fig/fig1.ps A eus/doc/latex/fig/fig-peg-naname-m1.ps A eus/doc/latex/fig/cup.ps A eus/doc/latex/fig/fig-peg-naname-m3.ps A eus/doc/latex/fig/fig-peg-in-hole2.ps A eus/doc/latex/fig/fig-peg-in-hole4.ps A eus/doc/latex/fig/threadfig.ps A eus/doc/latex/fig/panellayout.ps A eus/doc/latex/evaluation.tex A eus/doc/latex/io.tex A eus/doc/latex/hyph.tex A eus/doc/latex/man-title.ps A eus/doc/latex/xtoolkit.tex A eus/doc/latex/manual.tex A eus/doc/latex/Makefile A eus/doc/latex/http.tex A eus/doc/latex/image.tex A eus/doc/latex/text.tex A eus/doc/latex/mthread.tex AU eus/doc/latex/manual.pdf A eus/doc/latex/loadforeign.tex A eus/doc/latex/objects.tex A eus/doc/latex/manipulator.tex A eus/doc/latex/geometry.tex AU eus/doc/latex/manual.dvi A eus/doc/latex/xwindow.tex A eus/doc/latex/manual.idx A eus/doc/latex/methods.tex A eus/doc/latex/controls.tex A eus/doc/latex/matrix.tex A eus/doc/latex/database.tex A eus/doc/latex/arith.tex A eus/doc/latex/euslisp.hlp Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/latex' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/doc/latex'> At revision 670 A eus/doc/jlatex/jevaluation.tex A eus/doc/jlatex/jio.tex A eus/doc/jlatex/jxtoolkit.tex A eus/doc/jlatex/jmanual.tex A eus/doc/jlatex/tape.tex A eus/doc/jlatex/mytabbing.sty A eus/doc/jlatex/jimage.tex A eus/doc/jlatex/jmthread.tex AU eus/doc/jlatex/jmanual.pdf AU eus/doc/jlatex/test.dvi A eus/doc/jlatex/jobjects.tex A eus/doc/jlatex/jgeometry.tex A eus/doc/jlatex/jmanipulator.tex AU eus/doc/jlatex/fig A eus/doc/jlatex/jxwindow.tex AU eus/doc/jlatex/jmanual.dvi A eus/doc/jlatex/jmanual.idx A eus/doc/jlatex/jcontrols.tex AU eus/doc/jlatex/Makefile A eus/doc/jlatex/jmatrix.tex A eus/doc/jlatex/jarith.tex A eus/doc/jlatex/jvxw.tex A eus/doc/jlatex/jmars-pre.tex A eus/doc/jlatex/test.ps A eus/doc/jlatex/jsymbols.tex A eus/doc/jlatex/jsysfunc.tex A eus/doc/jlatex/jintro.tex A eus/doc/jlatex/jcontact.tex A eus/doc/jlatex/jsequences.tex A eus/doc/jlatex/jvoronoi.tex A eus/doc/jlatex/server.tex A eus/doc/jlatex/euslisp.hlp A eus/doc/jlatex/jgenerals.tex A eus/doc/jlatex/jgraphics.tex A eus/doc/jlatex/test.tex Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/jlatex' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/doc/jlatex'> At revision 670 At revision 1059 no change for http://svn.code.sf.net/p/jskeus/code/trunk since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/lisp since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/lib since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/models since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/latex since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/jlatex since the previous build [jskeus] $ /bin/sh -xe /tmp/hudson2785476151558737975.sh + sudo -t apt-get install -y subversion gcc g++ libjpeg-dev libxext-dev libx11-dev libgl1-mesa-dev libglu1-mesa-dev libpq-dev libpng12-dev xfonts-100dpi xfonts-75dpi msttcorefonts sudo: sorry, you must have a tty to run sudo Build step 'Execute shell' marked build as failure |
From: <je...@js...> - 2014-02-07 02:48:01
|
See <http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/201/> ------------------------------------------ [...truncated 845 lines...] A eus/models/room610-laundry-machine-object.l A eus/models/room602-wall2-object.l A eus/models/bariera-1400-middle-object.l A eus/models/room73b2-mug-cup-object.l A eus/models/room73a3-door-right-object.l A eus/models/plus-7000-desk-object.l A eus/models/sponge-object.l A eus/models/coffee-cup-saucer-object.l A eus/models/room73b2-desk-1-object.l A eus/models/dining-table-object.l AU eus/models/akihabara-floor-tex.jpg AU eus/models/azuma-short-broom.jpg AU eus/models/wheelchair-seat1.jpg A eus/models/coe-800-shelf-object.l A eus/models/hrp2-shelf-object.l A eus/models/room73b2-bariera-1200-middle3-1-object.l A eus/models/toyama-1800-sidetable-object.l A eus/models/darkgoldenrod-stairs-object.l A eus/models/room610-shelf2-object.l A eus/models/room73b2-panelwall-0-object.l A eus/models/room73b2-door-right-object.l A eus/models/room602-bariera-1200-right6-object.l A eus/models/kettle-object.l A eus/models/elevator_inside_panel-object.l AU eus/models/elevator_inside_panel_eng2.png A eus/models/room602-door-left-object.l A eus/models/room73b2-kitchen-object.l A eus/models/room83b1-askul-1400-desk-3-object.l A eus/models/zero-robot.l A eus/models/room73a3-bariera-1400-middle-7-object.l A eus/models/bariera-1200-right-object.l A eus/models/bariera-1200-middle2-object.l A eus/models/room73b2-foldable-desk-object.l A eus/models/gifuplastic-900-cart-object.l A eus/models/room602-askul-1200x700-desk-7-object.l A eus/models/room73b2-locker1-object.l A eus/models/toshiba-clacio-refrigerator-object.l A eus/models/room73b2-askul-1200x700-desk-4-object.l A eus/models/room73a3-village-chair-0-object.l A eus/models/room73b2-unknown-1200-desk-4-object.l A eus/models/room602-chair5-object.l A eus/models/sushi-cup-object.l A eus/models/room83b1-83b1-ground-object.l A eus/models/room602-wall4-object.l A eus/models/coe-1200-shelf-object.l A eus/models/room73b2-uchida-shelf-1300-object.l A eus/models/kaz2-robot.l A eus/models/uchida-monitor-leg-object.l A eus/models/room73a3-bariera-1400-middle-0-object.l A eus/models/room602-tableware-shelf2-object.l A eus/models/room73a3-askul-1400-desk-0-object.l A eus/models/arrow-object.l A eus/models/square-600-closet-object.l A eus/models/room73b2-askul-1400-desk-object.l A eus/models/room602-askul-1200x700-desk-0-object.l A eus/models/room83b1-scene.l A eus/models/akira-robot.l A eus/models/bariera-900-middle-object.l A eus/models/room73b2-sharp-52-aquostv-object.l A eus/models/single-arrow-object.l A eus/models/room602-trashbox0-object.l A eus/models/askul-gdh-cupboard-object.l A eus/models/room73b2-coe-450-shelf-object.l A eus/models/tot-robot.l A eus/models/room602-3t-600-clean-locker-object.l A eus/models/askul-corner-desk-object.l A eus/models/trashbox-object.l A eus/models/room83b1-askul-1600-desk-1-object.l A eus/models/room602-bariera-1200-corner1-object.l A eus/models/uchida-1000-desk-object.l A eus/models/coffee-cup-cup-object.l AU eus/models/elevator_call_panel_eng8.png A eus/models/room73a3-bariera-1400-middle-9-object.l A eus/models/room73b2-bottle-object.l A eus/models/room73a3-clock-object.l A eus/models/coe-demospace-object.l A eus/models/kokuyo-450-locker-object.l A eus/models/uchida-1500-desk-object.l A eus/models/room602-bariera-1200-middle3-object.l A eus/models/uchida-1800-desk-object.l A eus/models/room602-aquos1-object.l A eus/models/bariera-1200-corner-object.l A eus/models/room73b2-bariera-900-left-object.l A eus/models/itoki-900-closet-object.l A eus/models/askul-ntr-cupboard-object.l A eus/models/room73b2-askul-1200x700-desk-6-object.l A eus/models/broom-object.l A eus/models/room73a3-village-chair-2-object.l A eus/models/sakae-900-desk-object.l A eus/models/maruman-55-analog-clock-object.l A eus/models/room83b1-door-right-object.l A eus/models/room602-wall6-object.l A eus/models/room73b2-bariera-1200-middle-1-object.l A eus/models/akira3-robot.l A eus/models/room73a3-bariera-1400-middle-2-object.l A eus/models/book-object.l A eus/models/room602-tableware-shelf4-object.l A eus/models/room73a3-askul-1400-desk-2-object.l A eus/models/knife-object.l A eus/models/room73b2-cup-object.l A eus/models/sharp-52-aquostv-object.l A eus/models/white-bread-salad-dish-object.l A eus/models/room610-610-ground-object.l A eus/models/room602-askul-1200x700-desk-2-object.l A eus/models/room73b2-door-left-object.l A eus/models/uchida-2400-desk-object.l A eus/models/room602-door-object.l A eus/models/ape3-robot.l A eus/models/room73a3-officeprinter-object.l A eus/models/room73a3-shelf-1-object.l AU eus/models/wheelchair-seat2.jpg A eus/models/coe-stairs-object.l A eus/models/ball-object.l A eus/models/room73b2-sushi-cup2-object.l A eus/models/hitachi-fiesta-refrigerator-object.l A eus/models/h3s-robot.l A eus/models/plus-1800-pdesk-object.l A eus/models/room602-trashbox2-object.l A eus/models/room83b1-uchida-1800-desk-object.l Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/models' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/models'> At revision 670 A eus/doc/latex/opengl.tex A eus/doc/latex/mars-pre.tex A eus/doc/latex/symbols.tex A eus/doc/latex/sysfunc.tex A eus/doc/latex/mytabbing.sty A eus/doc/latex/contact.tex AU eus/doc/latex/intro.tex A eus/doc/latex/sequences.tex A eus/doc/latex/voronoi.tex A eus/doc/latex/datetime.tex A eus/doc/latex/manual.ps A eus/doc/latex/man.idx A eus/doc/latex/generals.tex A eus/doc/latex/graphics.tex A eus/doc/latex/types.tex A eus/doc/latex/preface.tex A eus/doc/latex/fig A eus/doc/latex/fig/textviewpanel.ps A eus/doc/latex/fig/simst.ps A eus/doc/latex/fig/filepanel.ps A eus/doc/latex/fig/eta3colavo.ps A eus/doc/latex/fig/threadpool.ps A eus/doc/latex/fig/threadobj.ps A eus/doc/latex/fig/mars.eps A eus/doc/latex/fig/synchports.ps A eus/doc/latex/fig/robot-ui2.ps A eus/doc/latex/fig/eta3hiru.ps A eus/doc/latex/fig/viewcoords.ps A eus/doc/latex/fig/xdraw.ps A eus/doc/latex/fig/fig-peg-naname-m2.ps A eus/doc/latex/fig/threadmodel.ps A eus/doc/latex/fig/fig-peg-in-hole1.ps A eus/doc/latex/fig/fig-peg-naname-m4.ps A eus/doc/latex/fig/fig-peg-in-hole3.ps A eus/doc/latex/fig/robot-st2.ps A eus/doc/latex/fig/parathreads.ps A eus/doc/latex/fig/beam.ps A eus/doc/latex/fig/eta3coords.ps A eus/doc/latex/fig/object.ps A eus/doc/latex/fig/block1.edg.ps A eus/doc/latex/fig/loop.ps A eus/doc/latex/fig/torus.ps A eus/doc/latex/fig/panelitem.ps A eus/doc/latex/fig/pointer.ps A eus/doc/latex/fig/simwindow.ps A eus/doc/latex/fig/fig1.ps A eus/doc/latex/fig/fig-peg-naname-m1.ps A eus/doc/latex/fig/cup.ps A eus/doc/latex/fig/fig-peg-naname-m3.ps A eus/doc/latex/fig/fig-peg-in-hole2.ps A eus/doc/latex/fig/fig-peg-in-hole4.ps A eus/doc/latex/fig/threadfig.ps A eus/doc/latex/fig/panellayout.ps A eus/doc/latex/evaluation.tex A eus/doc/latex/io.tex A eus/doc/latex/hyph.tex A eus/doc/latex/man-title.ps A eus/doc/latex/xtoolkit.tex A eus/doc/latex/manual.tex A eus/doc/latex/Makefile A eus/doc/latex/http.tex A eus/doc/latex/image.tex A eus/doc/latex/text.tex A eus/doc/latex/mthread.tex AU eus/doc/latex/manual.pdf A eus/doc/latex/loadforeign.tex A eus/doc/latex/objects.tex A eus/doc/latex/manipulator.tex A eus/doc/latex/geometry.tex AU eus/doc/latex/manual.dvi A eus/doc/latex/xwindow.tex A eus/doc/latex/manual.idx A eus/doc/latex/methods.tex A eus/doc/latex/controls.tex A eus/doc/latex/matrix.tex A eus/doc/latex/database.tex A eus/doc/latex/arith.tex A eus/doc/latex/euslisp.hlp Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/latex' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/doc/latex'> At revision 670 A eus/doc/jlatex/jevaluation.tex A eus/doc/jlatex/jio.tex A eus/doc/jlatex/jxtoolkit.tex A eus/doc/jlatex/jmanual.tex A eus/doc/jlatex/tape.tex A eus/doc/jlatex/mytabbing.sty A eus/doc/jlatex/jimage.tex A eus/doc/jlatex/jmthread.tex AU eus/doc/jlatex/jmanual.pdf AU eus/doc/jlatex/test.dvi A eus/doc/jlatex/jobjects.tex A eus/doc/jlatex/jgeometry.tex A eus/doc/jlatex/jmanipulator.tex AU eus/doc/jlatex/fig A eus/doc/jlatex/jxwindow.tex AU eus/doc/jlatex/jmanual.dvi A eus/doc/jlatex/jmanual.idx A eus/doc/jlatex/jcontrols.tex AU eus/doc/jlatex/Makefile A eus/doc/jlatex/jmatrix.tex A eus/doc/jlatex/jarith.tex A eus/doc/jlatex/jvxw.tex A eus/doc/jlatex/jmars-pre.tex A eus/doc/jlatex/test.ps A eus/doc/jlatex/jsymbols.tex A eus/doc/jlatex/jsysfunc.tex A eus/doc/jlatex/jintro.tex A eus/doc/jlatex/jcontact.tex A eus/doc/jlatex/jsequences.tex A eus/doc/jlatex/jvoronoi.tex A eus/doc/jlatex/server.tex A eus/doc/jlatex/euslisp.hlp A eus/doc/jlatex/jgenerals.tex A eus/doc/jlatex/jgraphics.tex A eus/doc/jlatex/test.tex Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/jlatex' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/doc/jlatex'> At revision 670 At revision 1059 no change for http://svn.code.sf.net/p/jskeus/code/trunk since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/lisp since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/lib since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/models since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/latex since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/jlatex since the previous build [jskeus] $ /bin/sh -xe /tmp/hudson323665443030292267.sh + sudo -t apt-get install -y subversion gcc g++ libjpeg-dev libxext-dev libx11-dev libgl1-mesa-dev libglu1-mesa-dev libpq-dev libpng12-dev xfonts-100dpi xfonts-75dpi msttcorefonts sudo: sorry, you must have a tty to run sudo Build step 'Execute shell' marked build as failure |
From: <je...@js...> - 2014-02-07 02:22:35
|
See <http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/200/> ------------------------------------------ [...truncated 845 lines...] A eus/models/room610-laundry-machine-object.l A eus/models/room602-wall2-object.l A eus/models/bariera-1400-middle-object.l A eus/models/room73b2-mug-cup-object.l A eus/models/room73a3-door-right-object.l A eus/models/plus-7000-desk-object.l A eus/models/sponge-object.l A eus/models/coffee-cup-saucer-object.l A eus/models/room73b2-desk-1-object.l A eus/models/dining-table-object.l AU eus/models/akihabara-floor-tex.jpg AU eus/models/azuma-short-broom.jpg AU eus/models/wheelchair-seat1.jpg A eus/models/coe-800-shelf-object.l A eus/models/hrp2-shelf-object.l A eus/models/room73b2-bariera-1200-middle3-1-object.l A eus/models/toyama-1800-sidetable-object.l A eus/models/darkgoldenrod-stairs-object.l A eus/models/room610-shelf2-object.l A eus/models/room73b2-panelwall-0-object.l A eus/models/room73b2-door-right-object.l A eus/models/room602-bariera-1200-right6-object.l A eus/models/kettle-object.l A eus/models/elevator_inside_panel-object.l AU eus/models/elevator_inside_panel_eng2.png A eus/models/room602-door-left-object.l A eus/models/room73b2-kitchen-object.l A eus/models/room83b1-askul-1400-desk-3-object.l A eus/models/zero-robot.l A eus/models/room73a3-bariera-1400-middle-7-object.l A eus/models/bariera-1200-right-object.l A eus/models/bariera-1200-middle2-object.l A eus/models/room73b2-foldable-desk-object.l A eus/models/gifuplastic-900-cart-object.l A eus/models/room602-askul-1200x700-desk-7-object.l A eus/models/room73b2-locker1-object.l A eus/models/toshiba-clacio-refrigerator-object.l A eus/models/room73b2-askul-1200x700-desk-4-object.l A eus/models/room73a3-village-chair-0-object.l A eus/models/room73b2-unknown-1200-desk-4-object.l A eus/models/room602-chair5-object.l A eus/models/sushi-cup-object.l A eus/models/room83b1-83b1-ground-object.l A eus/models/room602-wall4-object.l A eus/models/coe-1200-shelf-object.l A eus/models/room73b2-uchida-shelf-1300-object.l A eus/models/kaz2-robot.l A eus/models/uchida-monitor-leg-object.l A eus/models/room73a3-bariera-1400-middle-0-object.l A eus/models/room602-tableware-shelf2-object.l A eus/models/room73a3-askul-1400-desk-0-object.l A eus/models/arrow-object.l A eus/models/square-600-closet-object.l A eus/models/room73b2-askul-1400-desk-object.l A eus/models/room602-askul-1200x700-desk-0-object.l A eus/models/room83b1-scene.l A eus/models/akira-robot.l A eus/models/bariera-900-middle-object.l A eus/models/room73b2-sharp-52-aquostv-object.l A eus/models/single-arrow-object.l A eus/models/room602-trashbox0-object.l A eus/models/askul-gdh-cupboard-object.l A eus/models/room73b2-coe-450-shelf-object.l A eus/models/tot-robot.l A eus/models/room602-3t-600-clean-locker-object.l A eus/models/askul-corner-desk-object.l A eus/models/trashbox-object.l A eus/models/room83b1-askul-1600-desk-1-object.l A eus/models/room602-bariera-1200-corner1-object.l A eus/models/uchida-1000-desk-object.l A eus/models/coffee-cup-cup-object.l AU eus/models/elevator_call_panel_eng8.png A eus/models/room73a3-bariera-1400-middle-9-object.l A eus/models/room73b2-bottle-object.l A eus/models/room73a3-clock-object.l A eus/models/coe-demospace-object.l A eus/models/kokuyo-450-locker-object.l A eus/models/uchida-1500-desk-object.l A eus/models/room602-bariera-1200-middle3-object.l A eus/models/uchida-1800-desk-object.l A eus/models/room602-aquos1-object.l A eus/models/bariera-1200-corner-object.l A eus/models/room73b2-bariera-900-left-object.l A eus/models/itoki-900-closet-object.l A eus/models/askul-ntr-cupboard-object.l A eus/models/room73b2-askul-1200x700-desk-6-object.l A eus/models/broom-object.l A eus/models/room73a3-village-chair-2-object.l A eus/models/sakae-900-desk-object.l A eus/models/maruman-55-analog-clock-object.l A eus/models/room83b1-door-right-object.l A eus/models/room602-wall6-object.l A eus/models/room73b2-bariera-1200-middle-1-object.l A eus/models/akira3-robot.l A eus/models/room73a3-bariera-1400-middle-2-object.l A eus/models/book-object.l A eus/models/room602-tableware-shelf4-object.l A eus/models/room73a3-askul-1400-desk-2-object.l A eus/models/knife-object.l A eus/models/room73b2-cup-object.l A eus/models/sharp-52-aquostv-object.l A eus/models/white-bread-salad-dish-object.l A eus/models/room610-610-ground-object.l A eus/models/room602-askul-1200x700-desk-2-object.l A eus/models/room73b2-door-left-object.l A eus/models/uchida-2400-desk-object.l A eus/models/room602-door-object.l A eus/models/ape3-robot.l A eus/models/room73a3-officeprinter-object.l A eus/models/room73a3-shelf-1-object.l AU eus/models/wheelchair-seat2.jpg A eus/models/coe-stairs-object.l A eus/models/ball-object.l A eus/models/room73b2-sushi-cup2-object.l A eus/models/hitachi-fiesta-refrigerator-object.l A eus/models/h3s-robot.l A eus/models/plus-1800-pdesk-object.l A eus/models/room602-trashbox2-object.l A eus/models/room83b1-uchida-1800-desk-object.l Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/models' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/models'> At revision 670 A eus/doc/latex/opengl.tex A eus/doc/latex/mars-pre.tex A eus/doc/latex/symbols.tex A eus/doc/latex/sysfunc.tex A eus/doc/latex/mytabbing.sty A eus/doc/latex/contact.tex AU eus/doc/latex/intro.tex A eus/doc/latex/sequences.tex A eus/doc/latex/voronoi.tex A eus/doc/latex/datetime.tex A eus/doc/latex/manual.ps A eus/doc/latex/man.idx A eus/doc/latex/generals.tex A eus/doc/latex/graphics.tex A eus/doc/latex/types.tex A eus/doc/latex/preface.tex A eus/doc/latex/fig A eus/doc/latex/fig/textviewpanel.ps A eus/doc/latex/fig/simst.ps A eus/doc/latex/fig/filepanel.ps A eus/doc/latex/fig/eta3colavo.ps A eus/doc/latex/fig/threadpool.ps A eus/doc/latex/fig/threadobj.ps A eus/doc/latex/fig/mars.eps A eus/doc/latex/fig/synchports.ps A eus/doc/latex/fig/robot-ui2.ps A eus/doc/latex/fig/eta3hiru.ps A eus/doc/latex/fig/viewcoords.ps A eus/doc/latex/fig/xdraw.ps A eus/doc/latex/fig/fig-peg-naname-m2.ps A eus/doc/latex/fig/threadmodel.ps A eus/doc/latex/fig/fig-peg-in-hole1.ps A eus/doc/latex/fig/fig-peg-naname-m4.ps A eus/doc/latex/fig/fig-peg-in-hole3.ps A eus/doc/latex/fig/robot-st2.ps A eus/doc/latex/fig/parathreads.ps A eus/doc/latex/fig/beam.ps A eus/doc/latex/fig/eta3coords.ps A eus/doc/latex/fig/object.ps A eus/doc/latex/fig/block1.edg.ps A eus/doc/latex/fig/loop.ps A eus/doc/latex/fig/torus.ps A eus/doc/latex/fig/panelitem.ps A eus/doc/latex/fig/pointer.ps A eus/doc/latex/fig/simwindow.ps A eus/doc/latex/fig/fig1.ps A eus/doc/latex/fig/fig-peg-naname-m1.ps A eus/doc/latex/fig/cup.ps A eus/doc/latex/fig/fig-peg-naname-m3.ps A eus/doc/latex/fig/fig-peg-in-hole2.ps A eus/doc/latex/fig/fig-peg-in-hole4.ps A eus/doc/latex/fig/threadfig.ps A eus/doc/latex/fig/panellayout.ps A eus/doc/latex/evaluation.tex A eus/doc/latex/io.tex A eus/doc/latex/hyph.tex A eus/doc/latex/man-title.ps A eus/doc/latex/xtoolkit.tex A eus/doc/latex/manual.tex A eus/doc/latex/Makefile A eus/doc/latex/http.tex A eus/doc/latex/image.tex A eus/doc/latex/text.tex A eus/doc/latex/mthread.tex AU eus/doc/latex/manual.pdf A eus/doc/latex/loadforeign.tex A eus/doc/latex/objects.tex A eus/doc/latex/manipulator.tex A eus/doc/latex/geometry.tex AU eus/doc/latex/manual.dvi A eus/doc/latex/xwindow.tex A eus/doc/latex/manual.idx A eus/doc/latex/methods.tex A eus/doc/latex/controls.tex A eus/doc/latex/matrix.tex A eus/doc/latex/database.tex A eus/doc/latex/arith.tex A eus/doc/latex/euslisp.hlp Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/latex' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/doc/latex'> At revision 670 A eus/doc/jlatex/jevaluation.tex A eus/doc/jlatex/jio.tex A eus/doc/jlatex/jxtoolkit.tex A eus/doc/jlatex/jmanual.tex A eus/doc/jlatex/tape.tex A eus/doc/jlatex/mytabbing.sty A eus/doc/jlatex/jimage.tex A eus/doc/jlatex/jmthread.tex AU eus/doc/jlatex/jmanual.pdf AU eus/doc/jlatex/test.dvi A eus/doc/jlatex/jobjects.tex A eus/doc/jlatex/jgeometry.tex A eus/doc/jlatex/jmanipulator.tex AU eus/doc/jlatex/fig A eus/doc/jlatex/jxwindow.tex AU eus/doc/jlatex/jmanual.dvi A eus/doc/jlatex/jmanual.idx A eus/doc/jlatex/jcontrols.tex AU eus/doc/jlatex/Makefile A eus/doc/jlatex/jmatrix.tex A eus/doc/jlatex/jarith.tex A eus/doc/jlatex/jvxw.tex A eus/doc/jlatex/jmars-pre.tex A eus/doc/jlatex/test.ps A eus/doc/jlatex/jsymbols.tex A eus/doc/jlatex/jsysfunc.tex A eus/doc/jlatex/jintro.tex A eus/doc/jlatex/jcontact.tex A eus/doc/jlatex/jsequences.tex A eus/doc/jlatex/jvoronoi.tex A eus/doc/jlatex/server.tex A eus/doc/jlatex/euslisp.hlp A eus/doc/jlatex/jgenerals.tex A eus/doc/jlatex/jgraphics.tex A eus/doc/jlatex/test.tex Fetching 'https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/jlatex' at 670 into '<http://jenkins.jsk.imi.i.u-tokyo.ac.jp:8080/job/jskeus/ws/jskeus/eus/doc/jlatex'> At revision 670 At revision 1059 no change for http://svn.code.sf.net/p/jskeus/code/trunk since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/lisp since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/lib since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/models since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/latex since the previous build no change for https://svn.code.sf.net/p/euslisp/code/trunk/EusLisp/doc/jlatex since the previous build [jskeus] $ /bin/sh -xe /tmp/hudson3364026339956119851.sh + sudo apt-get install -y subversion gcc g++ libjpeg-dev libxext-dev libx11-dev libgl1-mesa-dev libglu1-mesa-dev libpq-dev libpng12-dev xfonts-100dpi xfonts-75dpi msttcorefonts sudo: sorry, you must have a tty to run sudo Build step 'Execute shell' marked build as failure |