diff --git a/jsk_2024_10_semi/README.md b/jsk_2024_10_semi/README.md index acd4388fa..23b120380 100644 --- a/jsk_2024_10_semi/README.md +++ b/jsk_2024_10_semi/README.md @@ -1,3 +1,10 @@ # jsk_2024_10_semi +## 目標 +手術ロボット。縫合タスク。 +## サブ目標 +スポンジを縫う + +## 発表スライド +https://docs.google.com/presentation/d/1k3P7t8WFiFfWd8XWg11Lx1IaNS1ZWhML7oywBxo_yrY/edit?usp=sharing \ No newline at end of file diff --git a/jsk_2024_10_semi/detect_test/niku.jpg b/jsk_2024_10_semi/detect_test/niku.jpg new file mode 100644 index 000000000..5e6be5661 Binary files /dev/null and b/jsk_2024_10_semi/detect_test/niku.jpg differ diff --git a/jsk_2024_10_semi/detect_test/niku_detect_1.py b/jsk_2024_10_semi/detect_test/niku_detect_1.py new file mode 100755 index 000000000..c4c431c97 --- /dev/null +++ b/jsk_2024_10_semi/detect_test/niku_detect_1.py @@ -0,0 +1,73 @@ +#!/usr/bin/env python + +##切れ目のsegmentation + +##参考: https://qiita.com/ysdyt/items/5972c9520acf6a094d90 +## https://pystyle.info/opencv-distance-transform/#google_vignette + + +#import common pkg in Python +import cv2 as cv +import numpy as np +import matplotlib.pyplot as plt + +#import pkg for connecting to ROS +import rospy +from sensor_msgs.msg import Image, CompressedImage, CameraInfo + + +#define call back function +def callback(msg): + global niku + niku = msg[0] + + + +rospy.init_node('client') +rospy.Subscriber("/kinect_head/rgb/image_raw/compressed", CompressedImage, callback) + +niku = cv.imread("./niku.jpg") +niku = niku[1000: 3200, 500 : 2700] + + +niku_gray = cv.cvtColor(niku, cv.COLOR_BGR2GRAY) + + + +plt.imshow(niku_gray,cmap='gray') +plt.show() + +thresh,bin_img = cv.threshold(niku_gray,0,255,cv.THRESH_BINARY_INV+cv.THRESH_OTSU) +plt.imshow(bin_img,cmap='gray') +plt.show() +print('大津法の二値化によって自動で決定された閾値:',thresh) + +## print(bin_img) #for debug + +kernel = np.ones((3,3),np.uint8) +opening = cv.morphologyEx(bin_img,cv.MORPH_OPEN,kernel,iterations = 2) +plt.imshow(opening,cmap='gray') +plt.show() + +#モルフォロジー演算のDilationを使う +sure_bg = cv.dilate(opening,kernel,iterations=2) +plt.imshow(sure_bg,cmap='gray') +plt.show() + +dist_transform = cv.distanceTransform(opening,cv.DIST_L2,5) +plt.imshow(dist_transform) +plt.show() + +ret, sure_fg = cv.threshold(dist_transform,0.05*dist_transform.max(),255,0) +print('閾値(距離変換で得られた値の最大値×0.5):',ret) +plt.imshow(sure_fg,cmap='gray') +plt.show() + +sure_fg = np.uint8(sure_fg) +unknown = cv.subtract(sure_bg,sure_fg) +plt.imshow(unknown,cmap='gray') + +# foregroundの1オブジェクトごとにラベル(番号)を振っていく +ret, markers = cv.connectedComponents(sure_fg) +plt.imshow(markers) +plt.show() diff --git a/jsk_2024_10_semi/first_motion.l b/jsk_2024_10_semi/first_motion.l new file mode 100644 index 000000000..122275c07 --- /dev/null +++ b/jsk_2024_10_semi/first_motion.l @@ -0,0 +1,248 @@ +;;Okada-sensei seminar practice task ;;last editted oct 17 ;; Michitoshi TSUBAKI +;;building specific motions using euslisp command + +(require "package://pr2eus/pr2.l") ;;import pr2 package +(require "package://pr2eus/pr2-utils.l") +(require "package://pr2eus/pr2-interface.l") +(if (not (boundp '*pr2*)) (pr2-init)) ;; (setq *pr2* (pr2))) ;; (pr2) is alternated by *pr2* +;;boudp 'xx : xxという変数に値が代入されているか +;;setq xx yy : xxとう変数にyyという値を代入する + +(send *pr2* :reset-pose) ;; 初期姿勢 +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :stop-grasp :arms) +(send *ri* :wait-interpolation) + + +(objects (list *pr2*)) + +;;徐々に腕(肩)を広げる(Oct 17) +(send *pr2* :larm :shoulder-p :joint-angle 74) +(send *pr2* :larm :shoulder-p :joint-angle 74) +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) + +(send *pr2* :larm :shoulder-p :joint-angle 54) +(send *pr2* :rarm :shoulder-p :joint-angle 54) + +(send *pr2* :larm :gripper :joint-angle 30) +(send *pr2* :rarm :gripper :joint-angle 30) + +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :start-grasp :arms) +(send *ri* :wait-interpolation) + + +(send *pr2* :larm :shoulder-p :joint-angle 34) +(send *pr2* :rarm :shoulder-p :joint-angle 34) +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) + + +(send *pr2* :larm :shoulder-p :joint-angle 20) +(send *pr2* :rarm :shoulder-p :joint-angle 20) +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) + + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle 0) +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) + + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) + + +;;徐々に型を下げる(Oct 22) +(send *pr2* :rarm :shoulder-r :joint-angle -80) +(send *pr2* :larm :shoulder-r :joint-angle 80) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) + + +(send *pr2* :rarm :shoulder-r :joint-angle -95) +(send *pr2* :larm :shoulder-r :joint-angle 95) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) + + +(send *pr2* :rarm :shoulder-r :joint-angle -110) +(send *pr2* :larm :shoulder-r :joint-angle 100) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) + + + +(send *pr2* :rarm :shoulder-r :joint-angle -130) +(send *pr2* :larm :shoulder-r :joint-angle 120) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) + + + + +(send *pr2* :larm :elbow-p :joint-angle -110) +(send *pr2* :rarm :elbow-p :joint-angle -100) +(send *pr2* :rarm :shoulder-r :joint-angle -130) +(send *pr2* :larm :shoulder-r :joint-angle 120) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *pr2* :rarm :shoulder-r :joint-angle -130) +(send *pr2* :larm :shoulder-r :joint-angle 120) +(send *pr2* :larm :elbow-p :joint-angle -100) +(send *pr2* :rarm :elbow-p :joint-angle -70) +(send *pr2* :rarm :elbow-r :joint-angle 0) +(send *pr2* :rarm :wrist-p :joint-angle -40) +(send *pr2* :larm :wrist-r :joint-angle 30) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) + + + + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *pr2* :rarm :shoulder-r :joint-angle -100) +(send *pr2* :larm :shoulder-r :joint-angle 100) +(send *pr2* :larm :elbow-p :joint-angle -100) +(send *pr2* :rarm :elbow-p :joint-angle -70) +(send *pr2* :rarm :elbow-r :joint-angle 0) +(send *pr2* :rarm :wrist-p :joint-angle -40) +(send *pr2* :larm :wrist-r :joint-angle 30) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) + + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *pr2* :rarm :shoulder-r :joint-angle -80) +(send *pr2* :larm :shoulder-r :joint-angle 80) +(send *pr2* :larm :elbow-p :joint-angle -110) +(send *pr2* :rarm :elbow-p :joint-angle -100) +(send *pr2* :rarm :elbow-r :joint-angle 0) +(send *pr2* :rarm :wrist-p :joint-angle -40) +(send *pr2* :larm :wrist-r :joint-angle 30) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) + + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *pr2* :rarm :shoulder-r :joint-angle -100) +(send *pr2* :larm :shoulder-r :joint-angle 100) +(send *pr2* :larm :elbow-p :joint-angle -120) +(send *pr2* :rarm :elbow-p :joint-angle -120) +(send *pr2* :rarm :elbow-r :joint-angle 0) +(send *pr2* :rarm :wrist-p :joint-angle -40) +(send *pr2* :larm :wrist-r :joint-angle 30) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) + + +;;fixing now last edited Oct 22 by Michitoshi TSUBAKI + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *pr2* :rarm :shoulder-r :joint-angle -100) +(send *pr2* :larm :shoulder-r :joint-angle 100) +(send *pr2* :larm :elbow-p :joint-angle -120) +(send *pr2* :rarm :elbow-p :joint-angle -120) +(send *pr2* :rarm :elbow-r :joint-angle 0) +(send *pr2* :rarm :wrist-p :joint-angle -40) +(send *pr2* :larm :wrist-r :joint-angle 0) +(send *pr2* :rarm :wrist-r :joint-angle 0) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) + + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *pr2* :rarm :shoulder-r :joint-angle -120) +(send *pr2* :larm :shoulder-r :joint-angle 120) +(send *pr2* :larm :elbow-p :joint-angle -120) +(send *pr2* :rarm :elbow-p :joint-angle -120) +(send *pr2* :rarm :elbow-r :joint-angle 0) +(send *pr2* :rarm :wrist-p :joint-angle -40) +(send *pr2* :larm :wrist-r :joint-angle 90) +(send *pr2* :rarm :wrist-r :joint-angle 90) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :torso :waist-z :joint-angle 200) +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) + + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *pr2* :rarm :shoulder-r :joint-angle -120) +(send *pr2* :larm :shoulder-r :joint-angle 120) +(send *pr2* :larm :elbow-p :joint-angle -120) +(send *pr2* :rarm :elbow-p :joint-angle -120) +(send *pr2* :rarm :elbow-r :joint-angle 0) +(send *pr2* :rarm :wrist-p :joint-angle -40) +(send *pr2* :larm :wrist-r :joint-angle 0) +(send *pr2* :rarm :wrist-r :joint-angle 0) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :torso :waist-z :joint-angle 300) + +(send *irtviewer* :draw-objects) +;;(unix:sleep 1) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) + + + diff --git a/jsk_2024_10_semi/first_task/demo_first.l b/jsk_2024_10_semi/first_task/demo_first.l new file mode 100644 index 000000000..eaad0d502 --- /dev/null +++ b/jsk_2024_10_semi/first_task/demo_first.l @@ -0,0 +1,5 @@ +(require "package://pr2eus/pr2.l") +(if (not (boundp '*pr2*)) (setq *pr2* (pr2))) +(objects (list *pr2*)) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *irtviewer* :draw-objects) diff --git a/jsk_2024_10_semi/first_task/homework_uml_1.act b/jsk_2024_10_semi/first_task/homework_uml_1.act new file mode 100644 index 000000000..0f0deb623 --- /dev/null +++ b/jsk_2024_10_semi/first_task/homework_uml_1.act @@ -0,0 +1,42 @@ +@startuml +|医者役| + start + :傷口を早く閉じて,休憩しないと死にそうだ〜: + + :針を通して,ロボットに渡す; + +|手術ロボット| + + :針を受け取る; + +|医者役| + + :「自動縫合モード」スタートさせる; + +|手術ロボット| + + :傷口を認識する(画像認識 segmantation? detection?); + + repeat + :アームを目標(傷口)に近づける; + :1針縫う; + + + repeat while (傷口が塞がれているか確認する(画像認識)) + :傷口が塞がれているなら,プログラムを停止する; + + + + +|医者役| + :休憩から帰ってきてちゃんと縫えているか確認する; + +|手術ロボット| + :お医者さんに褒められながらCtl+Cを押される(嬉しい?); + +|医者役| + :糸を結ぶ; + :手術終了; + +end +@enduml \ No newline at end of file diff --git a/jsk_2024_10_semi/first_task/homework_uml_2.act b/jsk_2024_10_semi/first_task/homework_uml_2.act new file mode 100644 index 000000000..0f0deb623 --- /dev/null +++ b/jsk_2024_10_semi/first_task/homework_uml_2.act @@ -0,0 +1,42 @@ +@startuml +|医者役| + start + :傷口を早く閉じて,休憩しないと死にそうだ〜: + + :針を通して,ロボットに渡す; + +|手術ロボット| + + :針を受け取る; + +|医者役| + + :「自動縫合モード」スタートさせる; + +|手術ロボット| + + :傷口を認識する(画像認識 segmantation? detection?); + + repeat + :アームを目標(傷口)に近づける; + :1針縫う; + + + repeat while (傷口が塞がれているか確認する(画像認識)) + :傷口が塞がれているなら,プログラムを停止する; + + + + +|医者役| + :休憩から帰ってきてちゃんと縫えているか確認する; + +|手術ロボット| + :お医者さんに褒められながらCtl+Cを押される(嬉しい?); + +|医者役| + :糸を結ぶ; + :手術終了; + +end +@enduml \ No newline at end of file diff --git a/jsk_2024_10_semi/first_task/memo1023.txt b/jsk_2024_10_semi/first_task/memo1023.txt new file mode 100644 index 000000000..d00d0e89d --- /dev/null +++ b/jsk_2024_10_semi/first_task/memo1023.txt @@ -0,0 +1,3783 @@ +mech-user@ki00119:~/semi_ws/src$ roseus +configuring by "/opt/ros/noetic/share/euslisp/jskeus/eus//lib/eusrt.l" +;; readmacro ;; object ;; packsym ;; common ;; constants ;; stream ;; string ;; loader ;; pprint ;; process ;; hashtab ;; array ;; mathtran ;; eusdebug ;; eusforeign ;; extnum ;; coordinates ;; tty ;; history ;; toplevel ;; trans ;; comp ;; builtins ;; par ;; intersection ;; geoclasses ;; geopack ;; geobody ;; primt ;; compose ;; polygon ;; viewing ;; viewport ;; viewsurface ;; hid ;; shadow ;; bodyrel ;; dda ;; helpsub ;; eushelp ;; xforeign ;; Xdecl ;; Xgraphics ;; Xcolor ;; Xeus ;; Xevent ;; Xpanel ;; Xitem ;; Xtext ;; Xmenu ;; Xscroll ;; Xcanvas ;; Xtop ;; Xapplwin +connected to Xserver DISPLAY=:0 +X events are being asynchronously monitored. +;; pixword ;; RGBHLS ;; convolve ;; piximage ;; pbmfile ;; image_correlation ;; oglforeign ;; gldecl ;; glconst ;; glforeign ;; gluconst ;; gluforeign ;; glxconst ;; glxforeign ;; eglforeign ;; eglfunc ;; glutil ;; gltexture ;; glprim ;; gleus ;; glview ;; toiv-undefined ;; fstringdouble irtmath irtutil irtc irtgeoc irtgraph gnuplotlib ___time ___pgsql irtgeo euspqp pqp irtscene irtmodel irtdyna irtrobot irtsensor irtbvh irtcollada irtstl irtwrl irtpointcloud eusbullet bullet irtcollision irtx eusjpeg euspng png irtimage irtglrgb +;; extending gcstack 0x55e070c10680[16374] --> 0x55e0710a0c90[32748] top=3d4b +irtgl irtglc irtviewer +EusLisp 9.29( 1.2.5) for Linux64 created on ip-10-0-1-5(Tue Jun 20 10:34:21 PST 2023) +roseus ;; loading roseus("1.7.5") on euslisp((9.29 ip-10-0-1-5 Tue Jun 20 10:34:21 PST 2023 1.2.5)) +eustf roseus_c_util 1.irteusgl$ (load "first_motion.l") +;; (make-irtviewer) executed +t +2.irteusgl$ (require "package://pr2eus/pr2-util.l") ;;import pr2 package +:larm :start-grasp) +;; error: cannot find method :start-grasp +nilp +3.irteusgl$ (require "package://pr2eus/pr2-util.l") ;;import pr2 package +:larm :start-grasp) +Call Stack (max depth: 20): + 0: at (apply #'ros::load-org-for-ros ros::fullname args) + 1: at (apply #'ros::load-org-for-ros ros::fullname args) + 2: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 3: at (require "package://pr2eus/pr2-util.l") + 4: at (require "package://pr2eus/pr2-util.l") + 5: at # +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: file #P"/opt/ros/noetic/share/pr2eus/pr2-util.l" not found in (apply #'ros::load-org-for-ros ros::fullname args) +4.E1-irteusgl$ nil +5.E1-irteusgl$ sh: 1: Syntax error: ")" unexpected +512 +6.E1-irteusgl$ (require "package://pr2eus/pr2-util.l") +:larm :start-grasp) +Call Stack (max depth: 20): + 0: at (apply #'ros::load-org-for-ros ros::fullname args) + 1: at (apply #'ros::load-org-for-ros ros::fullname args) + 2: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 3: at (require "package://pr2eus/pr2-util.l") + 4: at (require "package://pr2eus/pr2-util.l") + 5: at euserror + 6: at euserror + 7: at (apply #'ros::load-org-for-ros ros::fullname args) + 8: at (apply #'ros::load-org-for-ros ros::fullname args) + 9: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 10: at (require "package://pr2eus/pr2-util.l") + 11: at (require "package://pr2eus/pr2-util.l") + 12: at # +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: file #P"/opt/ros/noetic/share/pr2eus/pr2-util.l" not found in (apply #'ros::load-org-for-ros ros::fullname args) +7.E2-irteusgl$ nil +7.E2-irteusgl$ sh: 1: Syntax error: ")" unexpected +512 +8.E2-irteusgl$ (require "package://pr2eus/pr2-util.l") + +Call Stack (max depth: 20): + 0: at (apply #'ros::load-org-for-ros ros::fullname args) + 1: at (apply #'ros::load-org-for-ros ros::fullname args) + 2: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 3: at (require "package://pr2eus/pr2-util.l") + 4: at (require "package://pr2eus/pr2-util.l") + 5: at euserror + 6: at euserror + 7: at (apply #'ros::load-org-for-ros ros::fullname args) + 8: at (apply #'ros::load-org-for-ros ros::fullname args) + 9: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 10: at (require "package://pr2eus/pr2-util.l") + 11: at (require "package://pr2eus/pr2-util.l") + 12: at euserror + 13: at euserror + 14: at (apply #'ros::load-org-for-ros ros::fullname args) + 15: at (apply #'ros::load-org-for-ros ros::fullname args) + 16: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 17: at (require "package://pr2eus/pr2-util.l") + 18: at (require "package://pr2eus/pr2-util.l") + 19: at # +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: file #P"/opt/ros/noetic/share/pr2eus/pr2-util.l" not found in (apply #'ros::load-org-for-ros ros::fullname args) +9.E3-irteusgl$ nil +9.E3-irteusgl$ nil +9.E3-irteusgl$ (require "package://pr2eus/pr2-util.l") +Call Stack (max depth: 20): + 0: at (apply #'ros::load-org-for-ros ros::fullname args) + 1: at (apply #'ros::load-org-for-ros ros::fullname args) + 2: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 3: at (require "package://pr2eus/pr2-util.l") + 4: at (require "package://pr2eus/pr2-util.l") + 5: at euserror + 6: at euserror + 7: at (apply #'ros::load-org-for-ros ros::fullname args) + 8: at (apply #'ros::load-org-for-ros ros::fullname args) + 9: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 10: at (require "package://pr2eus/pr2-util.l") + 11: at (require "package://pr2eus/pr2-util.l") + 12: at euserror + 13: at euserror + 14: at (apply #'ros::load-org-for-ros ros::fullname args) + 15: at (apply #'ros::load-org-for-ros ros::fullname args) + 16: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 17: at (require "package://pr2eus/pr2-util.l") + 18: at (require "package://pr2eus/pr2-util.l") + 19: at euserror + And more... +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: file #P"/opt/ros/noetic/share/pr2eus/pr2-util.l" not found in (apply #'ros::load-org-for-ros ros::fullname args) +10.E4-irteusgl$ (require "package://pr2eus/pr2-utils.l") +:|PACKAGE://PR2EUS/PR2-UTILS.L| +11.E4-irteusgl$ (send *pr2* :larm :start-grasp) +;; error: cannot find method :start-grasp +nil +12.E4-irteusgl$ (send *pr2* :start-grasp :larm) +nil +13.E4-irteusgl$ (send *pr2* :stop-grasp :larm) +Call Stack (max depth: 20): + 0: at (if (eq #:case3317 ':larm) larm-grasping-obj nil nil) + 1: at (if (eq #:case3317 ':rarm) rarm-grasping-obj (if (eq #:case3317 ':larm) larm-grasping-obj nil nil) nil) + 2: at (let ((#:case3317 arm)) (if (eq #:case3317 ':rarm) rarm-grasping-obj (if (eq #:case3317 ':larm) larm-grasping-obj nil nil) nil)) + 3: at (case arm (:rarm rarm-grasping-obj) (:larm larm-grasping-obj)) + 4: at (cond ((or (derivedp target body) (derivedp target cascaded-coords)) (case arm (:rarm (setq rarm-grasping-obj target)) (:larm (setq larm-grasping-obj target)))) (target (case arm (:rarm rarm-grasping-obj) (:larm larm-grasping-obj))) ((null target) (case arm (:rarm (setq rarm-grasping-obj nil)) (:larm (setq larm-grasping-obj nil)))) (t)) + 5: at (send self :grasping-obj am) + 6: at (setq target (send self :grasping-obj am)) + 7: at (progn (setq target (send self :grasping-obj am))) + 8: at (if (null target) (progn (setq target (send self :grasping-obj am)))) + 9: at (when (null target) (setq target (send self :grasping-obj am))) + 10: at (while #:dolist3315 (setq am (pop #:dolist3315)) (when (null target) (setq target (send self :grasping-obj am))) (send self :grasping-obj am nil) (send (send self :gripper_finger_joint am) :parent-link :dissoc target) (send self :gripper am :joint-angle (+ (send (send self :gripper_finger_joint am) :max-angle) 15))) + 11: at (let ((am nil) (#:dolist3315 arm-lst)) nil (while #:dolist3315 (setq am (pop #:dolist3315)) (when (null target) (setq target (send self :grasping-obj am))) (send self :grasping-obj am nil) (send (send self :gripper_finger_joint am) :parent-link :dissoc target) (send self :gripper am :joint-angle (+ (send (send self :gripper_finger_joint am) :max-angle) 15))) nil) + 12: at (dolist (am arm-lst) (when (null target) (setq target (send self :grasping-obj am))) (send self :grasping-obj am nil) (send (send self :gripper_finger_joint am) :parent-link :dissoc target) (send self :gripper am :joint-angle (+ (send (send self :gripper_finger_joint am) :max-angle) 15))) + 13: at (cond ((and (numberp arg1) (derivedp arg2 body)) (setq angle arg1 target arg2) (dolist (am arm-lst) (when (eq (send self :grasping-obj am) target) (send self :grasping-obj am nil) (send (send self :gripper_finger_joint am) :parent-link :dissoc target)) (send self :gripper am :joint-angle angle))) ((numberp arg1) (setq angle arg1) (dolist (am arm-lst) (send self :gripper am :joint-angle angle))) (t (when (derivedp arg1 body) (setq target arg1)) (dolist (am arm-lst) (when (null target) (setq target (send self :grasping-obj am))) (send self :grasping-obj am nil) (send (send self :gripper_finger_joint am) :parent-link :dissoc target) (send self :gripper am :joint-angle (+ (send (send self :gripper_finger_joint am) :max-angle) 15))))) + 14: at (let (angle target finger-joint (arm-lst (case arm ((:rarm :larm) (list arm)) (:arms (list :rarm :larm))))) (cond ((and (numberp arg1) (derivedp arg2 body)) (setq angle arg1 target arg2) (dolist (am arm-lst) (when (eq (send self :grasping-obj am) target) (send self :grasping-obj am nil) (send (send self :gripper_finger_joint am) :parent-link :dissoc target)) (send self :gripper am :joint-angle angle))) ((numberp arg1) (setq angle arg1) (dolist (am arm-lst) (send self :gripper am :joint-angle angle))) (t (when (derivedp arg1 body) (setq target arg1)) (dolist (am arm-lst) (when (null target) (setq target (send self :grasping-obj am))) (send self :grasping-obj am nil) (send (send self :gripper_finger_joint am) :parent-link :dissoc target) (send self :gripper am :joint-angle (+ (send (send self :gripper_finger_joint am) :max-angle) 15)))))) + 15: at (send *pr2* :stop-grasp :larm) + 16: at euserror + 17: at euserror + 18: at (apply #'ros::load-org-for-ros ros::fullname args) + 19: at (apply #'ros::load-org-for-ros ros::fullname args) + And more... +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: unbound variable larm-grasping-obj in (if (eq #:case3317 ':larm) larm-grasping-obj nil nil) +14.E5-irteusgl$ (send *pr2* :larm :gripper :joint-angle 30) +30 +15.E5-irteusgl$ (send *pr2* :larm :gripper :joint-angle -30) +;; # :joint-angle(-15) violate min-angle(0.0) +;; # :joint-angle(-15) violate min-angle(0.0) +;; # :joint-angle(-15) violate min-angle(0.0) +;; # :joint-angle(-15) violate min-angle(0.0) +-30 +16.E5-irteusgl$ (send *pr2* :larm :gripper :joint-angle -0) +0 +17.E5-irteusgl$ (load "first_motion.l") +;; # :joint-angle(-15) violate min-angle(0.0) +;; # :joint-angle(-15) violate min-angle(0.0) +;; # :joint-angle(-15) violate min-angle(0.0) +;; # :joint-angle(-15) violate min-angle(0.0) +;; # :joint-angle(-15) violate min-angle(0.0) +;; # :joint-angle(-15) violate min-angle(0.0) +;; # :joint-angle(-15) violate min-angle(0.0) +;; # :joint-angle(-15) violate min-angle(0.0) +t +18.E5-irteusgl$ o(send *pr2* :larm :gripper :joint-angle -30) +(send *pr2* :rarm :gripper :joint-angle -30) + +;; # :joint-angle(-15) violate min-angle(0.0) +;; # :joint-angle(-15) violate min-angle(0.0) +;; # :joint-angle(-15) violate min-angle(0.0) +;; # :joint-angle(-15) violate min-angle(0.0) +-30 +19.E5-irteusgl$ ;; # :joint-angle(-15) violate min-angle(0.0) +;; # :joint-angle(-15) violate min-angle(0.0) +;; # :joint-angle(-15) violate min-angle(0.0) +;; # :joint-angle(-15) violate min-angle(0.0) +-30 +20.E5-irteusgl$ nil +20.E5-irteusgl$ (load "first_motion.l") +t +21.E5-irteusgl$ (exit) +[ INFO] [1729664760.034245223]: cell* ROSEUS_EXIT(context*, int, cell**) +mech-user@ki00119:~/semi_ws/src$ rossetmaster pr1040 +set ROS_MASTER_URI to http://pr1040:11311 +[http://pr1040:11311][] mech-user@ki00119:~/semi_ws/src$ rossetip +Could not resolve ip from address. Subnet may be different +set ROS_IP and ROS_HOSTNAME to 10.100.196.111 +[http://pr1040:11311][10.100.196.111] mech-user@ki00119:~/semi_ws/src$ rossetip +Could not resolve ip from address. Subnet may be different +set ROS_IP and ROS_HOSTNAME to 133.11.216.23 +[http://pr1040:11311][133.11.216.23] mech-user@ki00119:~/semi_ws/src$ rostopic list +/accelerometer/l_gripper_motor +/accelerometer/r_gripper_motor +/amcl/parameter_descriptions +/amcl/parameter_updates +/amcl_pose +/app_scheduler/app_schedules +/audible_warning/output/original_text +/audible_warning/output/text +/audible_warning/parameter_descriptions +/audible_warning/parameter_updates +/audio +/audio_play/audio +/base_controller/bl_caster_l_wheel_joint/parameter_descriptions +/base_controller/bl_caster_l_wheel_joint/parameter_updates +/base_controller/bl_caster_r_wheel_joint/parameter_descriptions +/base_controller/bl_caster_r_wheel_joint/parameter_updates +/base_controller/bl_caster_rotation_joint/position_controller/parameter_descriptions +/base_controller/bl_caster_rotation_joint/position_controller/parameter_updates +/base_controller/br_caster_l_wheel_joint/parameter_descriptions +/base_controller/br_caster_l_wheel_joint/parameter_updates +/base_controller/br_caster_r_wheel_joint/parameter_descriptions +/base_controller/br_caster_r_wheel_joint/parameter_updates +/base_controller/br_caster_rotation_joint/position_controller/parameter_descriptions +/base_controller/br_caster_rotation_joint/position_controller/parameter_updates +/base_controller/cmd_vel +/base_controller/command +/base_controller/command_unchecked +/base_controller/fl_caster_l_wheel_joint/parameter_descriptions +/base_controller/fl_caster_l_wheel_joint/parameter_updates +/base_controller/fl_caster_r_wheel_joint/parameter_descriptions +/base_controller/fl_caster_r_wheel_joint/parameter_updates +/base_controller/fl_caster_rotation_joint/position_controller/parameter_descriptions +/base_controller/fl_caster_rotation_joint/position_controller/parameter_updates +/base_controller/follow_joint_trajectory/cancel +/base_controller/follow_joint_trajectory/feedback +/base_controller/follow_joint_trajectory/goal +/base_controller/follow_joint_trajectory/result +/base_controller/follow_joint_trajectory/status +/base_controller/fr_caster_l_wheel_joint/parameter_descriptions +/base_controller/fr_caster_l_wheel_joint/parameter_updates +/base_controller/fr_caster_r_wheel_joint/parameter_descriptions +/base_controller/fr_caster_r_wheel_joint/parameter_updates +/base_controller/fr_caster_rotation_joint/position_controller/parameter_descriptions +/base_controller/fr_caster_rotation_joint/position_controller/parameter_updates +/base_controller/state +/base_hokuyo_node/parameter_descriptions +/base_hokuyo_node/parameter_updates +/base_odometry/odom +/base_odometry/odometer +/base_odometry/state +/base_scan +/base_scan_filtered +/base_scan_filtered/scan +/base_scan_shadow_filtered +/base_scan_throttled +/base_shadow_filter/dark_shadows/parameter_descriptions +/base_shadow_filter/dark_shadows/parameter_updates +/base_shadow_filter/shadows/parameter_descriptions +/base_shadow_filter/shadows/parameter_updates +/battery/server +/battery/server2 +/calibrated +/calibration_status +/camera_synchronizer_node/parameter_descriptions +/camera_synchronizer_node/parameter_updates +/check_room_light/output +/client_count +/cmd_vel_smoother/parameter_descriptions +/cmd_vel_smoother/parameter_updates +/connected_clients +/dashboard_agg +/ddwrt/accesspoint +/diagnostics +/diagnostics_agg +/diagnostics_toplevel_state +/dialog_response +/dialogflow_client/text_action/cancel +/dialogflow_client/text_action/feedback +/dialogflow_client/text_action/goal +/dialogflow_client/text_action/result +/dialogflow_client/text_action/status +/edgetpu_human_pose_estimator/output/class +/edgetpu_human_pose_estimator/output/image +/edgetpu_human_pose_estimator/output/image/compressed +/edgetpu_human_pose_estimator/output/poses +/edgetpu_human_pose_estimator/output/rects +/edgetpu_human_pose_estimator/output/skeletons +/edgetpu_human_pose_estimator/parameter_descriptions +/edgetpu_human_pose_estimator/parameter_updates +/email +/empty_cloud +/eng2/1f +/eng2/1f_tf +/eng2/2f +/eng2/2f_tf +/eng2/3f +/eng2/3f_tf +/eng2/7f +/eng2/7f_tf +/eng2/8f +/eng2/8f_tf +/femto_mega/accel/imu_info +/femto_mega/color/camera_info +/femto_mega/color/image_raw +/femto_mega/depth/camera_info +/femto_mega/depth/image_raw +/femto_mega/depth/points +/femto_mega/depth_to_accel +/femto_mega/depth_to_color +/femto_mega/depth_to_gyro +/femto_mega/depth_to_ir +/femto_mega/filter_status +/femto_mega/gyro/imu_info +/femto_mega/gyro_accel/sample +/femto_mega/ir/camera_info +/femto_mega/ir/image_raw +/femto_mega/sdk_version +/google_chat_ros/card_activity +/google_chat_ros/message_activity +/google_chat_ros/send/cancel +/google_chat_ros/send/feedback +/google_chat_ros/send/goal +/google_chat_ros/send/result +/google_chat_ros/send/status +/google_chat_ros/space_activity +/head_camera_trigger/trigger +/head_camera_trigger/waveform +/head_traj_controller/command +/head_traj_controller/command_deadman +/head_traj_controller/command_dummy +/head_traj_controller/follow_joint_trajectory/cancel +/head_traj_controller/follow_joint_trajectory/feedback +/head_traj_controller/follow_joint_trajectory/goal +/head_traj_controller/follow_joint_trajectory/result +/head_traj_controller/follow_joint_trajectory/status +/head_traj_controller/gains/head_pan_joint/parameter_descriptions +/head_traj_controller/gains/head_pan_joint/parameter_updates +/head_traj_controller/gains/head_tilt_joint/parameter_descriptions +/head_traj_controller/gains/head_tilt_joint/parameter_updates +/head_traj_controller/joint_trajectory_action/cancel +/head_traj_controller/joint_trajectory_action/feedback +/head_traj_controller/joint_trajectory_action/goal +/head_traj_controller/joint_trajectory_action/result +/head_traj_controller/joint_trajectory_action/status +/head_traj_controller/mux/selected +/head_traj_controller/point_head_action/cancel +/head_traj_controller/point_head_action/feedback +/head_traj_controller/point_head_action/goal +/head_traj_controller/point_head_action/result +/head_traj_controller/point_head_action/status +/head_traj_controller/state +/head_traj_controller_loose/command +/head_traj_controller_loose/state +/initialpose +/initialpose3d +/input_vel +/input_vel_mux/selected +/joint_states +/joy +/joy/set_feedback +/joy_org +/joy_org_ds3 +/joy_other +/joy_vel +/kinect_head/depth/camera_info +/kinect_head/depth/disparity +/kinect_head/depth/image +/kinect_head/depth/image/compressed +/kinect_head/depth/image/compressed/parameter_descriptions +/kinect_head/depth/image/compressed/parameter_updates +/kinect_head/depth/image/compressedDepth +/kinect_head/depth/image/compressedDepth/parameter_descriptions +/kinect_head/depth/image/compressedDepth/parameter_updates +/kinect_head/depth/image/theora +/kinect_head/depth/image/theora/parameter_descriptions +/kinect_head/depth/image/theora/parameter_updates +/kinect_head/depth/image/zdepth +/kinect_head/depth/image_raw +/kinect_head/depth/image_raw/compressed +/kinect_head/depth/image_raw/compressed/parameter_descriptions +/kinect_head/depth/image_raw/compressed/parameter_updates +/kinect_head/depth/image_raw/compressedDepth +/kinect_head/depth/image_raw/compressedDepth/parameter_descriptions +/kinect_head/depth/image_raw/compressedDepth/parameter_updates +/kinect_head/depth/image_raw/theora +/kinect_head/depth/image_raw/theora/parameter_descriptions +/kinect_head/depth/image_raw/theora/parameter_updates +/kinect_head/depth/image_raw/zdepth +/kinect_head/depth/image_rect +/kinect_head/depth/image_rect/compressed +/kinect_head/depth/image_rect/compressed/parameter_descriptions +/kinect_head/depth/image_rect/compressed/parameter_updates +/kinect_head/depth/image_rect/compressedDepth +/kinect_head/depth/image_rect/compressedDepth/parameter_descriptions +/kinect_head/depth/image_rect/compressedDepth/parameter_updates +/kinect_head/depth/image_rect/theora +/kinect_head/depth/image_rect/theora/parameter_descriptions +/kinect_head/depth/image_rect/theora/parameter_updates +/kinect_head/depth/image_rect/zdepth +/kinect_head/depth/image_rect_raw +/kinect_head/depth/image_rect_raw/compressed +/kinect_head/depth/image_rect_raw/compressed/parameter_descriptions +/kinect_head/depth/image_rect_raw/compressed/parameter_updates +/kinect_head/depth/image_rect_raw/compressedDepth +/kinect_head/depth/image_rect_raw/compressedDepth/parameter_descriptions +/kinect_head/depth/image_rect_raw/compressedDepth/parameter_updates +/kinect_head/depth/image_rect_raw/theora +/kinect_head/depth/image_rect_raw/theora/parameter_descriptions +/kinect_head/depth/image_rect_raw/theora/parameter_updates +/kinect_head/depth/image_rect_raw/zdepth +/kinect_head/depth/points +/kinect_head/depth_rectify_depth/parameter_descriptions +/kinect_head/depth_rectify_depth/parameter_updates +/kinect_head/depth_registered/camera_info +/kinect_head/depth_registered/disparity +/kinect_head/depth_registered/downsample_cloud_half/input/mask +/kinect_head/depth_registered/downsample_cloud_half/parameter_descriptions +/kinect_head/depth_registered/downsample_cloud_half/parameter_updates +/kinect_head/depth_registered/downsample_cloud_quater/input/mask +/kinect_head/depth_registered/downsample_cloud_quater/parameter_descriptions +/kinect_head/depth_registered/downsample_cloud_quater/parameter_updates +/kinect_head/depth_registered/half/points +/kinect_head/depth_registered/half/throttled/points +/kinect_head/depth_registered/hw_registered/image_rect +/kinect_head/depth_registered/hw_registered/image_rect/compressed +/kinect_head/depth_registered/hw_registered/image_rect/compressed/parameter_descriptions +/kinect_head/depth_registered/hw_registered/image_rect/compressed/parameter_updates +/kinect_head/depth_registered/hw_registered/image_rect/compressedDepth +/kinect_head/depth_registered/hw_registered/image_rect/compressedDepth/parameter_descriptions +/kinect_head/depth_registered/hw_registered/image_rect/compressedDepth/parameter_updates +/kinect_head/depth_registered/hw_registered/image_rect/theora +/kinect_head/depth_registered/hw_registered/image_rect/theora/parameter_descriptions +/kinect_head/depth_registered/hw_registered/image_rect/theora/parameter_updates +/kinect_head/depth_registered/hw_registered/image_rect/zdepth +/kinect_head/depth_registered/hw_registered/image_rect_raw +/kinect_head/depth_registered/hw_registered/image_rect_raw/compressed +/kinect_head/depth_registered/hw_registered/image_rect_raw/compressed/parameter_descriptions +/kinect_head/depth_registered/hw_registered/image_rect_raw/compressed/parameter_updates +/kinect_head/depth_registered/hw_registered/image_rect_raw/compressedDepth +/kinect_head/depth_registered/hw_registered/image_rect_raw/compressedDepth/parameter_descriptions +/kinect_head/depth_registered/hw_registered/image_rect_raw/compressedDepth/parameter_updates +/kinect_head/depth_registered/hw_registered/image_rect_raw/theora +/kinect_head/depth_registered/hw_registered/image_rect_raw/theora/parameter_descriptions +/kinect_head/depth_registered/hw_registered/image_rect_raw/theora/parameter_updates +/kinect_head/depth_registered/hw_registered/image_rect_raw/zdepth +/kinect_head/depth_registered/image +/kinect_head/depth_registered/image/compressed +/kinect_head/depth_registered/image/compressed/parameter_descriptions +/kinect_head/depth_registered/image/compressed/parameter_updates +/kinect_head/depth_registered/image/compressedDepth +/kinect_head/depth_registered/image/compressedDepth/parameter_descriptions +/kinect_head/depth_registered/image/compressedDepth/parameter_updates +/kinect_head/depth_registered/image/theora +/kinect_head/depth_registered/image/theora/parameter_descriptions +/kinect_head/depth_registered/image/theora/parameter_updates +/kinect_head/depth_registered/image/zdepth +/kinect_head/depth_registered/image_raw +/kinect_head/depth_registered/image_raw/compressed +/kinect_head/depth_registered/image_raw/compressed/parameter_descriptions +/kinect_head/depth_registered/image_raw/compressed/parameter_updates +/kinect_head/depth_registered/image_raw/compressedDepth +/kinect_head/depth_registered/image_raw/compressedDepth/parameter_descriptions +/kinect_head/depth_registered/image_raw/compressedDepth/parameter_updates +/kinect_head/depth_registered/image_raw/theora +/kinect_head/depth_registered/image_raw/theora/parameter_descriptions +/kinect_head/depth_registered/image_raw/theora/parameter_updates +/kinect_head/depth_registered/image_raw/zdepth +/kinect_head/depth_registered/image_rect +/kinect_head/depth_registered/image_rect/compressedDepth +/kinect_head/depth_registered/points +/kinect_head/depth_registered/points_self_filtered +/kinect_head/depth_registered/quater/points +/kinect_head/depth_registered/quater/throttled/points +/kinect_head/depth_registered/throttle_camera_info/parameter_descriptions +/kinect_head/depth_registered/throttle_camera_info/parameter_updates +/kinect_head/depth_registered/throttle_cloud/parameter_descriptions +/kinect_head/depth_registered/throttle_cloud/parameter_updates +/kinect_head/depth_registered/throttle_cloud_half/parameter_descriptions +/kinect_head/depth_registered/throttle_cloud_half/parameter_updates +/kinect_head/depth_registered/throttle_cloud_quater/parameter_descriptions +/kinect_head/depth_registered/throttle_cloud_quater/parameter_updates +/kinect_head/depth_registered/throttle_image/parameter_descriptions +/kinect_head/depth_registered/throttle_image/parameter_updates +/kinect_head/depth_registered/throttle_image_compressed/parameter_descriptions +/kinect_head/depth_registered/throttle_image_compressed/parameter_updates +/kinect_head/depth_registered/throttled/camera_info +/kinect_head/depth_registered/throttled/image_rect +/kinect_head/depth_registered/throttled/image_rect/compressedDepth +/kinect_head/depth_registered/throttled/points +/kinect_head/depth_registered_rectify_depth/parameter_descriptions +/kinect_head/depth_registered_rectify_depth/parameter_updates +/kinect_head/driver/parameter_descriptions +/kinect_head/driver/parameter_updates +/kinect_head/ir/camera_info +/kinect_head/ir/image_raw +/kinect_head/ir/image_raw/compressed +/kinect_head/ir/image_raw/compressed/parameter_descriptions +/kinect_head/ir/image_raw/compressed/parameter_updates +/kinect_head/ir/image_raw/compressedDepth +/kinect_head/ir/image_raw/compressedDepth/parameter_descriptions +/kinect_head/ir/image_raw/compressedDepth/parameter_updates +/kinect_head/ir/image_raw/theora +/kinect_head/ir/image_raw/theora/parameter_descriptions +/kinect_head/ir/image_raw/theora/parameter_updates +/kinect_head/ir/image_raw/zdepth +/kinect_head/ir/image_rect_ir +/kinect_head/ir/image_rect_ir/compressed +/kinect_head/ir/image_rect_ir/compressed/parameter_descriptions +/kinect_head/ir/image_rect_ir/compressed/parameter_updates +/kinect_head/ir/image_rect_ir/compressedDepth +/kinect_head/ir/image_rect_ir/compressedDepth/parameter_descriptions +/kinect_head/ir/image_rect_ir/compressedDepth/parameter_updates +/kinect_head/ir/image_rect_ir/theora +/kinect_head/ir/image_rect_ir/theora/parameter_descriptions +/kinect_head/ir/image_rect_ir/theora/parameter_updates +/kinect_head/ir/image_rect_ir/zdepth +/kinect_head/ir_rectify_ir/parameter_descriptions +/kinect_head/ir_rectify_ir/parameter_updates +/kinect_head/kinect_head_c2_nodelet_manager/bond +/kinect_head/kinect_head_nodelet_manager/bond +/kinect_head/projector/camera_info +/kinect_head/rgb/camera_info +/kinect_head/rgb/downsample_half/parameter_descriptions +/kinect_head/rgb/downsample_half/parameter_updates +/kinect_head/rgb/downsample_quater/parameter_descriptions +/kinect_head/rgb/downsample_quater/parameter_updates +/kinect_head/rgb/half/camera_info +/kinect_head/rgb/half/image_rect_color +/kinect_head/rgb/half/image_rect_color/compressed +/kinect_head/rgb/half/image_rect_color/compressed/parameter_descriptions +/kinect_head/rgb/half/image_rect_color/compressed/parameter_updates +/kinect_head/rgb/half/image_rect_color/compressedDepth +/kinect_head/rgb/half/image_rect_color/compressedDepth/parameter_descriptions +/kinect_head/rgb/half/image_rect_color/compressedDepth/parameter_updates +/kinect_head/rgb/half/image_rect_color/theora +/kinect_head/rgb/half/image_rect_color/theora/parameter_descriptions +/kinect_head/rgb/half/image_rect_color/theora/parameter_updates +/kinect_head/rgb/half/image_rect_color/zdepth +/kinect_head/rgb/image_color +/kinect_head/rgb/image_color/compressed +/kinect_head/rgb/image_color/compressed/parameter_descriptions +/kinect_head/rgb/image_color/compressed/parameter_updates +/kinect_head/rgb/image_color/compressedDepth +/kinect_head/rgb/image_color/compressedDepth/parameter_descriptions +/kinect_head/rgb/image_color/compressedDepth/parameter_updates +/kinect_head/rgb/image_color/theora +/kinect_head/rgb/image_color/theora/parameter_descriptions +/kinect_head/rgb/image_color/theora/parameter_updates +/kinect_head/rgb/image_color/zdepth +/kinect_head/rgb/image_mono +/kinect_head/rgb/image_mono/compressed +/kinect_head/rgb/image_mono/compressed/parameter_descriptions +/kinect_head/rgb/image_mono/compressed/parameter_updates +/kinect_head/rgb/image_mono/compressedDepth +/kinect_head/rgb/image_mono/compressedDepth/parameter_descriptions +/kinect_head/rgb/image_mono/compressedDepth/parameter_updates +/kinect_head/rgb/image_mono/theora +/kinect_head/rgb/image_mono/theora/parameter_descriptions +/kinect_head/rgb/image_mono/theora/parameter_updates +/kinect_head/rgb/image_mono/zdepth +/kinect_head/rgb/image_raw +/kinect_head/rgb/image_raw/compressed +/kinect_head/rgb/image_raw/compressed/parameter_descriptions +/kinect_head/rgb/image_raw/compressed/parameter_updates +/kinect_head/rgb/image_raw/compressedDepth +/kinect_head/rgb/image_raw/compressedDepth/parameter_descriptions +/kinect_head/rgb/image_raw/compressedDepth/parameter_updates +/kinect_head/rgb/image_raw/theora +/kinect_head/rgb/image_raw/theora/parameter_descriptions +/kinect_head/rgb/image_raw/theora/parameter_updates +/kinect_head/rgb/image_raw/zdepth +/kinect_head/rgb/image_rect_color +/kinect_head/rgb/image_rect_color/compressed +/kinect_head/rgb/image_rect_color/compressed/parameter_descriptions +/kinect_head/rgb/image_rect_color/compressed/parameter_updates +/kinect_head/rgb/image_rect_color/compressedDepth +/kinect_head/rgb/image_rect_color/compressedDepth/parameter_descriptions +/kinect_head/rgb/image_rect_color/compressedDepth/parameter_updates +/kinect_head/rgb/image_rect_color/theora +/kinect_head/rgb/image_rect_color/theora/parameter_descriptions +/kinect_head/rgb/image_rect_color/theora/parameter_updates +/kinect_head/rgb/image_rect_color/zdepth +/kinect_head/rgb/image_rect_mono +/kinect_head/rgb/image_rect_mono/compressed +/kinect_head/rgb/image_rect_mono/compressed/parameter_descriptions +/kinect_head/rgb/image_rect_mono/compressed/parameter_updates +/kinect_head/rgb/image_rect_mono/compressedDepth +/kinect_head/rgb/image_rect_mono/compressedDepth/parameter_descriptions +/kinect_head/rgb/image_rect_mono/compressedDepth/parameter_updates +/kinect_head/rgb/image_rect_mono/theora +/kinect_head/rgb/image_rect_mono/theora/parameter_descriptions +/kinect_head/rgb/image_rect_mono/theora/parameter_updates +/kinect_head/rgb/image_rect_mono/zdepth +/kinect_head/rgb/quater/camera_info +/kinect_head/rgb/quater/image_rect_color +/kinect_head/rgb/quater/image_rect_color/compressed +/kinect_head/rgb/quater/image_rect_color/compressed/parameter_descriptions +/kinect_head/rgb/quater/image_rect_color/compressed/parameter_updates +/kinect_head/rgb/quater/image_rect_color/compressedDepth +/kinect_head/rgb/quater/image_rect_color/compressedDepth/parameter_descriptions +/kinect_head/rgb/quater/image_rect_color/compressedDepth/parameter_updates +/kinect_head/rgb/quater/image_rect_color/theora +/kinect_head/rgb/quater/image_rect_color/theora/parameter_descriptions +/kinect_head/rgb/quater/image_rect_color/theora/parameter_updates +/kinect_head/rgb/quater/image_rect_color/zdepth +/kinect_head/rgb/throttle_camera_info/parameter_descriptions +/kinect_head/rgb/throttle_camera_info/parameter_updates +/kinect_head/rgb/throttle_rgb/parameter_descriptions +/kinect_head/rgb/throttle_rgb/parameter_updates +/kinect_head/rgb/throttle_rgb_compressed/parameter_descriptions +/kinect_head/rgb/throttle_rgb_compressed/parameter_updates +/kinect_head/rgb/throttled/camera_info +/kinect_head/rgb/throttled/image_rect_color +/kinect_head/rgb/throttled/image_rect_color/compressed +/kinect_head/rgb_debayer/parameter_descriptions +/kinect_head/rgb_debayer/parameter_updates +/kinect_head/rgb_rectify_color/parameter_descriptions +/kinect_head/rgb_rectify_color/parameter_updates +/kinect_head/rgb_rectify_mono/parameter_descriptions +/kinect_head/rgb_rectify_mono/parameter_updates +/kinect_head_c2/depth_registered/camera_info +/kinect_head_c2/depth_registered/points +/kinect_head_c2/rgb/camera_info +/kinect_head_c2/rgb/image_rect_color +/l_arm_controller/command +/l_arm_controller/follow_joint_trajectory/cancel +/l_arm_controller/follow_joint_trajectory/feedback +/l_arm_controller/follow_joint_trajectory/goal +/l_arm_controller/follow_joint_trajectory/result +/l_arm_controller/follow_joint_trajectory/status +/l_arm_controller/gains/l_elbow_flex_joint/parameter_descriptions +/l_arm_controller/gains/l_elbow_flex_joint/parameter_updates +/l_arm_controller/gains/l_forearm_roll_joint/parameter_descriptions +/l_arm_controller/gains/l_forearm_roll_joint/parameter_updates +/l_arm_controller/gains/l_shoulder_lift_joint/parameter_descriptions +/l_arm_controller/gains/l_shoulder_lift_joint/parameter_updates +/l_arm_controller/gains/l_shoulder_pan_joint/parameter_descriptions +/l_arm_controller/gains/l_shoulder_pan_joint/parameter_updates +/l_arm_controller/gains/l_upper_arm_roll_joint/parameter_descriptions +/l_arm_controller/gains/l_upper_arm_roll_joint/parameter_updates +/l_arm_controller/gains/l_wrist_flex_joint/parameter_descriptions +/l_arm_controller/gains/l_wrist_flex_joint/parameter_updates +/l_arm_controller/gains/l_wrist_roll_joint/parameter_descriptions +/l_arm_controller/gains/l_wrist_roll_joint/parameter_updates +/l_arm_controller/joint_trajectory_action/cancel +/l_arm_controller/joint_trajectory_action/feedback +/l_arm_controller/joint_trajectory_action/goal +/l_arm_controller/joint_trajectory_action/result +/l_arm_controller/joint_trajectory_action/status +/l_arm_controller/state +/l_arm_controller_loose/command +/l_arm_controller_loose/state +/l_forearm_cam/camera_info +/l_forearm_cam/image_color +/l_forearm_cam/image_color/compressed +/l_forearm_cam/image_color/compressed/parameter_descriptions +/l_forearm_cam/image_color/compressed/parameter_updates +/l_forearm_cam/image_color/compressedDepth +/l_forearm_cam/image_color/compressedDepth/parameter_descriptions +/l_forearm_cam/image_color/compressedDepth/parameter_updates +/l_forearm_cam/image_color/theora +/l_forearm_cam/image_color/theora/parameter_descriptions +/l_forearm_cam/image_color/theora/parameter_updates +/l_forearm_cam/image_color/zdepth +/l_forearm_cam/image_mono +/l_forearm_cam/image_mono/compressed +/l_forearm_cam/image_mono/compressed/parameter_descriptions +/l_forearm_cam/image_mono/compressed/parameter_updates +/l_forearm_cam/image_mono/compressedDepth +/l_forearm_cam/image_mono/compressedDepth/parameter_descriptions +/l_forearm_cam/image_mono/compressedDepth/parameter_updates +/l_forearm_cam/image_mono/theora +/l_forearm_cam/image_mono/theora/parameter_descriptions +/l_forearm_cam/image_mono/theora/parameter_updates +/l_forearm_cam/image_mono/zdepth +/l_forearm_cam/image_proc_debayer/parameter_descriptions +/l_forearm_cam/image_proc_debayer/parameter_updates +/l_forearm_cam/image_proc_rectify_color/parameter_descriptions +/l_forearm_cam/image_proc_rectify_color/parameter_updates +/l_forearm_cam/image_proc_rectify_mono/parameter_descriptions +/l_forearm_cam/image_proc_rectify_mono/parameter_updates +/l_forearm_cam/image_raw +/l_forearm_cam/image_raw/compressed +/l_forearm_cam/image_raw/compressed/parameter_descriptions +/l_forearm_cam/image_raw/compressed/parameter_updates +/l_forearm_cam/image_raw/compressedDepth +/l_forearm_cam/image_raw/compressedDepth/parameter_descriptions +/l_forearm_cam/image_raw/compressedDepth/parameter_updates +/l_forearm_cam/image_raw/theora +/l_forearm_cam/image_raw/theora/parameter_descriptions +/l_forearm_cam/image_raw/theora/parameter_updates +/l_forearm_cam/image_raw/zdepth +/l_forearm_cam/image_rect +/l_forearm_cam/image_rect/compressed +/l_forearm_cam/image_rect/compressed/parameter_descriptions +/l_forearm_cam/image_rect/compressed/parameter_updates +/l_forearm_cam/image_rect/compressedDepth +/l_forearm_cam/image_rect/compressedDepth/parameter_descriptions +/l_forearm_cam/image_rect/compressedDepth/parameter_updates +/l_forearm_cam/image_rect/theora +/l_forearm_cam/image_rect/theora/parameter_descriptions +/l_forearm_cam/image_rect/theora/parameter_updates +/l_forearm_cam/image_rect/zdepth +/l_forearm_cam/image_rect_color +/l_forearm_cam/image_rect_color/compressed +/l_forearm_cam/image_rect_color/compressed/parameter_descriptions +/l_forearm_cam/image_rect_color/compressed/parameter_updates +/l_forearm_cam/image_rect_color/compressedDepth +/l_forearm_cam/image_rect_color/compressedDepth/parameter_descriptions +/l_forearm_cam/image_rect_color/compressedDepth/parameter_updates +/l_forearm_cam/image_rect_color/theora +/l_forearm_cam/image_rect_color/theora/parameter_descriptions +/l_forearm_cam/image_rect_color/theora/parameter_updates +/l_forearm_cam/image_rect_color/zdepth +/l_forearm_cam/parameter_descriptions +/l_forearm_cam/parameter_updates +/l_forearm_cam_trigger/waveform +/l_gripper_controller/command +/l_gripper_controller/gripper_action/cancel +/l_gripper_controller/gripper_action/feedback +/l_gripper_controller/gripper_action/goal +/l_gripper_controller/gripper_action/result +/l_gripper_controller/gripper_action/status +/l_gripper_controller/pid/parameter_descriptions +/l_gripper_controller/pid/parameter_updates +/l_gripper_controller/state +/l_gripper_sensor_controller/command +/l_gripper_sensor_controller/contact_state +/l_gripper_sensor_controller/event_detector +/l_gripper_sensor_controller/event_detector/cancel +/l_gripper_sensor_controller/event_detector/feedback +/l_gripper_sensor_controller/event_detector/goal +/l_gripper_sensor_controller/event_detector/result +/l_gripper_sensor_controller/event_detector/status +/l_gripper_sensor_controller/event_detector_state +/l_gripper_sensor_controller/find_contact +/l_gripper_sensor_controller/find_contact/cancel +/l_gripper_sensor_controller/find_contact/feedback +/l_gripper_sensor_controller/find_contact/goal +/l_gripper_sensor_controller/find_contact/result +/l_gripper_sensor_controller/find_contact/status +/l_gripper_sensor_controller/force_servo +/l_gripper_sensor_controller/force_servo/cancel +/l_gripper_sensor_controller/force_servo/feedback +/l_gripper_sensor_controller/force_servo/goal +/l_gripper_sensor_controller/force_servo/result +/l_gripper_sensor_controller/force_servo/status +/l_gripper_sensor_controller/force_servo_state +/l_gripper_sensor_controller/grab/cancel +/l_gripper_sensor_controller/grab/feedback +/l_gripper_sensor_controller/grab/goal +/l_gripper_sensor_controller/grab/result +/l_gripper_sensor_controller/grab/status +/l_gripper_sensor_controller/gripper_action/cancel +/l_gripper_sensor_controller/gripper_action/feedback +/l_gripper_sensor_controller/gripper_action/goal +/l_gripper_sensor_controller/gripper_action/result +/l_gripper_sensor_controller/gripper_action/status +/l_gripper_sensor_controller/release/cancel +/l_gripper_sensor_controller/release/feedback +/l_gripper_sensor_controller/release/goal +/l_gripper_sensor_controller/release/result +/l_gripper_sensor_controller/release/status +/l_gripper_sensor_controller/slip_servo +/l_gripper_sensor_controller/slip_servo/cancel +/l_gripper_sensor_controller/slip_servo/feedback +/l_gripper_sensor_controller/slip_servo/goal +/l_gripper_sensor_controller/slip_servo/result +/l_gripper_sensor_controller/slip_servo/status +/l_gripper_sensor_controller/slip_servo_state +/l_gripper_sensor_controller/state +/laser_tilt_controller/gains/parameter_descriptions +/laser_tilt_controller/gains/parameter_updates +/laser_tilt_controller/laser_scanner_signal +/laser_tilt_controller/set_periodic_cmd +/laser_tilt_controller/set_traj_cmd +/left_endeffector/wrench +/lifelog/joint_states_logger/output +/lifelog/joint_states_logger/parameter_descriptions +/lifelog/joint_states_logger/parameter_updates +/lifelog/joint_states_throttle/output +/lifelog/joint_states_throttle/parameter_descriptions +/lifelog/joint_states_throttle/parameter_updates +/look_at_human/enabled +/map +/map_keepout +/map_metadata +/map_reload +/map_tf_mux/selected +/map_updates +/mechanism_statistics +/message_store/insert +/motor_trace/bl_caster_l_wheel_motor +/motor_trace/bl_caster_r_wheel_motor +/motor_trace/bl_caster_rotation_motor +/motor_trace/br_caster_l_wheel_motor +/motor_trace/br_caster_r_wheel_motor +/motor_trace/br_caster_rotation_motor +/motor_trace/fl_caster_l_wheel_motor +/motor_trace/fl_caster_r_wheel_motor +/motor_trace/fl_caster_rotation_motor +/motor_trace/fr_caster_l_wheel_motor +/motor_trace/fr_caster_r_wheel_motor +/motor_trace/fr_caster_rotation_motor +/motor_trace/head_pan_motor +/motor_trace/head_tilt_motor +/motor_trace/l_elbow_flex_motor +/motor_trace/l_forearm_roll_motor +/motor_trace/l_gripper_motor +/motor_trace/l_shoulder_lift_motor +/motor_trace/l_shoulder_pan_motor +/motor_trace/l_upper_arm_roll_motor +/motor_trace/l_wrist_l_motor +/motor_trace/l_wrist_r_motor +/motor_trace/laser_tilt_mount_motor +/motor_trace/r_elbow_flex_motor +/motor_trace/r_forearm_roll_motor +/motor_trace/r_gripper_motor +/motor_trace/r_shoulder_lift_motor +/motor_trace/r_shoulder_pan_motor +/motor_trace/r_upper_arm_roll_motor +/motor_trace/r_wrist_l_motor +/motor_trace/r_wrist_r_motor +/motor_trace/torso_lift_motor +/move_base/cancel +/move_base/feedback +/move_base/goal +/move_base/recovery_status +/move_base/result +/move_base/status +/move_base_node/DWAPlannerROS/cost_cloud +/move_base_node/DWAPlannerROS/global_plan +/move_base_node/DWAPlannerROS/local_plan +/move_base_node/DWAPlannerROS/parameter_descriptions +/move_base_node/DWAPlannerROS/parameter_updates +/move_base_node/DWAPlannerROS/trajectory_cloud +/move_base_node/NavfnROS/plan +/move_base_node/current_goal +/move_base_node/global_costmap/costmap +/move_base_node/global_costmap/costmap_updates +/move_base_node/global_costmap/footprint +/move_base_node/global_costmap/inflation_layer/parameter_descriptions +/move_base_node/global_costmap/inflation_layer/parameter_updates +/move_base_node/global_costmap/obstacle_layer/parameter_descriptions +/move_base_node/global_costmap/obstacle_layer/parameter_updates +/move_base_node/global_costmap/parameter_descriptions +/move_base_node/global_costmap/parameter_updates +/move_base_node/global_costmap/static_layer/parameter_descriptions +/move_base_node/global_costmap/static_layer/parameter_updates +/move_base_node/local_costmap/costmap +/move_base_node/local_costmap/costmap_updates +/move_base_node/local_costmap/footprint +/move_base_node/local_costmap/inflation_layer/parameter_descriptions +/move_base_node/local_costmap/inflation_layer/parameter_updates +/move_base_node/local_costmap/obstacle_layer/parameter_descriptions +/move_base_node/local_costmap/obstacle_layer/parameter_updates +/move_base_node/local_costmap/parameter_descriptions +/move_base_node/local_costmap/parameter_updates +/move_base_node/parameter_descriptions +/move_base_node/parameter_updates +/move_base_simple/goal +/multiple_joystick_mux/selected +/narrow_stereo/disparity +/narrow_stereo/left/camera_info +/narrow_stereo/left/image_color +/narrow_stereo/left/image_color/compressed +/narrow_stereo/left/image_color/compressed/parameter_descriptions +/narrow_stereo/left/image_color/compressed/parameter_updates +/narrow_stereo/left/image_color/compressedDepth +/narrow_stereo/left/image_color/compressedDepth/parameter_descriptions +/narrow_stereo/left/image_color/compressedDepth/parameter_updates +/narrow_stereo/left/image_color/theora +/narrow_stereo/left/image_color/theora/parameter_descriptions +/narrow_stereo/left/image_color/theora/parameter_updates +/narrow_stereo/left/image_color/zdepth +/narrow_stereo/left/image_mono +/narrow_stereo/left/image_mono/compressed +/narrow_stereo/left/image_mono/compressed/parameter_descriptions +/narrow_stereo/left/image_mono/compressed/parameter_updates +/narrow_stereo/left/image_mono/compressedDepth +/narrow_stereo/left/image_mono/compressedDepth/parameter_descriptions +/narrow_stereo/left/image_mono/compressedDepth/parameter_updates +/narrow_stereo/left/image_mono/theora +/narrow_stereo/left/image_mono/theora/parameter_descriptions +/narrow_stereo/left/image_mono/theora/parameter_updates +/narrow_stereo/left/image_mono/zdepth +/narrow_stereo/left/image_raw +/narrow_stereo/left/image_raw/compressed +/narrow_stereo/left/image_raw/compressed/parameter_descriptions +/narrow_stereo/left/image_raw/compressed/parameter_updates +/narrow_stereo/left/image_raw/compressedDepth +/narrow_stereo/left/image_raw/compressedDepth/parameter_descriptions +/narrow_stereo/left/image_raw/compressedDepth/parameter_updates +/narrow_stereo/left/image_raw/theora +/narrow_stereo/left/image_raw/theora/parameter_descriptions +/narrow_stereo/left/image_raw/theora/parameter_updates +/narrow_stereo/left/image_raw/zdepth +/narrow_stereo/left/image_rect +/narrow_stereo/left/image_rect/compressed +/narrow_stereo/left/image_rect/compressed/parameter_descriptions +/narrow_stereo/left/image_rect/compressed/parameter_updates +/narrow_stereo/left/image_rect/compressedDepth +/narrow_stereo/left/image_rect/compressedDepth/parameter_descriptions +/narrow_stereo/left/image_rect/compressedDepth/parameter_updates +/narrow_stereo/left/image_rect/theora +/narrow_stereo/left/image_rect/theora/parameter_descriptions +/narrow_stereo/left/image_rect/theora/parameter_updates +/narrow_stereo/left/image_rect/zdepth +/narrow_stereo/left/image_rect_color +/narrow_stereo/left/image_rect_color/compressed +/narrow_stereo/left/image_rect_color/compressed/parameter_descriptions +/narrow_stereo/left/image_rect_color/compressed/parameter_updates +/narrow_stereo/left/image_rect_color/compressedDepth +/narrow_stereo/left/image_rect_color/compressedDepth/parameter_descriptions +/narrow_stereo/left/image_rect_color/compressedDepth/parameter_updates +/narrow_stereo/left/image_rect_color/theora +/narrow_stereo/left/image_rect_color/theora/parameter_descriptions +/narrow_stereo/left/image_rect_color/theora/parameter_updates +/narrow_stereo/left/image_rect_color/zdepth +/narrow_stereo/narrow_stereo_proc/parameter_descriptions +/narrow_stereo/narrow_stereo_proc/parameter_updates +/narrow_stereo/narrow_stereo_proc_debayer_left/parameter_descriptions +/narrow_stereo/narrow_stereo_proc_debayer_left/parameter_updates +/narrow_stereo/narrow_stereo_proc_debayer_right/parameter_descriptions +/narrow_stereo/narrow_stereo_proc_debayer_right/parameter_updates +/narrow_stereo/narrow_stereo_proc_rectify_color_left/parameter_descriptions +/narrow_stereo/narrow_stereo_proc_rectify_color_left/parameter_updates +/narrow_stereo/narrow_stereo_proc_rectify_color_right/parameter_descriptions +/narrow_stereo/narrow_stereo_proc_rectify_color_right/parameter_updates +/narrow_stereo/narrow_stereo_proc_rectify_mono_left/parameter_descriptions +/narrow_stereo/narrow_stereo_proc_rectify_mono_left/parameter_updates +/narrow_stereo/narrow_stereo_proc_rectify_mono_right/parameter_descriptions +/narrow_stereo/narrow_stereo_proc_rectify_mono_right/parameter_updates +/narrow_stereo/points2 +/narrow_stereo/right/camera_info +/narrow_stereo/right/image_color +/narrow_stereo/right/image_color/compressed +/narrow_stereo/right/image_color/compressed/parameter_descriptions +/narrow_stereo/right/image_color/compressed/parameter_updates +/narrow_stereo/right/image_color/compressedDepth +/narrow_stereo/right/image_color/compressedDepth/parameter_descriptions +/narrow_stereo/right/image_color/compressedDepth/parameter_updates +/narrow_stereo/right/image_color/theora +/narrow_stereo/right/image_color/theora/parameter_descriptions +/narrow_stereo/right/image_color/theora/parameter_updates +/narrow_stereo/right/image_color/zdepth +/narrow_stereo/right/image_mono +/narrow_stereo/right/image_mono/compressed +/narrow_stereo/right/image_mono/compressed/parameter_descriptions +/narrow_stereo/right/image_mono/compressed/parameter_updates +/narrow_stereo/right/image_mono/compressedDepth +/narrow_stereo/right/image_mono/compressedDepth/parameter_descriptions +/narrow_stereo/right/image_mono/compressedDepth/parameter_updates +/narrow_stereo/right/image_mono/theora +/narrow_stereo/right/image_mono/theora/parameter_descriptions +/narrow_stereo/right/image_mono/theora/parameter_updates +/narrow_stereo/right/image_mono/zdepth +/narrow_stereo/right/image_raw +/narrow_stereo/right/image_raw/compressed +/narrow_stereo/right/image_raw/compressed/parameter_descriptions +/narrow_stereo/right/image_raw/compressed/parameter_updates +/narrow_stereo/right/image_raw/compressedDepth +/narrow_stereo/right/image_raw/compressedDepth/parameter_descriptions +/narrow_stereo/right/image_raw/compressedDepth/parameter_updates +/narrow_stereo/right/image_raw/theora +/narrow_stereo/right/image_raw/theora/parameter_descriptions +/narrow_stereo/right/image_raw/theora/parameter_updates +/narrow_stereo/right/image_raw/zdepth +/narrow_stereo/right/image_rect +/narrow_stereo/right/image_rect/compressed +/narrow_stereo/right/image_rect/compressed/parameter_descriptions +/narrow_stereo/right/image_rect/compressed/parameter_updates +/narrow_stereo/right/image_rect/compressedDepth +/narrow_stereo/right/image_rect/compressedDepth/parameter_descriptions +/narrow_stereo/right/image_rect/compressedDepth/parameter_updates +/narrow_stereo/right/image_rect/theora +/narrow_stereo/right/image_rect/theora/parameter_descriptions +/narrow_stereo/right/image_rect/theora/parameter_updates +/narrow_stereo/right/image_rect/zdepth +/narrow_stereo/right/image_rect_color +/narrow_stereo/right/image_rect_color/compressed +/narrow_stereo/right/image_rect_color/compressed/parameter_descriptions +/narrow_stereo/right/image_rect_color/compressed/parameter_updates +/narrow_stereo/right/image_rect_color/compressedDepth +/narrow_stereo/right/image_rect_color/compressedDepth/parameter_descriptions +/narrow_stereo/right/image_rect_color/compressedDepth/parameter_updates +/narrow_stereo/right/image_rect_color/theora +/narrow_stereo/right/image_rect_color/theora/parameter_descriptions +/narrow_stereo/right/image_rect_color/theora/parameter_updates +/narrow_stereo/right/image_rect_color/zdepth +/narrow_stereo_both/parameter_descriptions +/narrow_stereo_both/parameter_updates +/narrow_stereo_left/parameter_descriptions +/narrow_stereo_left/parameter_updates +/narrow_stereo_right/parameter_descriptions +/narrow_stereo_right/parameter_updates +/narrow_stereo_textured/disparity +/narrow_stereo_textured/left/camera_info +/narrow_stereo_textured/left/image_color +/narrow_stereo_textured/left/image_color/compressed +/narrow_stereo_textured/left/image_color/compressed/parameter_descriptions +/narrow_stereo_textured/left/image_color/compressed/parameter_updates +/narrow_stereo_textured/left/image_color/compressedDepth +/narrow_stereo_textured/left/image_color/compressedDepth/parameter_descriptions +/narrow_stereo_textured/left/image_color/compressedDepth/parameter_updates +/narrow_stereo_textured/left/image_color/theora +/narrow_stereo_textured/left/image_color/theora/parameter_descriptions +/narrow_stereo_textured/left/image_color/theora/parameter_updates +/narrow_stereo_textured/left/image_color/zdepth +/narrow_stereo_textured/left/image_mono +/narrow_stereo_textured/left/image_mono/compressed +/narrow_stereo_textured/left/image_mono/compressed/parameter_descriptions +/narrow_stereo_textured/left/image_mono/compressed/parameter_updates +/narrow_stereo_textured/left/image_mono/compressedDepth +/narrow_stereo_textured/left/image_mono/compressedDepth/parameter_descriptions +/narrow_stereo_textured/left/image_mono/compressedDepth/parameter_updates +/narrow_stereo_textured/left/image_mono/theora +/narrow_stereo_textured/left/image_mono/theora/parameter_descriptions +/narrow_stereo_textured/left/image_mono/theora/parameter_updates +/narrow_stereo_textured/left/image_mono/zdepth +/narrow_stereo_textured/left/image_raw +/narrow_stereo_textured/left/image_raw/compressed +/narrow_stereo_textured/left/image_raw/compressed/parameter_descriptions +/narrow_stereo_textured/left/image_raw/compressed/parameter_updates +/narrow_stereo_textured/left/image_raw/compressedDepth +/narrow_stereo_textured/left/image_raw/compressedDepth/parameter_descriptions +/narrow_stereo_textured/left/image_raw/compressedDepth/parameter_updates +/narrow_stereo_textured/left/image_raw/theora +/narrow_stereo_textured/left/image_raw/theora/parameter_descriptions +/narrow_stereo_textured/left/image_raw/theora/parameter_updates +/narrow_stereo_textured/left/image_raw/zdepth +/narrow_stereo_textured/left/image_rect +/narrow_stereo_textured/left/image_rect/compressed +/narrow_stereo_textured/left/image_rect/compressed/parameter_descriptions +/narrow_stereo_textured/left/image_rect/compressed/parameter_updates +/narrow_stereo_textured/left/image_rect/compressedDepth +/narrow_stereo_textured/left/image_rect/compressedDepth/parameter_descriptions +/narrow_stereo_textured/left/image_rect/compressedDepth/parameter_updates +/narrow_stereo_textured/left/image_rect/theora +/narrow_stereo_textured/left/image_rect/theora/parameter_descriptions +/narrow_stereo_textured/left/image_rect/theora/parameter_updates +/narrow_stereo_textured/left/image_rect/zdepth +/narrow_stereo_textured/left/image_rect_color +/narrow_stereo_textured/left/image_rect_color/compressed +/narrow_stereo_textured/left/image_rect_color/compressed/parameter_descriptions +/narrow_stereo_textured/left/image_rect_color/compressed/parameter_updates +/narrow_stereo_textured/left/image_rect_color/compressedDepth +/narrow_stereo_textured/left/image_rect_color/compressedDepth/parameter_descriptions +/narrow_stereo_textured/left/image_rect_color/compressedDepth/parameter_updates +/narrow_stereo_textured/left/image_rect_color/theora +/narrow_stereo_textured/left/image_rect_color/theora/parameter_descriptions +/narrow_stereo_textured/left/image_rect_color/theora/parameter_updates +/narrow_stereo_textured/left/image_rect_color/zdepth +/narrow_stereo_textured/narrow_stereo_textured_proc/parameter_descriptions +/narrow_stereo_textured/narrow_stereo_textured_proc/parameter_updates +/narrow_stereo_textured/narrow_stereo_textured_proc_debayer_left/parameter_descriptions +/narrow_stereo_textured/narrow_stereo_textured_proc_debayer_left/parameter_updates +/narrow_stereo_textured/narrow_stereo_textured_proc_debayer_right/parameter_descriptions +/narrow_stereo_textured/narrow_stereo_textured_proc_debayer_right/parameter_updates +/narrow_stereo_textured/narrow_stereo_textured_proc_rectify_color_left/parameter_descriptions +/narrow_stereo_textured/narrow_stereo_textured_proc_rectify_color_left/parameter_updates +/narrow_stereo_textured/narrow_stereo_textured_proc_rectify_color_right/parameter_descriptions +/narrow_stereo_textured/narrow_stereo_textured_proc_rectify_color_right/parameter_updates +/narrow_stereo_textured/narrow_stereo_textured_proc_rectify_mono_left/parameter_descriptions +/narrow_stereo_textured/narrow_stereo_textured_proc_rectify_mono_left/parameter_updates +/narrow_stereo_textured/narrow_stereo_textured_proc_rectify_mono_right/parameter_descriptions +/narrow_stereo_textured/narrow_stereo_textured_proc_rectify_mono_right/parameter_updates +/narrow_stereo_textured/points2 +/narrow_stereo_textured/right/camera_info +/narrow_stereo_textured/right/image_color +/narrow_stereo_textured/right/image_color/compressed +/narrow_stereo_textured/right/image_color/compressed/parameter_descriptions +/narrow_stereo_textured/right/image_color/compressed/parameter_updates +/narrow_stereo_textured/right/image_color/compressedDepth +/narrow_stereo_textured/right/image_color/compressedDepth/parameter_descriptions +/narrow_stereo_textured/right/image_color/compressedDepth/parameter_updates +/narrow_stereo_textured/right/image_color/theora +/narrow_stereo_textured/right/image_color/theora/parameter_descriptions +/narrow_stereo_textured/right/image_color/theora/parameter_updates +/narrow_stereo_textured/right/image_color/zdepth +/narrow_stereo_textured/right/image_mono +/narrow_stereo_textured/right/image_mono/compressed +/narrow_stereo_textured/right/image_mono/compressed/parameter_descriptions +/narrow_stereo_textured/right/image_mono/compressed/parameter_updates +/narrow_stereo_textured/right/image_mono/compressedDepth +/narrow_stereo_textured/right/image_mono/compressedDepth/parameter_descriptions +/narrow_stereo_textured/right/image_mono/compressedDepth/parameter_updates +/narrow_stereo_textured/right/image_mono/theora +/narrow_stereo_textured/right/image_mono/theora/parameter_descriptions +/narrow_stereo_textured/right/image_mono/theora/parameter_updates +/narrow_stereo_textured/right/image_mono/zdepth +/narrow_stereo_textured/right/image_raw +/narrow_stereo_textured/right/image_raw/compressed +/narrow_stereo_textured/right/image_raw/compressed/parameter_descriptions +/narrow_stereo_textured/right/image_raw/compressed/parameter_updates +/narrow_stereo_textured/right/image_raw/compressedDepth +/narrow_stereo_textured/right/image_raw/compressedDepth/parameter_descriptions +/narrow_stereo_textured/right/image_raw/compressedDepth/parameter_updates +/narrow_stereo_textured/right/image_raw/theora +/narrow_stereo_textured/right/image_raw/theora/parameter_descriptions +/narrow_stereo_textured/right/image_raw/theora/parameter_updates +/narrow_stereo_textured/right/image_raw/zdepth +/narrow_stereo_textured/right/image_rect +/narrow_stereo_textured/right/image_rect/compressed +/narrow_stereo_textured/right/image_rect/compressed/parameter_descriptions +/narrow_stereo_textured/right/image_rect/compressed/parameter_updates +/narrow_stereo_textured/right/image_rect/compressedDepth +/narrow_stereo_textured/right/image_rect/compressedDepth/parameter_descriptions +/narrow_stereo_textured/right/image_rect/compressedDepth/parameter_updates +/narrow_stereo_textured/right/image_rect/theora +/narrow_stereo_textured/right/image_rect/theora/parameter_descriptions +/narrow_stereo_textured/right/image_rect/theora/parameter_updates +/narrow_stereo_textured/right/image_rect/zdepth +/narrow_stereo_textured/right/image_rect_color +/narrow_stereo_textured/right/image_rect_color/compressed +/narrow_stereo_textured/right/image_rect_color/compressed/parameter_descriptions +/narrow_stereo_textured/right/image_rect_color/compressed/parameter_updates +/narrow_stereo_textured/right/image_rect_color/compressedDepth +/narrow_stereo_textured/right/image_rect_color/compressedDepth/parameter_descriptions +/narrow_stereo_textured/right/image_rect_color/compressedDepth/parameter_updates +/narrow_stereo_textured/right/image_rect_color/theora +/narrow_stereo_textured/right/image_rect_color/theora/parameter_descriptions +/narrow_stereo_textured/right/image_rect_color/theora/parameter_updates +/narrow_stereo_textured/right/image_rect_color/zdepth +/navigation/cmd_vel +/navigation/cmd_vel/raw +/network/connected +/odom_teleop +/particlecloud +/power_board/state +/power_monitor/parameter_descriptions +/power_monitor/parameter_updates +/power_state +/pr1040/app_list +/pr1040/application/app_status +/pr1040/bond0/receive +/pr1040/bond0/receive_kbps +/pr1040/bond0/receive_mbps +/pr1040/bond0/transmit +/pr1040/bond0/transmit_kbps +/pr1040/bond0/transmit_mbps +/pr1040/lan0/receive +/pr1040/lan0/receive_kbps +/pr1040/lan0/receive_mbps +/pr1040/lan0/transmit +/pr1040/lan0/transmit_kbps +/pr1040/lan0/transmit_mbps +/pr1040/lan1/receive +/pr1040/lan1/receive_kbps +/pr1040/lan1/receive_mbps +/pr1040/lan1/transmit +/pr1040/lan1/transmit_kbps +/pr1040/lan1/transmit_mbps +/pr1040/lan2/receive +/pr1040/lan2/receive_kbps +/pr1040/lan2/receive_mbps +/pr1040/lan2/transmit +/pr1040/lan2/transmit_kbps +/pr1040/lan2/transmit_mbps +/pr1040/lan3/receive +/pr1040/lan3/receive_kbps +/pr1040/lan3/receive_mbps +/pr1040/lan3/transmit +/pr1040/lan3/transmit_kbps +/pr1040/lan3/transmit_mbps +/pr1040/lo/receive +/pr1040/lo/receive_kbps +/pr1040/lo/receive_mbps +/pr1040/lo/transmit +/pr1040/lo/transmit_kbps +/pr1040/lo/transmit_mbps +/pr1040/nonlocal/receive +/pr1040/nonlocal/receive_kbps +/pr1040/nonlocal/receive_mbps +/pr1040/nonlocal/transmit +/pr1040/nonlocal/transmit_kbps +/pr1040/nonlocal/transmit_mbps +/pr1040/wan0/receive +/pr1040/wan0/receive_kbps +/pr1040/wan0/receive_mbps +/pr1040/wan0/transmit +/pr1040/wan0/transmit_kbps +/pr1040/wan0/transmit_mbps +/pr2_ethercat/motors_halted +/pr2_move_base/cancel +/pr2_move_base/feedback +/pr2_move_base/goal +/pr2_move_base/result +/pr2_move_base/status +/pr2twit_from_tablet +/pressure/l_gripper_motor +/pressure/r_gripper_motor +/projector_controller/falling_edge_timestamps +/projector_controller/rising_edge_timestamps +/projector_trigger/off_time +/projector_trigger/on_time +/projector_trigger/waveform +/prosilica_inhibit_projector_controller/waveform +/r_arm_controller/command +/r_arm_controller/follow_joint_trajectory/cancel +/r_arm_controller/follow_joint_trajectory/feedback +/r_arm_controller/follow_joint_trajectory/goal +/r_arm_controller/follow_joint_trajectory/result +/r_arm_controller/follow_joint_trajectory/status +/r_arm_controller/gains/r_elbow_flex_joint/parameter_descriptions +/r_arm_controller/gains/r_elbow_flex_joint/parameter_updates +/r_arm_controller/gains/r_forearm_roll_joint/parameter_descriptions +/r_arm_controller/gains/r_forearm_roll_joint/parameter_updates +/r_arm_controller/gains/r_shoulder_lift_joint/parameter_descriptions +/r_arm_controller/gains/r_shoulder_lift_joint/parameter_updates +/r_arm_controller/gains/r_shoulder_pan_joint/parameter_descriptions +/r_arm_controller/gains/r_shoulder_pan_joint/parameter_updates +/r_arm_controller/gains/r_upper_arm_roll_joint/parameter_descriptions +/r_arm_controller/gains/r_upper_arm_roll_joint/parameter_updates +/r_arm_controller/gains/r_wrist_flex_joint/parameter_descriptions +/r_arm_controller/gains/r_wrist_flex_joint/parameter_updates +/r_arm_controller/gains/r_wrist_roll_joint/parameter_descriptions +/r_arm_controller/gains/r_wrist_roll_joint/parameter_updates +/r_arm_controller/joint_trajectory_action/cancel +/r_arm_controller/joint_trajectory_action/feedback +/r_arm_controller/joint_trajectory_action/goal +/r_arm_controller/joint_trajectory_action/result +/r_arm_controller/joint_trajectory_action/status +/r_arm_controller/state +/r_arm_controller_loose/command +/r_arm_controller_loose/state +/r_forearm_cam/camera_info +/r_forearm_cam/image_color +/r_forearm_cam/image_color/compressed +/r_forearm_cam/image_color/compressed/parameter_descriptions +/r_forearm_cam/image_color/compressed/parameter_updates +/r_forearm_cam/image_color/compressedDepth +/r_forearm_cam/image_color/compressedDepth/parameter_descriptions +/r_forearm_cam/image_color/compressedDepth/parameter_updates +/r_forearm_cam/image_color/theora +/r_forearm_cam/image_color/theora/parameter_descriptions +/r_forearm_cam/image_color/theora/parameter_updates +/r_forearm_cam/image_color/zdepth +/r_forearm_cam/image_mono +/r_forearm_cam/image_mono/compressed +/r_forearm_cam/image_mono/compressed/parameter_descriptions +/r_forearm_cam/image_mono/compressed/parameter_updates +/r_forearm_cam/image_mono/compressedDepth +/r_forearm_cam/image_mono/compressedDepth/parameter_descriptions +/r_forearm_cam/image_mono/compressedDepth/parameter_updates +/r_forearm_cam/image_mono/theora +/r_forearm_cam/image_mono/theora/parameter_descriptions +/r_forearm_cam/image_mono/theora/parameter_updates +/r_forearm_cam/image_mono/zdepth +/r_forearm_cam/image_proc_debayer/parameter_descriptions +/r_forearm_cam/image_proc_debayer/parameter_updates +/r_forearm_cam/image_proc_rectify_color/parameter_descriptions +/r_forearm_cam/image_proc_rectify_color/parameter_updates +/r_forearm_cam/image_proc_rectify_mono/parameter_descriptions +/r_forearm_cam/image_proc_rectify_mono/parameter_updates +/r_forearm_cam/image_raw +/r_forearm_cam/image_raw/compressed +/r_forearm_cam/image_raw/compressed/parameter_descriptions +/r_forearm_cam/image_raw/compressed/parameter_updates +/r_forearm_cam/image_raw/compressedDepth +/r_forearm_cam/image_raw/compressedDepth/parameter_descriptions +/r_forearm_cam/image_raw/compressedDepth/parameter_updates +/r_forearm_cam/image_raw/theora +/r_forearm_cam/image_raw/theora/parameter_descriptions +/r_forearm_cam/image_raw/theora/parameter_updates +/r_forearm_cam/image_raw/zdepth +/r_forearm_cam/image_rect +/r_forearm_cam/image_rect/compressed +/r_forearm_cam/image_rect/compressed/parameter_descriptions +/r_forearm_cam/image_rect/compressed/parameter_updates +/r_forearm_cam/image_rect/compressedDepth +/r_forearm_cam/image_rect/compressedDepth/parameter_descriptions +/r_forearm_cam/image_rect/compressedDepth/parameter_updates +/r_forearm_cam/image_rect/theora +/r_forearm_cam/image_rect/theora/parameter_descriptions +/r_forearm_cam/image_rect/theora/parameter_updates +/r_forearm_cam/image_rect/zdepth +/r_forearm_cam/image_rect_color +/r_forearm_cam/image_rect_color/compressed +/r_forearm_cam/image_rect_color/compressed/parameter_descriptions +/r_forearm_cam/image_rect_color/compressed/parameter_updates +/r_forearm_cam/image_rect_color/compressedDepth +/r_forearm_cam/image_rect_color/compressedDepth/parameter_descriptions +/r_forearm_cam/image_rect_color/compressedDepth/parameter_updates +/r_forearm_cam/image_rect_color/theora +/r_forearm_cam/image_rect_color/theora/parameter_descriptions +/r_forearm_cam/image_rect_color/theora/parameter_updates +/r_forearm_cam/image_rect_color/zdepth +/r_forearm_cam/parameter_descriptions +/r_forearm_cam/parameter_updates +/r_forearm_cam_trigger/waveform +/r_gripper_controller/command +/r_gripper_controller/gripper_action/cancel +/r_gripper_controller/gripper_action/feedback +/r_gripper_controller/gripper_action/goal +/r_gripper_controller/gripper_action/result +/r_gripper_controller/gripper_action/status +/r_gripper_controller/pid/parameter_descriptions +/r_gripper_controller/pid/parameter_updates +/r_gripper_controller/state +/r_gripper_sensor_controller/command +/r_gripper_sensor_controller/contact_state +/r_gripper_sensor_controller/event_detector +/r_gripper_sensor_controller/event_detector/cancel +/r_gripper_sensor_controller/event_detector/feedback +/r_gripper_sensor_controller/event_detector/goal +/r_gripper_sensor_controller/event_detector/result +/r_gripper_sensor_controller/event_detector/status +/r_gripper_sensor_controller/event_detector_state +/r_gripper_sensor_controller/find_contact +/r_gripper_sensor_controller/find_contact/cancel +/r_gripper_sensor_controller/find_contact/feedback +/r_gripper_sensor_controller/find_contact/goal +/r_gripper_sensor_controller/find_contact/result +/r_gripper_sensor_controller/find_contact/status +/r_gripper_sensor_controller/force_servo +/r_gripper_sensor_controller/force_servo/cancel +/r_gripper_sensor_controller/force_servo/feedback +/r_gripper_sensor_controller/force_servo/goal +/r_gripper_sensor_controller/force_servo/result +/r_gripper_sensor_controller/force_servo/status +/r_gripper_sensor_controller/force_servo_state +/r_gripper_sensor_controller/grab/cancel +/r_gripper_sensor_controller/grab/feedback +/r_gripper_sensor_controller/grab/goal +/r_gripper_sensor_controller/grab/result +/r_gripper_sensor_controller/grab/status +/r_gripper_sensor_controller/gripper_action/cancel +/r_gripper_sensor_controller/gripper_action/feedback +/r_gripper_sensor_controller/gripper_action/goal +/r_gripper_sensor_controller/gripper_action/result +/r_gripper_sensor_controller/gripper_action/status +/r_gripper_sensor_controller/release/cancel +/r_gripper_sensor_controller/release/feedback +/r_gripper_sensor_controller/release/goal +/r_gripper_sensor_controller/release/result +/r_gripper_sensor_controller/release/status +/r_gripper_sensor_controller/slip_servo +/r_gripper_sensor_controller/slip_servo/cancel +/r_gripper_sensor_controller/slip_servo/feedback +/r_gripper_sensor_controller/slip_servo/goal +/r_gripper_sensor_controller/slip_servo/result +/r_gripper_sensor_controller/slip_servo/status +/r_gripper_sensor_controller/slip_servo_state +/r_gripper_sensor_controller/state +/right_endeffector/wrench +/robot_interface_marker_array +/robot_pose_ekf/odom_combined +/robotsound +/robotsound/cancel +/robotsound/feedback +/robotsound/goal +/robotsound/result +/robotsound/status +/robotsound_jp +/robotsound_jp/cancel +/robotsound_jp/feedback +/robotsound_jp/goal +/robotsound_jp/result +/robotsound_jp/status +/rosout +/rosout_agg +/safe_teleop_base/local_costmap/costmap +/safe_teleop_base/local_costmap/costmap_updates +/safe_teleop_base/local_costmap/footprint +/safe_teleop_base/local_costmap/inflation_layer/parameter_descriptions +/safe_teleop_base/local_costmap/inflation_layer/parameter_updates +/safe_teleop_base/local_costmap/obstacle_layer/parameter_descriptions +/safe_teleop_base/local_costmap/obstacle_layer/parameter_updates +/safe_teleop_base/local_costmap/parameter_descriptions +/safe_teleop_base/local_costmap/parameter_updates +/safe_teleop_base/local_plan +/safe_teleop_base/user_plan +/scene_marker_array +/server_name/smach/container_status +/server_name/smach/container_structure +/smach_image_publisher/image +/smach_image_publisher/image/compressed +/smach_to_mail/parameter_descriptions +/smach_to_mail/parameter_updates +/sound_play/cancel +/sound_play/feedback +/sound_play/goal +/sound_play/result +/sound_play/status +/speech_audio +/speech_to_text +/speech_to_text_google +/speech_to_text_julius +/speech_to_text_mux/selected +/speech_to_text_other +/spots_marker_array +/teleop/cmd_vel +/teleop/cmd_vel/safe +/teleop/cmd_vel/unsafe +/teleop/joy_vel +/tf +/tf2_buffer_server/cancel +/tf2_buffer_server/feedback +/tf2_buffer_server/goal +/tf2_buffer_server/result +/tf2_buffer_server/status +/tf_static +/tilt_hokuyo_node/parameter_descriptions +/tilt_hokuyo_node/parameter_updates +/tilt_laser_mux/selected +/tilt_scan +/tilt_scan_filtered +/tilt_scan_filtered/navigation +/tilt_scan_filtered/scan +/tilt_scan_interpolated +/tilt_scan_shadow_filtered +/tilt_scan_throttled +/tilt_shadow_filter/dark_shadows/parameter_descriptions +/tilt_shadow_filter/dark_shadows/parameter_updates +/tilt_shadow_filter/shadows/parameter_descriptions +/tilt_shadow_filter/shadows/parameter_updates +/torso_controller/command +/torso_controller/command_deadman +/torso_controller/command_dummy +/torso_controller/follow_joint_trajectory/cancel +/torso_controller/follow_joint_trajectory/feedback +/torso_controller/follow_joint_trajectory/goal +/torso_controller/follow_joint_trajectory/result +/torso_controller/follow_joint_trajectory/status +/torso_controller/gains/torso_lift_joint/parameter_descriptions +/torso_controller/gains/torso_lift_joint/parameter_updates +/torso_controller/joint_trajectory_action/cancel +/torso_controller/joint_trajectory_action/feedback +/torso_controller/joint_trajectory_action/goal +/torso_controller/joint_trajectory_action/result +/torso_controller/joint_trajectory_action/status +/torso_controller/mux/selected +/torso_controller/position_joint_action/cancel +/torso_controller/position_joint_action/feedback +/torso_controller/position_joint_action/goal +/torso_controller/position_joint_action/result +/torso_controller/position_joint_action/status +/torso_controller/state +/torso_lift_imu/data +/torso_lift_imu/is_calibrated +/tuck_arms/cancel +/tuck_arms/feedback +/tuck_arms/goal +/tuck_arms/result +/tuck_arms/status +/tweet +/tweet_client_tablet/parameter_descriptions +/tweet_client_tablet/parameter_updates +/tweet_client_uptime/parameter_descriptions +/tweet_client_uptime/parameter_updates +/tweet_client_warning/parameter_descriptions +/tweet_client_warning/parameter_updates +/tweet_client_worktime/parameter_descriptions +/tweet_client_worktime/parameter_updates +/tweet_compressed_image_mux/selected +/tweet_image +/tweet_image/compressed +/tweet_image_mux/selected +/tweet_image_server/parameter_descriptions +/tweet_image_server/parameter_updates +/tweet_image_server/tweet/cancel +/tweet_image_server/tweet/feedback +/tweet_image_server/tweet/goal +/tweet_image_server/tweet/result +/tweet_image_server/tweet/status +/unsafe_vel_mux/selected +/vel_type_mux/selected +/visualization/battery/value0 +/visualization/battery/value1 +/visualization/battery/value2 +/visualization/battery/value3 +/voice_text/parameter_descriptions +/voice_text/parameter_updates +/wide_stereo/disparity +/wide_stereo/left/camera_info +/wide_stereo/left/image_color +/wide_stereo/left/image_color/compressed +/wide_stereo/left/image_color/compressed/parameter_descriptions +/wide_stereo/left/image_color/compressed/parameter_updates +/wide_stereo/left/image_color/compressedDepth +/wide_stereo/left/image_color/compressedDepth/parameter_descriptions +/wide_stereo/left/image_color/compressedDepth/parameter_updates +/wide_stereo/left/image_color/theora +/wide_stereo/left/image_color/theora/parameter_descriptions +/wide_stereo/left/image_color/theora/parameter_updates +/wide_stereo/left/image_color/zdepth +/wide_stereo/left/image_mono +/wide_stereo/left/image_mono/compressed +/wide_stereo/left/image_mono/compressed/parameter_descriptions +/wide_stereo/left/image_mono/compressed/parameter_updates +/wide_stereo/left/image_mono/compressedDepth +/wide_stereo/left/image_mono/compressedDepth/parameter_descriptions +/wide_stereo/left/image_mono/compressedDepth/parameter_updates +/wide_stereo/left/image_mono/theora +/wide_stereo/left/image_mono/theora/parameter_descriptions +/wide_stereo/left/image_mono/theora/parameter_updates +/wide_stereo/left/image_mono/zdepth +/wide_stereo/left/image_raw +/wide_stereo/left/image_raw/compressed +/wide_stereo/left/image_raw/compressed/parameter_descriptions +/wide_stereo/left/image_raw/compressed/parameter_updates +/wide_stereo/left/image_raw/compressedDepth +/wide_stereo/left/image_raw/compressedDepth/parameter_descriptions +/wide_stereo/left/image_raw/compressedDepth/parameter_updates +/wide_stereo/left/image_raw/theora +/wide_stereo/left/image_raw/theora/parameter_descriptions +/wide_stereo/left/image_raw/theora/parameter_updates +/wide_stereo/left/image_raw/zdepth +/wide_stereo/left/image_rect +/wide_stereo/left/image_rect/compressed +/wide_stereo/left/image_rect/compressed/parameter_descriptions +/wide_stereo/left/image_rect/compressed/parameter_updates +/wide_stereo/left/image_rect/compressedDepth +/wide_stereo/left/image_rect/compressedDepth/parameter_descriptions +/wide_stereo/left/image_rect/compressedDepth/parameter_updates +/wide_stereo/left/image_rect/theora +/wide_stereo/left/image_rect/theora/parameter_descriptions +/wide_stereo/left/image_rect/theora/parameter_updates +/wide_stereo/left/image_rect/zdepth +/wide_stereo/left/image_rect_color +/wide_stereo/left/image_rect_color/compressed +/wide_stereo/left/image_rect_color/compressed/parameter_descriptions +/wide_stereo/left/image_rect_color/compressed/parameter_updates +/wide_stereo/left/image_rect_color/compressedDepth +/wide_stereo/left/image_rect_color/compressedDepth/parameter_descriptions +/wide_stereo/left/image_rect_color/compressedDepth/parameter_updates +/wide_stereo/left/image_rect_color/theora +/wide_stereo/left/image_rect_color/theora/parameter_descriptions +/wide_stereo/left/image_rect_color/theora/parameter_updates +/wide_stereo/left/image_rect_color/zdepth +/wide_stereo/points2 +/wide_stereo/right/camera_info +/wide_stereo/right/image_color +/wide_stereo/right/image_color/compressed +/wide_stereo/right/image_color/compressed/parameter_descriptions +/wide_stereo/right/image_color/compressed/parameter_updates +/wide_stereo/right/image_color/compressedDepth +/wide_stereo/right/image_color/compressedDepth/parameter_descriptions +/wide_stereo/right/image_color/compressedDepth/parameter_updates +/wide_stereo/right/image_color/theora +/wide_stereo/right/image_color/theora/parameter_descriptions +/wide_stereo/right/image_color/theora/parameter_updates +/wide_stereo/right/image_color/zdepth +/wide_stereo/right/image_mono +/wide_stereo/right/image_mono/compressed +/wide_stereo/right/image_mono/compressed/parameter_descriptions +/wide_stereo/right/image_mono/compressed/parameter_updates +/wide_stereo/right/image_mono/compressedDepth +/wide_stereo/right/image_mono/compressedDepth/parameter_descriptions +/wide_stereo/right/image_mono/compressedDepth/parameter_updates +/wide_stereo/right/image_mono/theora +/wide_stereo/right/image_mono/theora/parameter_descriptions +/wide_stereo/right/image_mono/theora/parameter_updates +/wide_stereo/right/image_mono/zdepth +/wide_stereo/right/image_raw +/wide_stereo/right/image_raw/compressed +/wide_stereo/right/image_raw/compressed/parameter_descriptions +/wide_stereo/right/image_raw/compressed/parameter_updates +/wide_stereo/right/image_raw/compressedDepth +/wide_stereo/right/image_raw/compressedDepth/parameter_descriptions +/wide_stereo/right/image_raw/compressedDepth/parameter_updates +/wide_stereo/right/image_raw/theora +/wide_stereo/right/image_raw/theora/parameter_descriptions +/wide_stereo/right/image_raw/theora/parameter_updates +/wide_stereo/right/image_raw/zdepth +/wide_stereo/right/image_rect +/wide_stereo/right/image_rect/compressed +/wide_stereo/right/image_rect/compressed/parameter_descriptions +/wide_stereo/right/image_rect/compressed/parameter_updates +/wide_stereo/right/image_rect/compressedDepth +/wide_stereo/right/image_rect/compressedDepth/parameter_descriptions +/wide_stereo/right/image_rect/compressedDepth/parameter_updates +/wide_stereo/right/image_rect/theora +/wide_stereo/right/image_rect/theora/parameter_descriptions +/wide_stereo/right/image_rect/theora/parameter_updates +/wide_stereo/right/image_rect/zdepth +/wide_stereo/right/image_rect_color +/wide_stereo/right/image_rect_color/compressed +/wide_stereo/right/image_rect_color/compressed/parameter_descriptions +/wide_stereo/right/image_rect_color/compressed/parameter_updates +/wide_stereo/right/image_rect_color/compressedDepth +/wide_stereo/right/image_rect_color/compressedDepth/parameter_descriptions +/wide_stereo/right/image_rect_color/compressedDepth/parameter_updates +/wide_stereo/right/image_rect_color/theora +/wide_stereo/right/image_rect_color/theora/parameter_descriptions +/wide_stereo/right/image_rect_color/theora/parameter_updates +/wide_stereo/right/image_rect_color/zdepth +/wide_stereo/wide_stereo_proc/parameter_descriptions +/wide_stereo/wide_stereo_proc/parameter_updates +/wide_stereo/wide_stereo_proc_debayer_left/parameter_descriptions +/wide_stereo/wide_stereo_proc_debayer_left/parameter_updates +/wide_stereo/wide_stereo_proc_debayer_right/parameter_descriptions +/wide_stereo/wide_stereo_proc_debayer_right/parameter_updates +/wide_stereo/wide_stereo_proc_rectify_color_left/parameter_descriptions +/wide_stereo/wide_stereo_proc_rectify_color_left/parameter_updates +/wide_stereo/wide_stereo_proc_rectify_color_right/parameter_descriptions +/wide_stereo/wide_stereo_proc_rectify_color_right/parameter_updates +/wide_stereo/wide_stereo_proc_rectify_mono_left/parameter_descriptions +/wide_stereo/wide_stereo_proc_rectify_mono_left/parameter_updates +/wide_stereo/wide_stereo_proc_rectify_mono_right/parameter_descriptions +/wide_stereo/wide_stereo_proc_rectify_mono_right/parameter_updates +/wide_stereo_both/parameter_descriptions +/wide_stereo_both/parameter_updates +/wide_stereo_left/parameter_descriptions +/wide_stereo_left/parameter_updates +/wide_stereo_right/parameter_descriptions +/wide_stereo_right/parameter_updates +[http://pr1040:11311][133.11.216.23] mech-user@ki00119:~/semi_ws/src$ rostopic echo cmd_vel +WARNING: topic [/cmd_vel] does not appear to be published yet +WARNING: topic [/cmd_vel] does not appear to be published yet C-c C-c[http://pr1040:11311][133.11.216.23] mech-user@ki00119:~/semi_ws/src$ rostopic echo /cmd_vel +WARNING: topic [/cmd_vel] does not appear to be published yet +WARNING: topic [/cmd_vel] does not appear to be published yet C-c C-c[http://pr1040:11311][133.11.216.23] mech-user@ki00119:~/semi_ws/src$ rostopic echo /teleop/cmd_vel +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.08775347471237183 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.08775347471237183 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.12523576021194457 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.12523576021194457 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.11585824489593506 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.1064807415008545 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.09710323810577393 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.09710323810577393 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: 0.0 + y: 0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.0 +--- +linear: + x: 0.0 + y: 0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.7156579494476318 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.7156579494476318 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.6594206333160401 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.38766720294952395 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: 0.0 + y: 0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.0 +--- +linear: + x: 0.0 + y: 0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.0 +--- +linear: + x: 0.0 + y: 0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.0 +--- +linear: + x: 0.0 + y: 0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.0 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.06897072196006775 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.06897072196006775 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.6031833648681642 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.6031833648681642 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: -0.0 + y: -0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: -0.8 +--- +linear: + x: 0.0 + y: 0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.0 +--- +linear: + x: 0.0 + y: 0.0 + z: 0.0 +angular: + x: 0.0 + y: 0.0 + z: 0.0 +--- + C-c C-c[http://pr1040:11311][133.11.216.23] mech-user@ki00119:~/semi_ws/src$ roseus +configuring by "/opt/ros/noetic/share/euslisp/jskeus/eus//lib/eusrt.l" +;; readmacro ;; object ;; packsym ;; common ;; constants ;; stream ;; string ;; loader ;; pprint ;; process ;; hashtab ;; array ;; mathtran ;; eusdebug ;; eusforeign ;; extnum ;; coordinates ;; tty ;; history ;; toplevel ;; trans ;; comp ;; builtins ;; par ;; intersection ;; geoclasses ;; geopack ;; geobody ;; primt ;; compose ;; polygon ;; viewing ;; viewport ;; viewsurface ;; hid ;; shadow ;; bodyrel ;; dda ;; helpsub ;; eushelp ;; xforeign ;; Xdecl ;; Xgraphics ;; Xcolor ;; Xeus ;; Xevent ;; Xpanel ;; Xitem ;; Xtext ;; Xmenu ;; Xscroll ;; Xcanvas ;; Xtop ;; Xapplwin +connected to Xserver DISPLAY=:0 +X events are being asynchronously monitored. +;; pixword ;; RGBHLS ;; convolve ;; piximage ;; pbmfile ;; image_correlation ;; oglforeign ;; gldecl ;; glconst ;; glforeign ;; gluconst ;; gluforeign ;; glxconst ;; glxforeign ;; eglforeign ;; eglfunc ;; glutil ;; gltexture ;; glprim ;; gleus ;; glview ;; toiv-undefined ;; fstringdouble irtmath irtutil irtc irtgeoc irtgraph gnuplotlib ___time ___pgsql irtgeo euspqp pqp irtscene irtmodel irtdyna irtrobot irtsensor irtbvh irtcollada irtstl irtwrl irtpointcloud eusbullet bullet irtcollision irtx eusjpeg euspng png irtimage irtglrgb +;; extending gcstack 0x55e5a09ab680[16374] --> 0x55e5a0e3bc90[32748] top=3d4b +irtgl irtglc irtviewer +EusLisp 9.29( 1.2.5) for Linux64 created on ip-10-0-1-5(Tue Jun 20 10:34:21 PST 2023) +roseus ;; loading roseus("1.7.5") on euslisp((9.29 ip-10-0-1-5 Tue Jun 20 10:34:21 PST 2023 1.2.5)) +eustf roseus_c_util 1.irteusgl$ (load "first_motion.l") +;; (make-irtviewer) executed +t +2.irteusgl$ +(require "package://pr2eus/pr2-interface.l") ;;import pr2 package + +nil +2.irteusgl$ ;; roseus_resume is disabled. +:|PACKAGE://PR2EUS/PR2-INTERFACE.L| +3.irteusgl$ nil +4.irteusgl$ nil +4.irteusgl$ pr2-init + +;; extending gcstack 0x55e5a0e3bc90[32738] --> 0x55e5a57c6540[65476] top=7d95 +;; # :joint-angle(-22.158) violate min-angle(-21.2682) +;; # :joint-angle(-122.512) violate min-angle(-121.542) +;; # :joint-angle(-5.38629) violate max-angle(-5.72958) +nil +5.irteusgl$ (send *ri* :angle-vector (send *pr2* :angle-vector)) +;; # :joint-angle(-22.158) violate min-angle(-21.2682) +;; # :joint-angle(-122.512) violate min-angle(-121.542) +;; # :joint-angle(-5.38629) violate max-angle(-5.72958) +;; # :joint-angle(-22.158) violate min-angle(-21.2682) +;; # :joint-angle(-122.512) violate min-angle(-121.542) +;; # :joint-angle(-5.38629) violate max-angle(-5.72958) +;; # :joint-angle(-22.158) violate min-angle(-21.2682) +;; # :joint-angle(-122.512) violate min-angle(-121.542) +;; # :joint-angle(-5.38629) violate max-angle(-5.72958) +;; # :joint-angle(-22.158) violate min-angle(-21.2682) +;; # :joint-angle(-122.512) violate min-angle(-121.542) +;; # :joint-angle(-5.38629) violate max-angle(-5.72958) +;; # :joint-angle(-22.158) violate min-angle(-21.2682) +;; # :joint-angle(-122.512) violate min-angle(-121.542) +;; # :joint-angle(-5.38629) violate max-angle(-5.72958) +;; # :joint-angle(-5.34142) violate max-angle(-5.72958) +;; # :joint-angle(-123.607) violate min-angle(-121.542) +;; # :joint-angle(-23.16) violate min-angle(-21.2682) +;; # :joint-angle(-22.158) violate min-angle(-21.2682) +;; # :joint-angle(-122.512) violate min-angle(-121.542) +;; # :joint-angle(-5.38629) violate max-angle(-5.72958) +#f(182.874 3.88879 68.4486 104.412 -81.4114 -98.4558 -5.72958 -4.6688 0.452866 63.2517 -79.7933 -121.542 -100.615 -105.832 12.949 5.53153 -21.2682) +6.irteusgl$ (load "first_motion.l") +t +7.irteusgl$ (send *ri* :angle-vector (send *pr2* :angle-vector)) +;; # :joint-angle(-22.158) violate min-angle(-21.2682) +;; # :joint-angle(-122.47) violate min-angle(-121.542) +;; # :joint-angle(-5.72782) violate max-angle(-5.72958) +;; # :joint-angle(-22.158) violate min-angle(-21.2682) +;; # :joint-angle(-122.47) violate min-angle(-121.542) +;; # :joint-angle(-5.72782) violate max-angle(-5.72958) +;; # :joint-angle(-22.158) violate min-angle(-21.2682) +;; # :joint-angle(-122.47) violate min-angle(-121.542) +;; # :joint-angle(-5.72782) violate max-angle(-5.72958) +;; # :joint-angle(-22.158) violate min-angle(-21.2682) +;; # :joint-angle(-122.47) violate min-angle(-121.542) +;; # :joint-angle(-5.72782) violate max-angle(-5.72958) +;; # :joint-angle(-22.158) violate min-angle(-21.2682) +;; # :joint-angle(-122.47) violate min-angle(-121.542) +;; # :joint-angle(-5.72782) violate max-angle(-5.72958) +;; # :joint-angle(-21.2682) violate min-angle(-21.2682) +;; # :joint-angle(-22.158) violate min-angle(-21.2682) +;; # :joint-angle(-122.47) violate min-angle(-121.542) +;; # :joint-angle(-5.72782) violate max-angle(-5.72958) +#f(300.0 60.0 10.0 120.0 -120.0 20.0 -30.0 0.0 -60.0 -20.0 -120.0 -120.0 0.0 -40.0 0.0 0.0 0.0) +8.irteusgl$ (send *ri* :wait-interpolation) +[ INFO] [1729665278.625315427]: wait-interpolation debug: start +[ERROR] [1729665278.658195900]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1729665278.658251240]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1729665278.662522301]: wait-interpolation debug: end +(nil nil nil nil) +9.irteusgl$ (load "first_motion.l") +[ INFO] [1729665371.924329834]: wait-interpolation debug: start +[ERROR] [1729665391.152011698]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1729665391.152091968]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1729665391.152622378]: wait-interpolation debug: end +Call Stack (max depth: 20): + 0: at (send *irtv0) + 1: at (apply #'ros::load-org-for-ros ros::fullname args) + 2: at (apply #'ros::load-org-for-ros ros::fullname args) + 3: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 4: at (load "first_motion.l") + 5: at # +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: unbound variable *irtv0 in (send *irtv0) +10.E1-irteusgl$ reset +11.irteusgl$ (load "first_motion.l") +[ INFO] [1729665412.405603378]: wait-interpolation debug: start +[ INFO] [1729665413.445186124]: wait-interpolation debug: end +[ INFO] [1729665413.457923364]: wait-interpolation debug: start +[ INFO] [1729665414.496236238]: wait-interpolation debug: end +t +12.irteusgl$ (send *ri* :stop-grasp :arms) +(t t) +13.irteusgl$ (load "first_motion.l") +[ INFO] [1729665532.834773457]: wait-interpolation debug: start +[ INFO] [1729665533.934082201]: wait-interpolation debug: end +[ INFO] [1729665533.953203205]: wait-interpolation debug: start +[ INFO] [1729665535.016466058]: wait-interpolation debug: end +[ WARN] [1729665535.057218743]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1729665535.057659665]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1729665535.058899420]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1729665535.061647748]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1729665535.061957258]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1729665535.062237995]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ INFO] [1729665537.552695448]: wait-interpolation debug: start +[ INFO] [1729665537.553253665]: wait-interpolation debug: end +[ INFO] [1729665537.564546634]: wait-interpolation debug: start +[ INFO] [1729665538.724101798]: wait-interpolation debug: end +[ INFO] [1729665538.737843726]: wait-interpolation debug: start +[ WARN] [1729665538.821487506]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1729665538.822414806]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1729665538.828988142]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1729665538.829903044]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ INFO] [1729665539.849467686]: wait-interpolation debug: end +[ INFO] [1729665539.861754963]: wait-interpolation debug: start +[ INFO] [1729665540.953058540]: wait-interpolation debug: end +[ INFO] [1729665540.969119606]: wait-interpolation debug: start +[ INFO] [1729665542.035728532]: wait-interpolation debug: end +[ INFO] [1729665542.045338513]: wait-interpolation debug: start +[ INFO] [1729665543.169270450]: wait-interpolation debug: end +[ INFO] [1729665543.182459409]: wait-interpolation debug: start +[ WARN] [1729665543.244370062]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1729665543.245664202]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1729665543.250024477]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1729665543.259581768]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ INFO] [1729665544.229971396]: wait-interpolation debug: end +[ INFO] [1729665544.240476576]: wait-interpolation debug: start +[ WARN] [1729665544.258518085]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1729665544.260639341]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ INFO] [1729665545.290826686]: wait-interpolation debug: end +[ INFO] [1729665545.300205633]: wait-interpolation debug: start +[ INFO] [1729665546.343070104]: wait-interpolation debug: end +[ INFO] [1729665547.401782224]: wait-interpolation debug: start +[ INFO] [1729665548.449819092]: wait-interpolation debug: end +[ INFO] [1729665548.471123723]: wait-interpolation debug: start +[ INFO] [1729665549.540332440]: wait-interpolation debug: end +[ INFO] [1729665549.558752173]: wait-interpolation debug: start +[ INFO] [1729665550.593625320]: wait-interpolation debug: end +[ WARN] [1729665550.618664274]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1729665550.619075040]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ INFO] [1729665550.620444971]: wait-interpolation debug: start +[ INFO] [1729665551.662678868]: wait-interpolation debug: end +[ INFO] [1729665551.674839178]: wait-interpolation debug: start +[ WARN] [1729665551.690175755]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1729665551.690608557]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ INFO] [1729665552.819662941]: wait-interpolation debug: end +[ INFO] [1729665552.849406243]: wait-interpolation debug: start +[ERROR] [1729665564.452784076]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1729665564.452839911]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1729665564.454964335]: wait-interpolation debug: end +[ INFO] [1729665567.835068546]: wait-interpolation debug: start +[ERROR] [1729665575.595436467]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1729665575.595495803]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1729665575.597102187]: wait-interpolation debug: end +t +14.irteusgl$ + + + +mech-user@ki00119:~/semi_ws/src$ git clone https://github.com/jsk-ros-pkg/jsk_robot +Cloning into 'jsk_robot'... +remote: Enumerating objects: 38978, done. +remote: Counting objects: 100% (5743/5743), done. +remote: Compressing objects: 100% (1842/1842), done. +remote: Total 38978 (delta 4058), reused 5421 (delta 3884), pack-reused 33235 (from 1) +Receiving objects: 100% (38978/38978), 179.66 MiB | 24.21 MiB/s, done. +Resolving deltas: 100% (25707/25707), done. +mech-user@ki00119:~/semi_ws/src$ ls +jsk_robot +mech-user@ki00119:~/semi_ws/src$ ls +jsk_robot +mech-user@ki00119:~/semi_ws/src$ rm -fr jsk_robot/ +mech-user@ki00119:~/semi_ws/src$ cd .. +mech-user@ki00119:~/semi_ws$ git clone https://github.com/jsk-ros-pkg/jsk_demos -b jsk_2024_semi +Cloning into 'jsk_demos'... +fatal: Remote branch jsk_2024_semi not found in upstream origin +mech-user@ki00119:~/semi_ws$ git clone https://github.com/jsk-ros-pkg/jsk_demos +Cloning into 'jsk_demos'... +remote: Enumerating objects: 32410, done. +remote: Counting objects: 100% (6/6), done. +remote: Compressing objects: 100% (5/5), done. +remote: Total 32410 (delta 0), reused 5 (delta 0), pack-reused 32404 (from 1) +Receiving objects: 100% (32410/32410), 177.20 MiB | 23.39 MiB/s, done. +Resolving deltas: 100% (23469/23469), done. +cd j mech-user@ki00119:~/semi_ws$ cd jsk_demos/ +mech-user@ki00119:~/semi_ws/jsk_demos$ ls +2010_05_pr2_workshop jsk_2013_04_pr2_610 jsk_demo_common +README.md jsk_2013_05_pr2_tatu jsk_maps +detect_cans_in_fridge_201202 jsk_2014_06_pr2_drcbox jsk_semantic_maps +diabolo_pr2_201806 jsk_2015_06_hrp_drc rwt_teleop +elevator_move_base_pr2 jsk_2017_10_semi welcome_to_jsk_fetch +interactive_behavior_201409 jsk_2019_10_semi +jsk_2011_07_pr2_semantic jsk_2022_08_miraikan_demo +mech-user@ki00119:~/semi_ws/jsk_demos$ git checkout jsk_2024_10_semi +Branch 'jsk_2024_10_semi' set up to track remote branch 'jsk_2024_10_semi' from 'origin'. +Switched to a new branch 'jsk_2024_10_semi' +mech-user@ki00119:~/semi_ws/jsk_demos$ ls +2010_05_pr2_workshop jsk_2013_04_pr2_610 jsk_2024_10_semi +README.md jsk_2013_05_pr2_tatu jsk_demo_common +detect_cans_in_fridge_201202 jsk_2014_06_pr2_drcbox jsk_maps +diabolo_pr2_201806 jsk_2015_06_hrp_drc jsk_semantic_maps +elevator_move_base_pr2 jsk_2017_10_semi rwt_teleop +interactive_behavior_201409 jsk_2019_10_semi welcome_to_jsk_fetch +jsk_2011_07_pr2_semantic jsk_2022_08_miraikan_demo +mech-user@ki00119:~/semi_ws/jsk_demos$ cd ../src/ +mech-user@ki00119:~/semi_ws/src$ ls +mech-user@ki00119:~/semi_ws/src$ ln -sf ../jsk_demos/jsk_2024_10_semi/ +mech-user@ki00119:~/semi_ws/src$ ls +jsk_2024_10_semi +mech-user@ki00119:~/semi_ws/src$ cd jsk_2024_10_semi +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ ls +CMakeLists.txt README.md package.xml +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ catkin b t-vi +ca==> Expanding alias 'b' from 'catkin b t-vi' to 'catkin build t-vi' +Initialized new catkin workspace in `/home/mech-user/semi_ws/jsk_demos/jsk_2024_10_semi` +[build] Error: Unable to find source space `/home/mech-user/semi_ws/jsk_demos/jsk_2024_10_semi/src` +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ catkin bt -vi +==> Expanding alias 'bt' from 'catkin bt -vi' to 'catkin b --this -vi' +==> Expanding alias 'b' from 'catkin b --this -vi' to 'catkin build --this -vi' +[build] Error: In order to use --this, the current directory must be part of a catkin package. +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ cd ../../ +mech-user@ki00119:~/semi_ws$ catkin b +==> Expanding alias 'b' from 'catkin b' to 'catkin build' +Initialized new catkin workspace in `/home/mech-user/semi_ws` +------------------------------------------------------------ +Profile: default +Extending: [env] /opt/ros/noetic +Workspace: /home/mech-user/semi_ws +------------------------------------------------------------ +Build Space: [exists] /home/mech-user/semi_ws/build +Devel Space: [exists] /home/mech-user/semi_ws/devel +Install Space: [unused] /home/mech-user/semi_ws/install +Log Space: [missing] /home/mech-user/semi_ws/logs +Source Space: [exists] /home/mech-user/semi_ws/src +DESTDIR: [unused] None +------------------------------------------------------------ +Devel Space Layout: linked +Install Space Layout: None +------------------------------------------------------------ +Additional CMake Args: None +Additional Make Args: None +Additional catkin Make Args: None +Internal Make Job Server: True +Cache Job Environments: False +------------------------------------------------------------ +Buildlisted Packages: None +Skiplisted Packages: None +------------------------------------------------------------ +Workspace configuration appears valid. + +NOTE: Forcing CMake to run for each package. +------------------------------------------------------------ +[build] Found 1 packages in 0.0 seconds. +[build] Updating package table. +Starting >>> catkin_tools_prebuild +Finished <<< catkin_tools_prebuild [ 2.2 seconds ] +Starting >>> jsk_2024_10_semi +Finished <<< jsk_2024_10_semi [ 1.8 seconds ] +[build] Summary: All 2 packages succeeded! +[build] Ignored: None. +[build] Warnings: None. +[build] Abandoned: None. +[build] Failed: None. +[build] Runtime: 4.1 seconds total. +[build] Note: Workspace packages have changed, please re-source setup files to use them. +mech-user@ki00119:~/semi_ws$ source devel/setup.bash +mech-user@ki00119:~/semi_ws$ roscd jsk_2024_10_semi/ +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ ls +CMakeLists.txt README.md package.xml +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git remote -v +origin https://github.com/jsk-ros-pkg/jsk_demos (fetch) +origin https://github.com/jsk-ros-pkg/jsk_demos (push) +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ cp ~/semi_ws.bak/ +.catkin_tools/ devel/ src/ +.git/ homework241016.webm task.txt +README.md homework_uml.png +build/ logs/ +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ cp ~/semi_ws.bak/src/ +demo.l first_motion.l~ homework241016.l +first_motion.l hampen.mov homework_uml.act +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ cp ~/semi_ws.bak/src/* . +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ ls +CMakeLists.txt demo.l first_motion.l~ homework241016.l package.xml +README.md first_motion.l hampen.mov homework_uml.act +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git diff +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ ls +CMakeLists.txt demo.l first_motion.l~ homework241016.l package.xml +README.md first_motion.l hampen.mov homework_uml.act +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git add --all +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git commit -m"add 1023" +[jsk_2024_10_semi 295d7a47] add 1023 + 9 files changed, 496 insertions(+) + create mode 100644 jsk_2024_10_semi/.catkin_tools/CATKIN_IGNORE + create mode 100644 jsk_2024_10_semi/.catkin_tools/README + create mode 100644 jsk_2024_10_semi/.catkin_tools/VERSION + create mode 100644 jsk_2024_10_semi/.catkin_tools/profiles/profiles.yaml + create mode 100644 jsk_2024_10_semi/demo.l + create mode 100644 jsk_2024_10_semi/first_motion.l + create mode 100644 jsk_2024_10_semi/hampen.mov + create mode 100644 jsk_2024_10_semi/homework241016.l + create mode 100644 jsk_2024_10_semi/homework_uml.act +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git push +Username for 'https://github.com': ^C +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ rm -fr .catkin_tools/ +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git rm .catkin_tools/ +fatal: not removing '.catkin_tools/' recursively without -r +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git rm -r .catkin_tools/ +rm 'jsk_2024_10_semi/.catkin_tools/CATKIN_IGNORE' +rm 'jsk_2024_10_semi/.catkin_tools/README' +rm 'jsk_2024_10_semi/.catkin_tools/VERSION' +rm 'jsk_2024_10_semi/.catkin_tools/profiles/profiles.yaml' +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git commit --amend +[jsk_2024_10_semi a0d98162] add 1023 + Date: Wed Oct 23 15:56:46 2024 +0900 + 5 files changed, 481 insertions(+) + create mode 100644 jsk_2024_10_semi/demo.l + create mode 100644 jsk_2024_10_semi/first_motion.l + create mode 100644 jsk_2024_10_semi/hampen.mov + create mode 100644 jsk_2024_10_semi/homework241016.l + create mode 100644 jsk_2024_10_semi/homework_uml.act +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ ls +CMakeLists.txt demo.l first_motion.l~ homework241016.l package.xml +README.md first_motion.l hampen.mov homework_uml.act +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ ls -al +total 195140 +drwxrwxr-x 2 mech-user mech-user 4096 10月 23 15:57 . +drwxrwxr-x 24 mech-user mech-user 4096 10月 23 15:55 .. +-rw-rw-r-- 1 mech-user mech-user 206 10月 23 15:55 CMakeLists.txt +-rw-rw-r-- 1 mech-user mech-user 21 10月 23 15:55 README.md +-rw-rw-r-- 1 mech-user mech-user 184 10月 23 15:55 demo.l +-rw-rw-r-- 1 mech-user mech-user 8480 10月 23 15:55 first_motion.l +-rw-rw-r-- 1 mech-user mech-user 449 10月 23 15:55 first_motion.l~ +-rw-rw-r-- 1 mech-user mech-user 199762796 10月 23 15:55 hampen.mov +-rw-rw-r-- 1 mech-user mech-user 6555 10月 23 15:55 homework241016.l +-rw-rw-r-- 1 mech-user mech-user 843 10月 23 15:55 homework_uml.act +-rw-rw-r-- 1 mech-user mech-user 438 10月 23 15:55 package.xml +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git push +Username for 'https://github.com': ^C +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ ls +CMakeLists.txt demo.l first_motion.l~ homework241016.l package.xml +README.md first_motion.l hampen.mov homework_uml.act +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git remote add Michi-Tsubaki https://github.com//Michi-Tsubaki/jsk_demos.git +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git push Michi-Tsubaki jsk_2024_10_semi +Username for 'https://github.com': ^C +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git remote -v +Michi-Tsubaki https://github.com//Michi-Tsubaki/jsk_demos.git (fetch) +Michi-Tsubaki https://github.com//Michi-Tsubaki/jsk_demos.git (push) +origin https://github.com/jsk-ros-pkg/jsk_demos (fetch) +origin https://github.com/jsk-ros-pkg/jsk_demos (push) +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git remote add Michi-Tsubaki git@github.com:Michi-Tsubaki/jsk_demos.git +fatal: remote Michi-Tsubaki already exists. +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git remote del Michi-Tsubaki +error: Unknown subcommand: del +usage: git remote [-v | --verbose] + or: git remote add [-t ] [-m ] [-f] [--tags | --no-tags] [--mirror=] + or: git remote rename + or: git remote remove + or: git remote set-head (-a | --auto | -d | --delete | ) + or: git remote [-v | --verbose] show [-n] + or: git remote prune [-n | --dry-run] + or: git remote [-v | --verbose] update [-p | --prune] [( | )...] + or: git remote set-branches [--add] ... + or: git remote get-url [--push] [--all] + or: git remote set-url [--push] [] + or: git remote set-url --add + or: git remote set-url --delete + + -v, --verbose be verbose; must be placed before a subcommand + +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git remote remove Michi-Tsubaki +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git remote add Michi-Tsubaki git@github.com:Michi-Tsubaki/jsk_demos.git +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git push Michi-Tsubaki jsk_2024_10_semi +Enumerating objects: 10, done. +Counting objects: 100% (10/10), done. +Delta compression using up to 8 threads +Compressing objects: 100% (8/8), done. +Writing objects: 100% (8/8), 190.28 MiB | 3.34 MiB/s, done. +Total 8 (delta 2), reused 0 (delta 0) +remote: Resolving deltas: 100% (2/2), completed with 1 local object. +remote: error: Trace: 9a75dffa0e412693f5af2d6fce134396be0f6820799246e55dcd8d745f26056c +remote: error: See https://gh.io/lfs for more information. +remote: error: File jsk_2024_10_semi/hampen.mov is 190.51 MB; this exceeds GitHub's file size limit of 100.00 MB +remote: error: GH001: Large files detected. You may want to try Git Large File Storage - https://git-lfs.github.com. +To github.com:Michi-Tsubaki/jsk_demos.git + ! [remote rejected] jsk_2024_10_semi -> jsk_2024_10_semi (pre-receive hook declined) +error: failed to push some refs to 'git@github.com:Michi-Tsubaki/jsk_demos.git' +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ ls +CMakeLists.txt demo.l first_motion.l~ homework241016.l package.xml +README.md first_motion.l hampen.mov homework_uml.act +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ cp hampen.mov .. +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git rm hampen.mov +rm 'jsk_2024_10_semi/hampen.mov' +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git commit --amend +[jsk_2024_10_semi d0dedc45] add 1023 + Date: Wed Oct 23 15:56:46 2024 +0900 + 4 files changed, 481 insertions(+) + create mode 100644 jsk_2024_10_semi/demo.l + create mode 100644 jsk_2024_10_semi/first_motion.l + create mode 100644 jsk_2024_10_semi/homework241016.l + create mode 100644 jsk_2024_10_semi/homework_uml.act +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ git push Michi-Tsubaki jsk_2024_10_semi +Enumerating objects: 9, done. +Counting objects: 100% (9/9), done. +Delta compression using up to 8 threads +Compressing objects: 100% (7/7), done. +Writing objects: 100% (7/7), 2.23 KiB | 2.23 MiB/s, done. +Total 7 (delta 2), reused 0 (delta 0) +remote: Resolving deltas: 100% (2/2), completed with 1 local object. +To github.com:Michi-Tsubaki/jsk_demos.git + a6024b89..d0dedc45 jsk_2024_10_semi -> jsk_2024_10_semi +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ ls +CMakeLists.txt demo.l first_motion.l~ homework_uml.act +README.md first_motion.l homework241016.l package.xml +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ emacs homework.act +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ emacs homework_uml.act +^Z +[1]+ Stopped emacs homework_uml.act +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ emacs memo1023.txt +mech-user@ki00119:~/semi_ws/src/jsk_2024_10_semi$ fg +emacs homework_uml.act diff --git a/jsk_2024_10_semi/first_task/uml1.png b/jsk_2024_10_semi/first_task/uml1.png new file mode 100644 index 000000000..b03c62adf Binary files /dev/null and b/jsk_2024_10_semi/first_task/uml1.png differ diff --git a/jsk_2024_10_semi/homework241016.l b/jsk_2024_10_semi/homework241016.l new file mode 100644 index 000000000..178181037 --- /dev/null +++ b/jsk_2024_10_semi/homework241016.l @@ -0,0 +1,186 @@ +;;Okada-sensei seminar practice task ;;last editted oct 17 ;; Michitoshi TSUBAKI +;;building specific motions using euslisp command + +(require "package://pr2eus/pr2.l") ;;import pr2 package +(if (not (boundp '*pr2*)) (setq *pr2* (pr2))) ;; (pr2) is alternated by *pr2* +;;boudp 'xx : xxという変数に値が代入されているか +;;setq xx yy : xxとう変数にyyという値を代入する + +(send *pr2* :reset-pose) ;; 初期姿勢 + +(objects (list *pr2*)) + +;;徐々に腕(肩)を広げる(Oct 17) +(send *pr2* :larm :shoulder-p :joint-angle 74) +(send *pr2* :larm :shoulder-p :joint-angle 74) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + +(send *pr2* :larm :shoulder-p :joint-angle 54) +(send *pr2* :rarm :shoulder-p :joint-angle 54) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + +(send *pr2* :larm :shoulder-p :joint-angle 34) +(send *pr2* :rarm :shoulder-p :joint-angle 34) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + +(send *pr2* :larm :shoulder-p :joint-angle 20) +(send *pr2* :rarm :shoulder-p :joint-angle 20) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle 0) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + +;;徐々に型を下げる(Oct 22) +(send *pr2* :rarm :shoulder-r :joint-angle -80) +(send *pr2* :larm :shoulder-r :joint-angle 80) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + +(send *pr2* :rarm :shoulder-r :joint-angle -95) +(send *pr2* :larm :shoulder-r :joint-angle 95) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + +(send *pr2* :rarm :shoulder-r :joint-angle -110) +(send *pr2* :larm :shoulder-r :joint-angle 100) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + + +(send *pr2* :rarm :shoulder-r :joint-angle -130) +(send *pr2* :larm :shoulder-r :joint-angle 120) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + + + +(send *pr2* :larm :elbow-p :joint-angle -110) +(send *pr2* :rarm :elbow-p :joint-angle -100) +(send *pr2* :rarm :shoulder-r :joint-angle -130) +(send *pr2* :larm :shoulder-r :joint-angle 120) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *pr2* :rarm :shoulder-r :joint-angle -130) +(send *pr2* :larm :shoulder-r :joint-angle 120) +(send *pr2* :larm :elbow-p :joint-angle -100) +(send *pr2* :rarm :elbow-p :joint-angle -70) +(send *pr2* :rarm :elbow-r :joint-angle 0) +(send *pr2* :rarm :wrist-p :joint-angle -40) +(send *pr2* :larm :wrist-r :joint-angle 30) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + + + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *pr2* :rarm :shoulder-r :joint-angle -100) +(send *pr2* :larm :shoulder-r :joint-angle 100) +(send *pr2* :larm :elbow-p :joint-angle -100) +(send *pr2* :rarm :elbow-p :joint-angle -70) +(send *pr2* :rarm :elbow-r :joint-angle 0) +(send *pr2* :rarm :wrist-p :joint-angle -40) +(send *pr2* :larm :wrist-r :joint-angle 30) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *pr2* :rarm :shoulder-r :joint-angle -80) +(send *pr2* :larm :shoulder-r :joint-angle 80) +(send *pr2* :larm :elbow-p :joint-angle -110) +(send *pr2* :rarm :elbow-p :joint-angle -100) +(send *pr2* :rarm :elbow-r :joint-angle 0) +(send *pr2* :rarm :wrist-p :joint-angle -40) +(send *pr2* :larm :wrist-r :joint-angle 30) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *pr2* :rarm :shoulder-r :joint-angle -100) +(send *pr2* :larm :shoulder-r :joint-angle 100) +(send *pr2* :larm :elbow-p :joint-angle -120) +(send *pr2* :rarm :elbow-p :joint-angle -120) +(send *pr2* :rarm :elbow-r :joint-angle 0) +(send *pr2* :rarm :wrist-p :joint-angle -40) +(send *pr2* :larm :wrist-r :joint-angle 30) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + +;;fixing now last edited Oct 22 by Michitoshi TSUBAKI + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *pr2* :rarm :shoulder-r :joint-angle -100) +(send *pr2* :larm :shoulder-r :joint-angle 100) +(send *pr2* :larm :elbow-p :joint-angle -120) +(send *pr2* :rarm :elbow-p :joint-angle -120) +(send *pr2* :rarm :elbow-r :joint-angle 0) +(send *pr2* :rarm :wrist-p :joint-angle -40) +(send *pr2* :larm :wrist-r :joint-angle 0) +(send *pr2* :rarm :wrist-r :joint-angle 0) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *pr2* :rarm :shoulder-r :joint-angle -120) +(send *pr2* :larm :shoulder-r :joint-angle 120) +(send *pr2* :larm :elbow-p :joint-angle -120) +(send *pr2* :rarm :elbow-p :joint-angle -120) +(send *pr2* :rarm :elbow-r :joint-angle 0) +(send *pr2* :rarm :wrist-p :joint-angle -40) +(send *pr2* :larm :wrist-r :joint-angle 90) +(send *pr2* :rarm :wrist-r :joint-angle 90) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :torso :waist-z :joint-angle 200) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *pr2* :rarm :shoulder-r :joint-angle -120) +(send *pr2* :larm :shoulder-r :joint-angle 120) +(send *pr2* :larm :elbow-p :joint-angle -120) +(send *pr2* :rarm :elbow-p :joint-angle -120) +(send *pr2* :rarm :elbow-r :joint-angle 0) +(send *pr2* :rarm :wrist-p :joint-angle -40) +(send *pr2* :larm :wrist-r :joint-angle 0) +(send *pr2* :rarm :wrist-r :joint-angle 0) +(send *pr2* :larm :shoulder-p :joint-angle 10) +(send *pr2* :torso :waist-z :joint-angle 300) +(send *irtviewer* :draw-objects) +(unix:sleep 1) + + diff --git a/jsk_2024_10_semi/homework241023.l b/jsk_2024_10_semi/homework241023.l new file mode 100755 index 000000000..488940f25 --- /dev/null +++ b/jsk_2024_10_semi/homework241023.l @@ -0,0 +1,202 @@ +#!/usr/bin/env roseus + +;chmod u+x ./surgery_motion_1.l --> ./surgery_motion_1.l ;; change from ki00119 Michi-Tsubaki + +;;Okada-seisei seminar homework achievement ;;last editted oct 29 ;; Michi-Tsubaki + +;; +;;Thiscode is for trying to make unique motion for sewing something. Still Trying + + +;;Load packages for using PR2 model and PR2 robot in real. +(require "package://pr2eus/pr2.l") +(require "package://pr2eus/pr2-utils.l") +(require "package://pr2eus/pr2-interface.l") + + +;;Making PR2 object +(if (not (boundp '*pr2*)) (pr2-init)) + + +;;Setting cube as a desk for surgery. +(setq *desk* (make-cube 500 500 600)) +(send *desk* :translate (float-vector 700 0 350)) ;; 質問:世界座標の原点がわからないので,机を床に設置(接地)できない. +(send *desk* :set-color :brown) +;[memo] (send *desk* :translate (float-vector 500 0 80)) ;;CAUTION!!(by Michi-Tsubaki)<-parameter that make robot motion NOT converge + + +;;Setting cylinder as needle. +(setq *needle* (make-cylinder 2 40)) +(send *needle* :translate (float-vector 700 0 700)) +(send *needle* :set-color :yellow) +(send *needle* :rotate #d90 :x) + + +;;Setting hampen +(setq *hampen* (make-cube 60 60 20)) +(send *hampen* :translate (float-vector 700 0 660)) ; 質問:座標じゃなくてdeskの上面に設置させたい +(send *hampen* :set-color :white) + +;;Setting coordination. +(send *desk* :put :left-coords + (make-cascoords + :coords (send (send *desk* :copy-worldcoords) :translate (float-vector 0 0 500)) + :parent *desk*)) +;;Setting coordination. +(send *needle* :put :left-coords + (make-cascoords + :coords (send (send *needle* :copy-worldcoords) :translate (float-vector 0 0 -5)) + :parent *needle*)) ;;質問:parent座標をpr2に設定したら収束しなくなった + +(send *pr2* :larm :inverse-kinematics + (send (send *needle* :get :left-coords) :copy-worldcoords) + :rotation-axis :z) + +;;Show all objects in viewer. +(objects (list *pr2* *desk* *needle* *hampen*)) ;;Dont forget to add all items + + +;Setting Initial Pose +(send *pr2* :reset-pose) +(send *ri* :stop-grasp :arms) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + + +;Putting arms above each side of the desk +;;Setting the right arm and the left arm to the initial position. +;;USING INVERSE KINEMATICS +(send *pr2* :larm :inverse-kinematics + (send (send *desk* :get :left-coords) :copy-worldcoords) + :rotation-axis :z) +;(send *pr2* :rarm :inverse-kinematics +; (send (send *desk* :get :left-coords) :copy-worldcoords) +; :rotation-axis :z) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + + +;;Grasping needle +;;1. Reach +(send *pr2* :larm :inverse-kinematics + (send (send *needle* :get :left-coords) :copy-worldcoords) + :rotation-axis :z) +(send *pr2* :larm :end-coords :assoc *needle*) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + +;;2. Graspe +(send *ri* :start-grasp :arms) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + + + +;;Stitching with the left hand +(send *pr2* + :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0.0 -10.0 -10.0)) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :debug-view t) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + + +(send *pr2* :larm :wrist-p :joint-angle -100) +(send *pr2* + :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector 50.0 20.0 0.0)) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :debug-view t) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + + +(send *pr2* + :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0.0 -12.0 20.0)) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :debug-view t) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + + +(send *pr2* :larm :wrist-p :joint-angle -80) +(send *pr2* + :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector -35.0 -10.0 5.0)) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :debug-view t) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + + +(send *pr2* :larm :elbow-r :joint-angle 95) +(send *pr2* :larm :shoulder-r :joint-angle 95) +(send *pr2* + :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0.0 2.0 2.0)) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :debug-view t) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + + +;;Switching hands +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + +(send *pr2* :rarm :inverse-kinematics + (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector -10.0 0 0) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :rarm :end-coords) :parent)) + :rotation-axis :x)) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + + + + + +;;質問:ここでikが上手く行かなくなった。左では上手く行っているのに、右では下からアプローチする。assocの切り替えもわからない。あと,オフセット +;;Grasping needle with right hand +(send *pr2* :rarm :inverse-kinematics + (send (send *needle* :get :left-coords) :copy-worldcoords) + :rotation-axis :z) +(send *pr2* :rarm :end-coords :assoc *needle*) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) diff --git a/jsk_2024_10_semi/object.l b/jsk_2024_10_semi/object.l new file mode 100644 index 000000000..1d9d1a8d8 --- /dev/null +++ b/jsk_2024_10_semi/object.l @@ -0,0 +1,151 @@ +#!/usr/bin/env irteusgl + +(defclass trajectory + :super cascaded-link + :slots (end-coords tp1 tp2 tp3 tp4 tp5 start-coords)) + +(defmethod trajectory + (:init () + (let (b) + (send-super :init) + ;; tp5 + (setq b (make-cube 1 1 1)) + (send b :locate #f(0 0 50)) + (send b :set-color :black) + (setq tp5 (instance bodyset-link :init (make-cascoords) :bodies (list b) :name 'tp5)) + (setq end-coords (make-cascoords :pos #f(0 0 20))) + (send tp5 :assoc end-coords) + (send tp5 :locate #f(0 0 100)) + ;; tp4 + (setq b (make-cube 1 1 1)) + (send b :locate #f(0 0 4)) + (send b :set-color :red) + (setq tp4 (instance bodyset-link :init (make-cascoords) :bodies (list b) :name 'tp4)) + (send tp4 :assoc tp5) + (send tp4 :locate #f(0 0 4)) + ;; tp3 + (setq b (make-cube 1 1 1)) + (send b :locate #f(0 0 3)) + (send b :set-color :blue) + (setq tp3 (instance bodyset-link :init (make-cascoords) :bodies (list b) :name 'tp3)) + (send tp3 :assoc tp4) + (send tp3 :locate #f(0 0 4)) + ;; tp2 + (setq b (make-cube 1 1 1)) + (send b :locate #f(0 0 2)) + (send b :set-color :red) + (setq tp2 (instance bodyset-link :init (make-cascoords) :bodies (list b) :name 'tp2)) + (send tp2 :assoc tp3) + (send tp2 :locate #f(0 0 20)) + ;; tp1 + (setq b (make-cube 1 1 1)) + (send b :locate #f(0 0 1)) + (send b :set-color :white) + (setq tp1 (instance bodyset-link :init (make-cascoords) :bodies (list b) :name 'tp1)) + (send tp1 :assoc tp2) + + (setq links (list tp1 tp2 tp3 tp4 tp5)) + (send self :init-ending) + self)) + + (:end-coords (&rest args) (forward-message-to end-coords args)) + + ;; 等間隔にポイントを配置するメソッド + (:set-equal-intervals (start-coord end-coord) + (let* ((num-points 5) ;; tp1 から tp5 までの5点 + (start-pos (send start-coord :pos)) + (end-pos (send end-coord :pos)) + (delta-x (/ (- (aref end-pos 0) (aref start-pos 0)) (float (1- num-points)))) + (delta-y (/ (- (aref end-pos 1) (aref start-pos 1)) (float (1- num-points)))) + (delta-z (/ (- (aref end-pos 2) (aref start-pos 2)) (float (1- num-points))))) + + ;; 各ポイントを計算して配置 + (setq tp1 (send self :update-point tp1 start-pos delta-x delta-y delta-z 0)) + (setq tp2 (send self :update-point tp2 start-pos delta-x delta-y delta-z 1)) + (setq tp3 (send self :update-point tp3 start-pos delta-x delta-y delta-z 2)) + (setq tp4 (send self :update-point tp4 start-pos delta-x delta-y delta-z 3)) + (setq tp5 (send self :update-point tp5 start-pos delta-x delta-y delta-z 4)) + + ;; 更新されたターゲットポイントをリンクに再設定 + (send tp1 :assoc tp2) + (send tp2 :assoc tp3) + (send tp3 :assoc tp4) + (send tp4 :assoc tp5) + self)) + + ;; 各ターゲットポイントを更新するサブルーチン + (:update-point (point start-pos delta-x delta-y delta-z index) + (let* ((new-pos (list (+ (aref start-pos 0) (* delta-x index)) + (+ (aref start-pos 1) (* delta-y index)) + (+ (aref start-pos 2) (* delta-z index))))) + ;; new-pos をベクターとして変換 + (setq new-pos (vector (aref new-pos 0) (aref new-pos 1) (aref new-pos 2))) ;; ベクターに変換 + (send point :locate new-pos) + point)) + ) + +;; 使用例 +(setq r (instance trajectory :init)) +(setq start-coord (make-cascoords :pos #f(0 0 0))) +(setq end-coord (make-cascoords :pos #f(0 0 100))) +;(send r :set-equal-intervals start-coord end-coord) +(objects (list r (send r :end-coords))) +(send *irtviewer* :draw-objects) + + + + +#| +(defclass trajectory + :super cascaded-link + :slots (end-coords tp1 tp2 tp3 tp4 tp5)) + +(defmethod trajectory + (:init () + (let (b) + (send-super :init) + ;; tp5 + (setq b (make-cube 1 1 1)) + (send b :locate #f(0 0 50)) + (send b :set-color :black) + (setq tp5 (instance bodyset-link :init (make-cascoords) :bodies (list b) :name 'tp5)) + (setq end-coords (make-cascoords :pos #f(0 0 20))) + (send tp5 :assoc end-coords) + (send tp5 :locate #f(0 0 100)) + ;; tp4 + (setq b (make-cube 1 1 1)) + (send b :locate #f(0 0 4)) + (send b :set-color :red) + (setq tp4 (instance bodyset-link :init (make-cascoords) :bodies (list b) :name 'tp4)) + (send tp4 :assoc tp5) + (send tp4 :locate #f(0 0 4)) + ;; tp3 + (setq b (make-cube 1 1 1)) + (send b :locate #f(0 0 3)) + (send b :set-color :blue) + (setq tp3 (instance bodyset-link :init (make-cascoords) :bodies (list b) :name 'tp3)) + (send tp3 :assoc tp4) + (send tp3 :locate #f(0 0 4)) + ;; tp2 + (setq b (make-cube 1 1 1)) + (send b :locate #f(0 0 2)) + (send b :set-color :red) + (setq tp2 (instance bodyset-link :init (make-cascoords) :bodies (list b) :name 'tp2)) + (send tp2 :assoc tp3) + (send tp2 :locate #f(0 0 20)) + ;; tp1 + (setq b (make-cube 1 1 1)) + (send b :locate #f(0 0 1)) + (send b :set-color :white) + (setq tp1 (instance bodyset-link :init (make-cascoords) :bodies (list b) :name 'tp1)) + (send tp1 :assoc tp2) + + (setq links (list tp1 tp2 tp3 tp4 tp5)) + (send self :init-ending) + self)) + (:end-coords (&rest args) (forward-message-to end-coords args)) + ) + +(setq r (instance trajectory :init)) +(objects (list r (send r :end-coords))) +(send *irtviewer* :draw-objects) diff --git a/jsk_2024_10_semi/pingpong-sample/pingpong.l b/jsk_2024_10_semi/pingpong-sample/pingpong.l new file mode 100644 index 000000000..af97c4f02 --- /dev/null +++ b/jsk_2024_10_semi/pingpong-sample/pingpong.l @@ -0,0 +1,55 @@ +#!/usr/bin/env roseus +#| + +35.E8-irteusgl$ (send *ri* :state :potentio-vector) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +#f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702) +36.E8-irteusgl$ (send *ri* :state :potentio-vector) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.99275) violate max-angle(-5.72958) +#f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -36.0762 26.7834 -79.1134 -106.885 386.621 -5.72958 91.7235 3.47953 74.2702) +37.E8-irteusgl$ (send *ri* :state :potentio-vector) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.13983) violate max-angle(-5.72958) +#f(232.409 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.0287 20.0704 -75.42 -95.7531 397.257 -5.72958 91.8606 3.52153 74.2702) + +|# + +(setq r1 #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702)) +(setq r2 #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -36.0762 26.7834 -79.1134 -106.885 386.621 -5.72958 91.7235 3.47953 74.2702)) +(setq r3 #f(232.409 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.0287 20.0704 -75.42 -95.7531 397.257 -5.72958 91.8606 3.52153 74.2702)) + + + +(require "package://pr2eus/pr2.l") +(require "package://pr2eus/pr2-utils.l") +(require "package://pr2eus/pr2-interface.l") ;;*ri* +(require "package://pr2eus/speak.l") ;;pkg for speaking + +(setq r1 #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702)) +(setq r2 #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -36.0762 26.7834 -79.1134 -106.885 386.621 -5.72958 91.7235 3.47953 74.2702)) +(setq r3 #f(232.409 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.0287 20.0704 -75.42 -95.7531 397.257 -5.72958 91.8606 3.52153 74.2702)) + + +(if (not (boundp '*pr2*)) (pr2-init)) + +(objects (list *pr2*)) + +;;(send *ri* :angle-vector r1 1000) +;;(send *ri* :wait-interpolation) +;;(send *irtviewer* :draw-objects) + +;;(send *ri* :angle-vector r2 50) +;;(send *ri* :wait-interpolation) +;;(send *irtviewer* :draw-objects) + +;;(send *ri* :angle-vector r3 5 +(setq tm 300) +(send *ri* :angle-vector-sequence (list r1 r2 r3 r1) (list tm tm tm 1000) + :default-controller 0.001 + :min-time 0.0001 + :minjerk-interpolation t + ) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) diff --git a/jsk_2024_10_semi/pr2_surgery/.catkin_workspace b/jsk_2024_10_semi/pr2_surgery/.catkin_workspace new file mode 100644 index 000000000..52fd97e7e --- /dev/null +++ b/jsk_2024_10_semi/pr2_surgery/.catkin_workspace @@ -0,0 +1 @@ +# This file currently only serves to mark the location of a catkin workspace for tool integration diff --git a/jsk_2024_10_semi/pr2_surgery/CMakeLists.txt b/jsk_2024_10_semi/pr2_surgery/CMakeLists.txt new file mode 100644 index 000000000..fd690c7b8 --- /dev/null +++ b/jsk_2024_10_semi/pr2_surgery/CMakeLists.txt @@ -0,0 +1,208 @@ +cmake_minimum_required(VERSION 3.0.2) +project(pr2_surgery) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + jsk_recognition_msgs + roscpp + roseus + rospy + std_msgs +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# jsk_recognition_msgs# std_msgs +# ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES pr2_surgery +# CATKIN_DEPENDS jsk_recognition_msgs roscpp roseus rospy std_msgs +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +# include + ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +# add_library(${PROJECT_NAME} +# src/${PROJECT_NAME}/pr2_surgery.cpp +# ) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/pr2_surgery_node.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +# target_link_libraries(${PROJECT_NAME}_node +# ${catkin_LIBRARIES} +# ) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# catkin_install_python(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# install(TARGETS ${PROJECT_NAME}_node +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +# install(TARGETS ${PROJECT_NAME} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_pr2_surgery.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/jsk_2024_10_semi/pr2_surgery/config/table_marker.yaml b/jsk_2024_10_semi/pr2_surgery/config/table_marker.yaml new file mode 100644 index 000000000..0db13fdb8 --- /dev/null +++ b/jsk_2024_10_semi/pr2_surgery/config/table_marker.yaml @@ -0,0 +1,16 @@ +boxes: +- dimensions: + - 0.5 + - 0.3 + - 0.2 + frame_id: base_footprint + name: table + orientation: + - 3.9531047036326084e-10 + - 0.008311730048626616 + - 4.293287988035861e-12 + - 0.9999654569751891 + position: + - 0.7592881917953491 + - 0.015209555625915527 + - 0.849845826625824 diff --git a/jsk_2024_10_semi/pr2_surgery/launch/recognize_wound.launch b/jsk_2024_10_semi/pr2_surgery/launch/recognize_wound.launch new file mode 100755 index 000000000..a8459f8e7 --- /dev/null +++ b/jsk_2024_10_semi/pr2_surgery/launch/recognize_wound.launch @@ -0,0 +1,157 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + queue_size: 100 + + + + + + display_interactive_manipulator: true + display_interactive_manipulator_only_selected: true + display_description_only_selected: true + + + + + + + config_file: $(find pr2_surgery)/config/table_marker.yaml + config_auto_save: true + + + + + + + index: 0 + + + + + + + + + use_multiple_attention: false + + + + + + + keep_organized: true + approximate_sync: true + max_queue_size: 100 + + + + + + + use_indices: false + keep_organized: true + h_limit_max: 10 + h_limit_min: -10 + s_limit_max: 255 + s_limit_min: 35 + i_limit_max: 255 + i_limit_min: 0 + + + + + + + tolerance: 0.02 + min_size: 10 + downsample_enable: true + cluster_filter: 1 + + + + + + + + align_boxes: true + align_boxes_with_plane: false + force_to_flip_z_axis: false + use_pca: false + target_frame_id: base_footprint + + + + + diff --git a/jsk_2024_10_semi/pr2_surgery/package.xml b/jsk_2024_10_semi/pr2_surgery/package.xml new file mode 100644 index 000000000..c7b57c504 --- /dev/null +++ b/jsk_2024_10_semi/pr2_surgery/package.xml @@ -0,0 +1,74 @@ + + + pr2_surgery + 0.0.0 + The pr2_surgery package + + + + + mech-user + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + jsk_recognition_msgs + roscpp + roseus + rospy + std_msgs + jsk_recognition_msgs + roscpp + roseus + rospy + std_msgs + jsk_recognition_msgs + roscpp + roseus + rospy + std_msgs + + + + + + + + diff --git a/jsk_2024_10_semi/pr2_surgery/src/CMakeLists.txt b/jsk_2024_10_semi/pr2_surgery/src/CMakeLists.txt new file mode 120000 index 000000000..201681686 --- /dev/null +++ b/jsk_2024_10_semi/pr2_surgery/src/CMakeLists.txt @@ -0,0 +1 @@ +/opt/ros/noetic/share/catkin/cmake/toplevel.cmake \ No newline at end of file diff --git a/jsk_2024_10_semi/pr2_surgery/src/hoge.l b/jsk_2024_10_semi/pr2_surgery/src/hoge.l new file mode 100644 index 000000000..f918951cf --- /dev/null +++ b/jsk_2024_10_semi/pr2_surgery/src/hoge.l @@ -0,0 +1,23 @@ +(setq a nil) +(push 0 a) +(push 1 a) +(push 2 a) +(setq a (reverse a)) +(print a) +(dolist (b a) + (print b)) + +(print "--") +(setq a nil) +(setq a (append a (list 0))) +(setq a (append a (list 1))) +(setq a (append a (list 2))) +(print a) +(dolist (b a) + (print b)) ;; + + + + + + diff --git a/jsk_2024_10_semi/pr2_surgery/src/pr2_surgery.l b/jsk_2024_10_semi/pr2_surgery/src/pr2_surgery.l new file mode 100755 index 000000000..4fa7cf548 --- /dev/null +++ b/jsk_2024_10_semi/pr2_surgery/src/pr2_surgery.l @@ -0,0 +1,484 @@ +#!/usr/bin/env roseus + +#| DESCRIPTION +Okada-sensei seminar +Surgery-method dev3 +Last editted Dec 19 by Michi-Tsubaki +GOAL: Trying to make unique motion for stitching sponge! + +## Functions +- voice recognition (trriger) +- perception (recognize wound) +- sew sponge + +## For Future +- Dual Pandaでやってみたい. +- チート実験台ではなく,平らな傷口に上面からアプローチしたい +- そのために,class trajを継承して曲がった経路を生成する +|# + +;;Load pkgs around PR2 Interface +(require "package://pr2eus/pr2.l") +(require "package://pr2eus/pr2-utils.l") +(require "package://pr2eus/pr2-interface.l") ;;*ri* +(require "package://pr2eus/speak.l") ;;pkg for speaking +;;ros msgs +(ros::load-ros-package "jsk_recognition_msgs") +(ros::roseus-add-msgs "speech_recognition_msgs") +(ros::roseus-add-msgs "geometry_msgs") + + +;;ここをかえるだけで調整できる!(外界の変化に合わせて) +;; Drawing Pram +(setq *draw-param-left* 0.2) +(setq *draw-param-right* 0.6) +;; Env Param +(setq *centerx* 700) +(setq *centery* 0) +(setq *centerz* 755) +(setq *deskw* 500) +;; Hampen Param +(setq *target-ypos* 0) +(setq *target-xpos* 0) +(setq *target-zpos* 30) +;; Traj Param +(setq *needle_len* 70) +(setq *interval* 10) +(setq *traj_num* 10) +(setq *traj_len* (* *interval* *traj_num*)) +;; Set remain +(setq *remain* 450) ;;450 ;;how long remaining thread? +(setq *diff_remain* 55) ;;55 +;; Offset +(setq *rarm_offset* 2) + + +;; Frag (DO NOT CHANGE) +(setq *start-flag* 0) +(setq *is_first* 1) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; Environment ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; Define set-environment method +(defun set-env() + ;;Set center + (setq *deskh* *centerz*) + + (setq *center* (make-cube 10 10 10)) + (send *center* :translate (float-vector *centerx* *centery* *centerz*)) + (send *center* :set-color :black) + (setq *o* (send *center* :copy-worldcoords)) + + ;;Set desk + (setq *desk* (make-cube *deskw* *deskw* *deskh*)) + (send *desk* :translate (float-vector *centerx* *centery* (/ *centerz* 2))) + (send *desk* :set-color :brown) + + ;;Set needle + (setq *needle* (make-cylinder 0.5 *needle_len*)) + (send *needle* :translate (v+ (float-vector -100 20 300) (send *center* :pos))) + (send *needle* :set-color :yellow) + (send *needle* :rotate #d90 :y) + + ;;Set hampen + (setq *hampen* (make-cube 50 50 50)) + (send *hampen* :translate (v+ (float-vector 0 0 10) (send *center* :pos))) + (send *hampen* :set-color :white) + (send *hampen* :rotate #d45 :x) + + (send *desk* :put :left-coords + (make-cascoords + :coords (send (send *desk* :copy-worldcoords) :translate (float-vector 0 0 500)) + :parent *pr2*)) + (send *needle* :put :left-coords + (make-cascoords + :coords (send (send *needle* :copy-worldcoords) :translate (float-vector 0 0 -5)) + :parent *needle*)) +) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; Sensing ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; Voice Detection +(defun speech-cb(msg) + (setq *ans* (elt (send msg :transcript) 0)) + (print *ans*) + (if (equal *ans* "どうぞ") + (setq *start-flag* 1) + ;; 1回フラグが立てばそれでいい + )) + +(defun detect-voice () + (ros::ros-info "start waiting for call ~%") + (ros::subscribe "speech_to_text" speech_recognition_msgs::SpeechRecognitionCandidates #'speech-cb) + (ros::rate 10) + (while (not (eq *start-flag* 1)) + (ros::spin-once) + (ros::sleep) + (ros::ros-info "wait for voice command ...") + ) + ) + +;; Perception +(defun cb-recog(msg) + (ros::ros-info "boxes ~A" (length (send msg :boxes))) + (if (and (> (length (send msg :boxes)) 0) (> (send (send (elt (send msg :boxes) 0) :dimensions) :x) 0)) + (setq *target-ypos-tmp* (send (send (send (elt (send msg :boxes) 0) :pose) :position) :y)) + ) + ) + +(defun detect-wound() + (ros::subscribe "/recognize_wound/cluster_decomposer/boxes" jsk_recognition_msgs::BoundingBoxArray #'cb-recog) + (ros::rate 10) + (while (null *target-ypos-tmp*) + (ros::ros-info "wait for target...") + (ros::sleep) + (ros::spin-once)) + (setq *target-ypos* *target-ypos-tmp*) + ) + +(defun cb-rforce(msg) + (ros::ros-info "checking right-virtual-force") + (setq *rforce* (send (send (send msg :wrench) :force) :z)) + (format t "rforce: ~A ~%" *rforce*) + (if (> (send (send (send msg :wrench) :force) :z) *draw-param-right*) + (progn + (setq *right-drawing* t) + (format t "drawing~%") + ) + ) + ) + +(defun cb-lforce(msg) + (ros::ros-info "checking left-virtual-force") + (setq *lforce* (send (send (send msg :wrench) :force) :z)) + (if (> (send (send (send msg :wrench) :force) :z) *draw-param-left*) + (progn + (setq *left-drawing* t) + (format t "drawing~%") + ) + ) + ) +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; Stitching ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; Path ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;; Define Trajectory Class +(defclass traj + :super cascaded-coords + :slots (points)) + +(defmethod traj + (:init (&rest args) + (send-super* :init args) + (dotimes (i *traj_num*) + (push + (make-cube 10 10 10 :pos (float-vector (* (- i 5) *interval*) 0 0)) + points)) + (dotimes (i (- (length points) 1)) + (send (elt points i) :assoc (elt points (+ 1 i)))) + (send self :assoc (car points)) + self) + (:points () points) + ) + + +;; Define set-environment method +(defun set-env() + ;;Set center + (setq *deskh* *centerz*) + + (setq *center* (make-cube 10 10 10)) + (send *center* :translate (float-vector *centerx* *centery* *centerz*)) + (send *center* :set-color :black) + (setq *o* (send *center* :copy-worldcoords)) + + ;;Set desk + (setq *desk* (make-cube *deskw* *deskw* *deskh*)) + (send *desk* :translate (float-vector *centerx* *centery* (/ *centerz* 2))) + (send *desk* :set-color :brown) + + ;;Set needle + (setq *needle* (make-cylinder 0.5 *needle_len*)) + (send *needle* :translate (v+ (float-vector -100 20 300) (send *center* :pos))) + (send *needle* :set-color :yellow) + (send *needle* :rotate #d90 :y) + + ;;Set hampen + (setq *hampen* (make-cube 50 50 50)) + (send *hampen* :translate (v+ (float-vector 0 0 10) (send *center* :pos))) + (send *hampen* :set-color :white) + (send *hampen* :rotate #d45 :x) + + (send *desk* :put :left-coords + (make-cascoords + :coords (send (send *desk* :copy-worldcoords) :translate (float-vector 0 0 500)) + :parent *pr2*)) + (send *needle* :put :left-coords + (make-cascoords + :coords (send (send *needle* :copy-worldcoords) :translate (float-vector 0 0 -5)) + :parent *needle*)) +) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; Motion ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;;Define preparation task. +(defun preparation() + (send *ri* :speak-jp "縫合を始めます.注意してください." :wait t) + (send *pr2* :reset-pose) ;;Set Initial Pose + (send *pr2* :torso :waist-z :joint-angle 240) + (send *ri* :start-grasp :arms) + (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + + (send *pr2* :head :look-at (send *center* :worldpos)) + + (send *pr2* :larm :inverse-kinematics + (send (send (send *needle* :get :left-coords) + :copy-worldcoords) + :rotate (deg2rad 90) :z) + :rotation-axis :z) ;;IK to needle pose + (send *pr2* :larm :end-coords :assoc *needle*) ;; + (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + + ;;Grasp needle (real) + (send *ri* :speak-jp "左手に,針を持たせてください." :wait t) + (send *ri* :stop-grasp :larm :wait t) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + ) + + +;;Define initial task. +(defun init-task() + (send *ri* :speak-jp "手を閉じます.挟まれないように気をつけてください" :wait t) + (send *ri* :start-grasp :larm :wait t) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + (send *ri* :speak-jp "これから針を持って作業します.離れてください." :wait t) + (unix:sleep 2) + + ;;Grasp needle (dummy) + (send *pr2* :larm :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) :rotate (deg2rad 90) :z) :rotation-axis :z) + (send *pr2* :larm :end-coords :assoc *needle*) ;;針を固定 + (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) +) + + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; others ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +(defun stop() + (send *ri* :stop-grasp) + ) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;;;;main.l;;;;; +;;Set PR2 +(if (not (boundp '*pr2*)) (pr2-init)) + +;; Set the experimental environments. +(set-env) + +;; Show all objects in irtviewer. +(objects (list *pr2* *center* *desk* *needle* *hampen*)) + +;; Human help Robot to grab needle. +(preparation) + +;; The Nurse pass the needle saying "douzo!" +(if (send *ri* :simulation-modep) + (unix:sleep 2) + (detect-voice) + ) + +;; Do initial task. +(init-task) + +;; Dummy pos to be able to calculate IK +(setq current-coords (send (send *desk* :get :left-coords) :copy-worldcoords)) +(setq new-coords (send current-coords :translate (float-vector 0 100 50))) +(send *pr2* :larm :inverse-kinematics new-coords :rotation-axis :x) +(send *pr2* :larm :end-coords :assoc *needle*) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + +;; Perception +;; Perception (dummy) +(ros::subscribe "/recognize_wound/cluster_decomposer/boxes" jsk_recognition_msgs::BoundingBoxArray #'cb-recog) +(if (send *ri* :simulation-modep) + (setq *target-ypos-tmp* 0) + (setq *target-ypos-tmp* nil) + ) +(detect-wound) + +;; Stitch +(dotimes (i 4) ;;5は難しい。。。 + ;; Make trajectory points. + (setq r (instance traj :init)) + (send r :rotate pi/2 :z) + (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (+ *target-ypos* (* *traj_len* 0.12)) *target-zpos*))) ;; 0.2は実験則 ;; Trajectoryの中心座標をHampenにあわせている + (send r :locate *target* :world) + (objects (append (list *pr2* *center* *desk* *needle* *hampen*) (send r :points))) + + ;; Set start position. + ;; Rarm + (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) + (send *r-pos* :rotate pi/2 :y :local) + (send *r-pos* :rotate -pi/2 :z :local) ;; if -pi/2, rarm state is parallel to desk + (send *r-pos* :translate #f(-10 0 0) :local) + (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) + (send *ri* :angle-vector (send *pr2* :angle-vector) 500) + (send *ri* :stop-grasp :rarm) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + ;; Follow the trajectory points. Stitch. + (setq tm 500) + (setq path (list)) + (setq time-vec (list 4000)) + (dolist (e (send r :points)) + (let (ee) + (setq ee (send e :copy-worldcoords)) + (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) + (send ee :rotate pi :z :local) + (send ee :rotate pi/2 :y :local) + (send ee :draw-on :flush t :size 100) + (push (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) path) + (push tm time-vec) + ) + ) + (pop time-vec) + (nreverse time-vec) + (nreverse path) + (send *ri* :angle-vector-sequence path time-vec + :default-controller 0.001 + :min-time 0.0001 + :minjerk-interpolation t + ) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + + ;; Pass on the needle. (左手から右手に針を戻す) + (send *ri* :start-grasp :rarm :wait t) + (send *ri* :wait-interpolation) + (unix:sleep 1) + (send *ri* :stop-grasp :larm :wait t) + (send *ri* :wait-interpolation) + + ;; Fix the right arm and neadle (針の固定を左から右に移す) + (send *pr2* :larm :end-coords :dissoc *needle*) + (send *pr2* :rarm :end-coords :assoc *needle*) + (format t "is_first: ~A ~%" *is_first*) + ;; Draw the needle from the object. (対象物から針を抜き出) + (if (= *is_first* 1) + (progn (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) + (send *ri* :angle-vector-sequence (list (send *pr2* :angle-vector)) (list 10000) + :default-controller 0.001 + :min-time 0.0001 + :minjerk-interpolation t + ) (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + (setq *remain* (- *remain* *diff_remain*)) + ) + (progn + (setq remain_tmp (- *remain* *diff_remain*)) + (send *pr2* :rarm :move-end-pos (float-vector 0 0 -60) :local) + (send *irtviewer* :draw-objects) + (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + ;;(setq *remain* (- *remain* 60));; オリジナリティポイント: 1回縫うと針を引ける量が減るのを再現 + (format t "remaining ~A ~%" *remain*) ;; for debug! (*remain*が0になったらbreakするようにしたい) + (if (> *remain* remain_tmp) + (progn + (setq *right-drawing* nil) + (setq *position1* (send *ri* :state :angle-vector)) + (ros::subscribe "/right_endeffector/wrench" geometry_msgs::WrenchStamped #'cb-rforce 1) + (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- remain_tmp)) :local) + (setq *position2* (send *pr2* :angle-vector)) + ;;(send *ri* :angle-vector (print (send *pr2* :angle-vector)) 10000) ;;bug + (send *ri* :angle-vector-sequence (list (send *pr2* :angle-vector)) (list 10000) + :default-controller 0.001 + :min-time 0.0001 + :minjerk-interpolation t + ) + (send *irtviewer* :draw-objects) + (ros::duration-sleep 2.0) + (while (null *right-drawing*) + (ros::duration-sleep 0.05) + (ros::spin-once) + (if (not (send *ri* :interpolatingp)) + (setq *right-drawing* t)) + ) + (send *ri* :cancel-angle-vector :wait t) + ;;(send *ri* :stop-motion) + (send *pr2* :angle-vector (send *ri* :state :potentio-vector)) + ) + ) + ) + ) + + + ;; Move left hand to the delivery point. + (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) + :translate (float-vector 45 (* *needle_len* 0.5) 150)) + :rotate pi/2 :z) + :rotate pi/2 :y) + :rotate pi :x)) + (send *pass-larm* :draw-on :flush t :size 100) ;; for debug! + (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) ;; Use torso! (腰を使わないとIKが解けないので注意) + (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + + ;; Move right hand to the delivery point. + (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) + :translate (float-vector 45 (- 0 (* *needle_len* 0.5)) 150)) + :translate #f(-10 0 0)) + :rotate -pi/2 :x)) + (send *pass-rarm* :draw-on :flush t :size 100) ;; for debug! + (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) ;; Do not use torso! (左手との相対座標が狂う) + (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + + ;; Pass on the needle. (右手から左手に針を戻す) + (send *ri* :start-grasp :larm) + (send *ri* :wait-interpolation) + (unix:sleep 1) + (send *ri* :stop-grasp :rarm) + (send *ri* :wait-interpolation) + + ;; Fix the left arm and needle again (針の固定を右から左に移す) + (send *pr2* :rarm :end-coords :dissoc *needle*) + (send *pr2* :larm :end-coords :assoc *needle*) + (send *ri* :speak-jp "繰り返し,つぎの経路で縫います.注意してください." :wait t) + (unix:sleep 1) + (send *pr2* :rarm :move-end-pos (float-vector 0 0 -50) :local) + (send *ri* :wait-interpolation) + (ros::rate 10) + (setq *left-drawing* nil) + ;;余っている糸を左に引く作業を知的化した + (ros::subscribe "/left_endeffector/wrench" geometry_msgs::WrenchStamped #'cb-lforce 1) + (send *pr2* :larm :move-end-pos (float-vector 0 0 -240) :local) + ;;(send *ri* :angle-vector (send *pr2* :angle-vector) 15000) + (send *ri* :angle-vector-sequence (list (send *pr2* :angle-vector)) (list 15000) + :default-controller 0.001 + :min-time 0.0001 + :end-coords-interpolation t + ) + (while (null *left-drawing*) + (ros::duration-sleep 0.02) + (ros::spin-once) + (if (not (send *ri* :interpolatingp)) + (setq *left-drawing* t)) + ) + (send *ri* :cancel-angle-vector :wait t) + (setq *is_first* 0) + ) + +(send *pr2* :reset-pose) ;;Set Initial Pose +(send *ri* :stop-grasp :arms) +(send *ri* :angle-vector (send *pr2* :angle-vector) 10000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + +(send *ri* :speak-jp "縫合がおわりました.お疲れ様でした." :wait t) diff --git a/jsk_2024_10_semi/pr2_surgery_dev1/surgery_method_2.l b/jsk_2024_10_semi/pr2_surgery_dev1/surgery_method_2.l new file mode 100755 index 000000000..0e54a4d6d --- /dev/null +++ b/jsk_2024_10_semi/pr2_surgery_dev1/surgery_method_2.l @@ -0,0 +1,357 @@ +#!/usr/bin/env roseus + +;;Okada-seisei seminar +;;Surgery-method dev1 +;;last editted Nov 12 ;; Michi-Tsubaki + +;; +;;This program is for trying to make unique motion for sewing sponge. Still Trying + +;;Load pkgs for using PR2 model and PR2 robot in real. +(require "package://pr2eus/pr2.l") +(require "package://pr2eus/pr2-utils.l") +(require "package://pr2eus/pr2-interface.l") +(require "package://pr2eus/speak.l") ;;pkg for speaking +(load "models/arrow-object.l") + +;;Define Trajectory Point (7) +(defvar *tp1* nil) +(defvar *tp2* nil) +(defvar *tp3* nil) +(defvar *tp4* nil) +(defvar *tp5* nil) +(defvar *tp6* nil) +(defvar *tp7* nil) + +;;Set PR2 +(if (not (boundp '*pr2*)) (pr2-init)) + +;;Set Center of a Table +(setq *center* (make-cube 10 10 10)) +(send *center* :translate (float-vector 700 0 750)) +(send *center* :set-color :black) + +;;Set cube as a desk for surgery. +(setq *desk* (make-cube 500 500 750)) +(send *desk* :translate (float-vector 700 0 750/2)) +(send *desk* :set-color :brown) + +;;Set cylinder as needle. +(setq *needle* (make-cylinder 0.5 70)) +(send *needle* :translate (v+ (float-vector 0 20 100) (send *center* :pos))) +(send *needle* :set-color :yellow) +(send *needle* :rotate #d270 :x) + +;;Set hampen +(setq *hampen* (make-cube 50 50 50)) +(send *hampen* :translate (v+ (float-vector 0 0 10) (send *center* :pos))) +(send *hampen* :set-color :white) +(send *hampen* :rotate #d45 :x) + + + +;;Define set-trajectory function +(defun set-trajectory (x) + (let ((prev-pos *center*)) ; 最初の座標を原点に設定 + ;; tp1 + (setq *tp1* (make-cube 2 2 2)) + (send *tp1* :translate (v+ (float-vector (- x 15) 30 40) (send *center* :pos))) + (send *tp1* :rotate #d0 :z) + (send *tp1* :set-color :red) + (send *tp1* :put :left-coords + (make-cascoords + :coords (send (send *tp1* :copy-worldcoords) + :translate (float-vector 1 0 0)) + :rot #2f((0 0 1) + (-1 0 0) + (0 -1 0)) + :parent *tp1*)) + (setq prev-pos (send *tp1* :pos)) + ;; tp2 + (setq *tp2* (make-cube 2 2 2)) + (send *tp2* :translate (v+ (float-vector 0 -10 0) prev-pos)) + (send *tp2* :rotate #d90 :z) + (send *tp2* :set-color :red) + (send *tp2* :put :left-coords + (make-cascoords + :coords (send (send *tp2* :copy-worldcoords) + :translate (float-vector 1 0 0)) + :rot #2f((0 0 1) + (-1 0 0) + (0 -1 0)) + :parent *tp1*)) + (setq prev-pos (send *tp2* :pos)) + ;; tp3 + (setq *tp3* (make-cube 2 2 2)) + (send *tp3* :translate (v+ (float-vector 0 -10 0) prev-pos)) + (send *tp3* :rotate #d270 :z) + (send *tp3* :set-color :red) + (send *tp3* :put :left-coords + (make-cascoords + :coords (send (send *tp3* :copy-worldcoords) + :translate (float-vector 1 0 0)) + :rot #2f((0 0 1) + (-1 0 0) + (0 -1 0)) + :parent *tp2*)) + (setq prev-pos (send *tp3* :pos)) + ;; tp4 + (setq *tp4* (make-cube 2 2 2)) + (send *tp4* :translate (v+ (float-vector 0 -10 0) prev-pos)) + (send *tp4* :rotate #d90 :x) + (send *tp4* :set-color :red) + (send *tp4* :put :left-coords + (make-cascoords + :coords (send (send *tp3* :copy-worldcoords) + :translate (float-vector 1 0 0)) + :rot #2f((0 0 1) + (-1 0 0) + (0 -1 0)) + :parent *tp3*)) + (setq prev-pos (send *tp4* :pos)) + ;; tp5 + (setq *tp5* (make-cube 2 2 2)) + (send *tp5* :translate (v+ (float-vector 0 10 0) prev-pos)) + (send *tp5* :rotate #d90 :x) + (send *tp5* :set-color :red) + (send *tp5* :put :left-coords + (make-cascoords + :coords (send (send *tp3* :copy-worldcoords) + :translate (float-vector 1 0 0)) + :rot #2f((0 0 1) + (-1 0 0) + (0 -1 0)) + :parent *tp4*)) + (setq prev-pos (send *tp5* :pos)) + ;; tp6 + (setq *tp6* (make-cube 2 2 2)) + (send *tp6* :translate (v+ (float-vector 0 -10 0) prev-pos)) + (send *tp6* :rotate #d90 :x) + (send *tp6* :set-color :red) + (send *tp6* :put :left-coords + (make-cascoords + :coords (send (send *tp6* :copy-worldcoords) + :translate (float-vector 1 0 0)) + :rot #2f((0 0 1) + (-1 0 0) + (0 -1 0)) + :parent *tp5*)) + (setq prev-pos (send *tp6* :pos)) + ;; tp7 + (setq *tp7* (make-cube 2 2 2)) + (send *tp7* :translate (v+ (float-vector 0 -70 0) prev-pos)) + (send *tp7* :rotate #d90 :x) + (send *tp7* :set-color :red) + (send *tp7* :put :left-coords + (make-cascoords + :coords (send (send *tp6* :copy-worldcoords) + :translate (float-vector 1 0 0)) + :rot #2f((0 0 1) + (-1 0 0) + (0 -1 0)) + :parent *tp6*)) + (setq prev-pos (send *tp7* :pos)))) + + +(set-trajectory 0) + +;;Set coordination. +(send *desk* :put :left-coords + (make-cascoords + :coords (send (send *desk* :copy-worldcoords) :translate (float-vector 0 0 500)) + :parent *pr2*)) +(send *needle* :put :left-coords + (make-cascoords + :coords (send (send *needle* :copy-worldcoords) :translate (float-vector 0 0 -5)) + :parent *needle*)) + +;;Show Worldrecord +(setq *arrow* (arrow)) +(send *arrow* :copy-worldcoords) + +;;Show all objects in IRTVIEWER +(objects (list *pr2* *center* *arrow* *desk* *needle* *hampen* *tp1* *tp2* *tp3* *tp4* *tp5* *tp6* *tp7*)) + +;;Set initial pose +(send *ri* :speak-jp "初期姿勢に戻ります。" :wait t) +(send *pr2* :reset-pose) +(send *ri* :start-grasp :arms) +(send *ri* :angle-vector (send *pr2* :angle-vector) 2000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + +(send *ri* :speak-jp "左手を開きます。針を持たせてください。") +(send *ri* :stop-grasp :larm :wait t) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + +(send *ri* :speak-jp "閉じます。" :wait t) +(send *ri* :start-grasp :larm :wait t) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + +(send *ri* :speak-jp "これから針を持って作業します.離れてください." :wait t) +(unix:sleep 2) + + +;;Grasping needle (dummy) +(send *pr2* :larm :inverse-kinematics + (send (send *needle* :get :left-coords) :copy-worldcoords) + :rotation-axis :z) +(send *pr2* :larm :end-coords :assoc *needle*) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + + +;;Set Start Position +;;Larm +(setq current-coords (send (send *desk* :get :left-coords) :copy-worldcoords)) +(setq new-coords (send current-coords :translate (float-vector 0 100 50))) +(send *pr2* :larm :inverse-kinematics new-coords :rotation-axis :x) +(send *pr2* :larm :end-coords :assoc *needle*) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + +;;Rarm +(setq current-coords (send (send *desk* :get :left-coords) :copy-worldcoords)) +(setq new-coords (send current-coords :translate (float-vector 0 -100 100))) +(send *pr2* :rarm :inverse-kinematics new-coords :rotation-axis :x) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + + +(do ((i 0 (+ i 1))) ; i を 0 から 1 ずつ増加 + ((> i 3) (format t "done")) ;; それぞれの位置と角度情報をリストに格納 ; i が 3 より大きくなったら終了 + (set-trajectory (- (* i 10) 3)) ; i の値に基づいて座標計算 + (format t "Trajectory tp1:~A tp2:~A tp3:~A tp4:~A tp5:~A tp6:~A tp7:~A. ~%" (send *tp1* :copy-worldcoords) (send *tp2* :copy-worldcoords) (send *tp3* :copy-worldcoords) (send *tp4* :copy-worldcoords) (send *tp5* :copy-worldcoords) (send *tp6* :copy-worldcoords) (send *tp7* :copy-worldcoords)) + (objects (list *pr2* *center* *arrow* *desk* *needle* *hampen* *tp1* *tp2* *tp3* *tp4* *tp5* *tp6* *tp7*)) + (send *irtviewer* :draw-objects) + + (send *ri* :start-grasp :larm :wait t) + (send *irtviewer* :draw-objects) + (send *pr2* + :larm + :inverse-kinematics (send (send (send *tp1* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0 -7 0)) + ;;:move-target (send *hanger* :get :left-coords) + ;;:link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis :z + :debug-view t + ) + (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + (send *pr2* + :larm + :inverse-kinematics (send (send (send *tp2* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0 -7 0)) ;; 5cm上、5cm手前 + ;;:move-target (send *hanger* :get :left-coords) + ;;:link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis :z + :debug-view t + ) + (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + (send *pr2* + :larm + :inverse-kinematics (send (send (send *tp3* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0 -7 0)) + ;;:move-target (send *hanger* :get :left-coords) + ;;:link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis :z + :debug-view t + ) + (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + (send *pr2* + :larm + :inverse-kinematics (send (send (send *tp4* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0 -7 0)) + ;;:move-target (send *hanger* :get :left-coords) + ;;:link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis :z + :debug-view t + ) + (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + (send *pr2* + :larm + :inverse-kinematics (send (send (send *tp5* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0 -7 0)) + ;;:move-target (send *hanger* :get :left-coords) + ;;:link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis :z + :debug-view t + ) + (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + (send *pr2* + :larm + :inverse-kinematics (send (send (send *tp6* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0 -7 0)) + ;;:move-target (send *hanger* :get :left-coords) + ;;:link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis :z + :debug-view t + ) + #| + (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + (send *pr2* + :larm + :inverse-kinematics (send (send (send *tp7* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0 -7 0)) + ;;:move-target (send *hanger* :get :left-coords) + ;;:link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis :z + :debug-view t + ) + (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) +|# + + + + ;;Rarm Swith Hands + (send *ri* :stop-grasp :rarm :wait t) + (send *irtviewer* :draw-objects) + + (send *pr2* :rarm :inverse-kinematics + (send (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0.0 0.0 60.0))) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :debug-view t) + (send *ri* :angle-vector (send *pr2* :angle-vector) 5000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + + (send *ri* :start-grasp :rarm :wait t) + (send *irtviewer* :draw-objects) + (send *pr2* :rarm + :inverse-kinematics (send (send (send *tp7* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0 -7 0)) + ;;:move-target (send *hanger* :get :left-coords) + ;;:link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis :z + :debug-view t + ) + (send *ri* :angle-vector (send *pr2* :angle-vector) 5000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + (send *ri* :stop-grasp :larm :wait t) + (send *irtviewer* :draw-objects) + + + + (unix:sleep 2)) ; 1秒間スリープ diff --git a/jsk_2024_10_semi/pr2_surgery_dev2/.#*shell* b/jsk_2024_10_semi/pr2_surgery_dev2/.#*shell* new file mode 120000 index 000000000..45f967377 --- /dev/null +++ b/jsk_2024_10_semi/pr2_surgery_dev2/.#*shell* @@ -0,0 +1 @@ +mech-user@ki00119.4627:1731969929 \ No newline at end of file diff --git a/jsk_2024_10_semi/pr2_surgery_dev2/launch/recognize_wound.launch b/jsk_2024_10_semi/pr2_surgery_dev2/launch/recognize_wound.launch new file mode 100644 index 000000000..5c83e7cd8 --- /dev/null +++ b/jsk_2024_10_semi/pr2_surgery_dev2/launch/recognize_wound.launch @@ -0,0 +1,106 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + queue_size: 100 + + + + + + + use_indices: false + keep_organized: true + h_limit_max: 11 + h_limit_min: -8 + s_limit_max: 255 + s_limit_min: 104 + i_limit_max: 255 + i_limit_min: 0 + + + + + + + tolerance: 0.02 + min_size: 10 + + + + + + + + align_boxes: true + align_boxes_with_plane: false + force_to_flip_z_axis: false + use_pca: false + target_frame_id: base_footprint + + + + + diff --git a/jsk_2024_10_semi/pr2_surgery_dev2/main.l b/jsk_2024_10_semi/pr2_surgery_dev2/main.l new file mode 100644 index 000000000..7dcfb5e0f --- /dev/null +++ b/jsk_2024_10_semi/pr2_surgery_dev2/main.l @@ -0,0 +1,360 @@ +#!/usr/bin/env roseus + +;;(progn (ros::rate 5)(do-until-key (send *ri* :state :potentio-vector)(print (v- (send *ri* :robot :larm :end-coords :worldpos) (send *pr2* :larm :end-coords :worldpos))) (ros::sleep))) + +#| DESCRIPTION +Okada-sensei seminar +Surgery-method dev2 +Last editted Nov 23 by Michi-Tsubaki +GOAL: Trying to make unique motion for sewing sponge. +## Done +- voice recognition +- perception +- stitch sponge + +今後やること +・画像認識で位置決め(Perception) +・手術ロボットでしてみる +・曲がった経路にする(make-trajectory) +|# + +;;Load pkgs around PR2 Interface +(require "package://pr2eus/pr2.l") +(require "package://pr2eus/pr2-utils.l") +(require "package://pr2eus/pr2-interface.l") ;;*ri* +(require "package://pr2eus/speak.l") ;;pkg for speaking + + +(ros::load-ros-package "jsk_recognition_msgs") + + +#| UNDER CONSTRUCTION +;; For perception +(ros::load-ros-manifest "jsk_recognition_msgs") + +;; For listening +(ros::roseus-add-msgs "speech_recognition_msgs") + +;;set node +(ros::roseus "surgery") +|# + +(ros::roseus-add-msgs "speech_recognition_msgs") + +;;Load class related +(load "models/arrow-object.l") ;;*arrow* + + +;; Voice Detection +(defun speech-cb(msg) + (setq *ans* (elt (send msg :transcript) 0)) + (print *ans*) + (if (equal *ans* "メス") + (setq *start-flag* 1) + ;; 1回フラグが立てばそれでいい + )) + +(defun detect-voice () + (ros::ros-info "start waiting for call ~%") + + (ros::subscribe "speech_to_text" speech_recognition_msgs::SpeechRecognitionCandidates #'speech-cb) + (ros::rate 10) + (while (not (eq *start-flag* 1)) + (ros::spin-once) + (ros::sleep) + (ros::ros-info "wait for voice command ...") + ) + ) + + + +(defun cb-recog(msg) + (ros::ros-info "boxes ~A" (length (send msg :boxes))) + (if (> (length (send msg :boxes)) 0) + + (setq *target-ypos-tmp* (send (send (send (elt (send msg :boxes) 0) :pose) :position) :y)) + ) + ) + +;;Global Param +(setq *start-flag* 0) +(setq *centerx* 700) +(setq *centery* 0) +(setq *centerz* 750) +(setq *deskw* 500) +(setq *needle_len* 70) +(setq *interval* 10) +(setq *traj_num* 10) +(setq *traj_len* (* *interval* *traj_num*)) + +;; Set remain +(setq *remain* 280) ;;how long remaining thread? +(setq *diff_remain* 100) + +;; Offset +(setq *rarm_offset* 2) + + +;; Define Trajectory Class +(defclass traj + :super cascaded-coords + :slots (points)) + +(defmethod traj + (:init (&rest args) + (send-super* :init args) + (dotimes (i *traj_num*) + (push + (make-cube 10 10 10 :pos (float-vector (* (- i 5) *interval*) 0 0)) + points)) + (dotimes (i (- (length points) 1)) + (send (elt points i) :assoc (elt points (+ 1 i)))) + (send self :assoc (car points)) + self) ;; :init + (:points () points) + ) ;; defmethod + + +;; Define set-environment method +(defun set-env() + ;;Set center + (setq *deskh* *centerz*) + + (setq *center* (make-cube 10 10 10)) + (send *center* :translate (float-vector *centerx* *centery* *centerz*)) + (send *center* :set-color :black) + (setq *o* (send *center* :copy-worldcoords)) + + ;;Set desk + (setq *desk* (make-cube *deskw* *deskw* *deskh*)) + (send *desk* :translate (float-vector *centerx* *centery* (/ *centerz* 2))) + (send *desk* :set-color :brown) + + ;;Set needle + (setq *needle* (make-cylinder 0.5 *needle_len*)) + (send *needle* :translate (v+ (float-vector -100 20 300) (send *center* :pos))) + (send *needle* :set-color :yellow) + (send *needle* :rotate #d90 :y) + + ;;Set hampen + (setq *hampen* (make-cube 50 50 50)) + (send *hampen* :translate (v+ (float-vector 0 0 10) (send *center* :pos))) + (send *hampen* :set-color :white) + (send *hampen* :rotate #d45 :x) + + (send *desk* :put :left-coords + (make-cascoords + :coords (send (send *desk* :copy-worldcoords) :translate (float-vector 0 0 500)) + :parent *pr2*)) + (send *needle* :put :left-coords + (make-cascoords + :coords (send (send *needle* :copy-worldcoords) :translate (float-vector 0 0 -5)) + :parent *needle*)) +) + + +;;Define preparation task. +(defun preparation() + (require "package://pr2eus/pr2.l") + (require "package://pr2eus/pr2-utils.l") + (require "package://pr2eus/pr2-interface.l") + (require "package://pr2eus/speak.l") + + (send *ri* :speak-jp "初期姿勢に戻ります.注意してください." :wait t) + (send *pr2* :reset-pose) ;;Set Initial Pose + (send *ri* :start-grasp :arms) + (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + + (send *pr2* :head :look-at (send *center* :worldpos)) + + (send *pr2* :larm :inverse-kinematics + (send (send (send *needle* :get :left-coords) + :copy-worldcoords) + :rotate (deg2rad 90) :z) + :rotation-axis :z) ;;IK to needle pose + (send *pr2* :larm :end-coords :assoc *needle*) ;; + (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + + ;;Grasp needle (real) + (send *ri* :speak-jp "左手を開きます.針を持たせてください." :wait t) + (send *ri* :stop-grasp :larm :wait t) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + ) + +;;Define initial task. +(defun init-task() + (send *ri* :speak-jp "手を閉じます.挟まれないように気をつけてください" :wait t) + (send *ri* :start-grasp :larm :wait t) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + (send *ri* :speak-jp "これから針を持って作業します.離れてください." :wait t) + (unix:sleep 2) + + ;;Grasp needle (dummy) + (send *pr2* :larm :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) :rotate (deg2rad 90) :z) :rotation-axis :z) + (send *pr2* :larm :end-coords :assoc *needle*) ;;針を固定 + (send *ri* :angle-vector (send *pr2* :angle-vector) 500) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + ) + + +;;;;main.l;;;;; + +;;Set arrow (for debug) +(setq *arrow* (arrow)) +(send *arrow* :copy-worldcoords) + +;;Set PR2 +(if (not (boundp '*pr2*)) (pr2-init)) + +;; Set the experimental environments. +(set-env) + +;; Show all objects in irtviewer. +(objects (list *pr2* *center* *arrow* *desk* *needle* *hampen*)) + +;; Human help Robot to grab needle. +(preparation) + +;; The Doctore declare the start of the surgery. +;;音声認識******************************************************************************************************** +(detect-voice) +;;(unix:sleep 3) ;;dummy + +;; Do initial task. +(init-task) + +;; Perception (dummy) +(if (send *ri* :simulation-modep) + (setq *target-ypos-tmp* 0) + (setq *target-ypos-tmp* nil) + ) +(setq *target-ypos* 0) +(setq *target-xpos* 0) +(setq *target-zpos* 30) +(ros::subscribe "/recognize_wound/cluster_decomposer/boxes" jsk_recognition_msgs::BoundingBoxArray #'cb-recog) + + +(setq current-coords (send (send *desk* :get :left-coords) :copy-worldcoords)) +(setq new-coords (send current-coords :translate (float-vector 0 100 50))) +(send *pr2* :larm :inverse-kinematics new-coords :rotation-axis :x) +(send *pr2* :larm :end-coords :assoc *needle*) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + +;; + +(ros::rate 10) +(while (null *target-ypos-tmp*) + (ros::ros-info "wait for target...") + ;;(ros::duration-sleep 0.1) + (ros::sleep) + (ros::spin-once)) +(setq *target-ypos* *target-ypos-tmp*) + +;; Stitch +(dotimes (i 5) + ;; Make trajectory points. + (setq r (instance traj :init)) + (send r :rotate pi/2 :z) + (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (+ *target-ypos* (* *traj_len* 0.2)) *target-zpos*))) ;; 0.2は実験則 ;; Trajectoryの中心座標をHampenにあわせている + (send r :locate *target* :world) + (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) + + ;; Set start position. + ;; Rarm + (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) + (send *r-pos* :rotate pi/2 :y :local) + (send *r-pos* :rotate -pi/2 :z :local) ;; if -pi/2, rarm state is parallel to desk + (send *r-pos* :translate #f(-10 0 0) :local) + (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) + (send *ri* :angle-vector (send *pr2* :angle-vector) 500) + (send *ri* :stop-grasp :rarm) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + + + ;; Follow the trajectory points. Stitch. + (dolist (e (send r :points)) + (let (ee) + (setq ee (send e :copy-worldcoords)) + (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) + (send ee :rotate pi :z :local) + (send ee :rotate pi/2 :y :local) + (send ee :draw-on :flush t :size 100) + (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) + (send *ri* :angle-vector (send *pr2* :angle-vector) 500) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + ) + ) + + ;; Pass on the needle. (左手から右手に針を戻す) + (send *ri* :start-grasp :rarm :wait t) + (send *ri* :wait-interpolation) + (unix:sleep 1) + (send *ri* :stop-grasp :larm :wait t) + (send *ri* :wait-interpolation) + + ;; Fix the right arm and neadle (針の固定を左から右に移す) + (send *pr2* :larm :end-coords :dissoc *needle*) + (send *pr2* :rarm :end-coords :assoc *needle*) + + ;; Draw the needle from the object. (対象物から針を抜き出) + (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) + (- *remain* *diff_remain*) ;; オリジナリティポイント: 1回縫うと針を引ける量が減るのを再現 + (format t "remaining ~A ~%" *remain*) ;; for debug! (*remain*が0になったらbreakするようにしたい)******************************************************************************************** + (send *irtviewer* :draw-objects) + (send *ri* :angle-vector (send *pr2* :angle-vector) 5000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + + ;; Move left hand to the delivery point. + (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) + :translate (float-vector 50 (* *needle_len* 0.5) 150)) + :rotate pi/2 :z) + :rotate pi/2 :y) + :rotate pi :x)) + (send *pass-larm* :draw-on :flush t :size 100) ;; for debug! + (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) ;; Use torso! (腰を使わないとIKが解けないので注意) + (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + + ;; Move right hand to the delivery point. + (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) + :translate (float-vector 50 (- 0 (* *needle_len* 0.5)) 150)) + :translate #f(-10 0 0)) + :rotate -pi/2 :x)) + (send *pass-rarm* :draw-on :flush t :size 100) ;; for debug! + (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) ;; Do not use torso! (左手との相対座標が狂う) + (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + + ;; Pass on the needle. (右手から左手に針を戻す) + (send *ri* :start-grasp :larm) + (send *ri* :wait-interpolation) + (unix:sleep 1) + (send *ri* :stop-grasp :rarm) + (send *ri* :wait-interpolation) + + ;; Fix the left arm and needle again (針の固定を右から左に移す) + (send *pr2* :rarm :end-coords :dissoc *needle*) + (send *pr2* :larm :end-coords :assoc *needle*) + (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) + (unix:sleep 1) + (send *pr2* :rarm :move-end-pos (float-vector 0 0 -50) :local) + (send *pr2* :larm :move-end-pos (float-vector 0 0 -100) :local) + (send *ri* :angle-vector (send *pr2* :angle-vector) 500) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + + ) diff --git a/jsk_2024_10_semi/pr2_surgery_dev2/perception.l b/jsk_2024_10_semi/pr2_surgery_dev2/perception.l new file mode 100644 index 000000000..1a6d65c31 --- /dev/null +++ b/jsk_2024_10_semi/pr2_surgery_dev2/perception.l @@ -0,0 +1,55 @@ +#!/usr/bin/env roseus + + + +(require "package://pr2eus/pr2.l") +(require "package://pr2eus/pr2-utils.l") +(require "package://pr2eus/pr2-interface.l") ;;*ri* +(require "package://pr2eus/speak.l") ;;pkg for speaking +;; robotの初期化) + (send *pr2* :reset-pose) + +;; jsk_pcl_rosのmsgを使うため、loadする +;;(ros::load-ros-manifest "jsk_pcl_ros") +(ros::roseus-add-msgs "jsk_recognition_msgs") + +;; クラスタリング結果であるBoundingBoxのtopic名 +(if (ros::get-param "/use_sim_time" nil) + (defvar *topic-name* "/camera/aligned_depth_to_color/boxes") + (defvar *topic-name* "/remote/aligned_depth_to_color/boxes")) +(defvar *bounding-box-list* nil) + +;; ros::initする +(ros::roseus "boundingboxarray_subscriber") + +;; コールバック関数 +(defun bounding-box-array-cb (msg) + (setq *bounding-box-list* (send msg :boxes)) ;; boxesは、BoundingBoxのArray(Euslispではlist) + ;; BoundingBoxがあれば表示する + (when *bounding-box-list* + (send *irtviewer* :draw-objects :flush nil) + (mapcar #'(lambda (b) + ;; BoundingBoxは、dimensions(直方体の幅・奥行き・高さ)をもつ + (let* ((dims (ros::tf-point->pos (send b :dimensions))) + (bx (make-cube (elt dims 0) (elt dims 1) (elt dims 2))) + ;; (1) BoundingBoxのカメラ相対の座標系は、geometry_msgs/Poseという型で得られるので、Euslispのcoordsに変換する + (cam->obj-coords (ros::tf-pose->coords (send b :pose))) + ;; (2) *robot*モデルがカメラの座標系をもってるので、取得する + (cam-coords (send (send *jedy* :camera_color_optical_frame_lk) :copy-worldcoords)) + ) + ;; (3) Euslisp内部でのworld座標系の値にして、そこにmake-cubeの箱を設置する + (send bx :newcoords (send cam-coords :transform cam->obj-coords)) + (send bx :worldcoords) + (send bx :draw-on :flush nil :color #f(1 0 0)) ;; 描画 + bx)) + *bounding-box-list*) + (send *irtviewer* :viewer :viewsurface :flush) + )) + +(ros::subscribe *topic-name* jsk_recognition_msgs::BoundingBoxArray #'bounding-box-array-cb 1) + +(do-until-key + (x::window-main-one) ;; IRT viewerの視点を変えられる。見にくければ変えよう + (ros::spin-once) + (ros::sleep) + ) diff --git a/jsk_2024_10_semi/pr2_surgery_dev2/removable/env.l b/jsk_2024_10_semi/pr2_surgery_dev2/removable/env.l new file mode 100644 index 000000000..151f4831b --- /dev/null +++ b/jsk_2024_10_semi/pr2_surgery_dev2/removable/env.l @@ -0,0 +1,33 @@ +(defun set-env() + ;;cet center + (setq *center* (make-cube 10 10 10)) + (send *center* :translate (float-vector *centerx* *centery* *centerz*)) + (send *center* :set-color :black) + (setq *o* (make-cascoords :pos (send *center* :pos))) + + ;;Set desk + (setq *desk* (make-cube *deskw* *deskw* *deskh*)) + (send *desk* :translate (float-vector *centerx* *centery* (/ *centerz* 2))) + (send *desk* :set-color :brown) + + ;;Set needle + (setq *needle* (make-cylinder 0.5 70)) + (send *needle* :translate (v+ (float-vector 0 20 300) (send *center* :pos))) + (send *needle* :set-color :yellow) + (send *needle* :rotate #d90 :y) + + ;;Set hampen + (setq *hampen* (make-cube 50 50 50)) + (send *hampen* :translate (v+ (float-vector 0 0 10) (send *center* :pos))) + (send *hampen* :set-color :white) + (send *hampen* :rotate #d45 :x) + + (send *desk* :put :left-coords + (make-cascoords + :coords (send (send *desk* :copy-worldcoords) :translate (float-vector 0 0 500)) + :parent *pr2*)) + (send *needle* :put :left-coords + (make-cascoords + :coords (send (send *needle* :copy-worldcoords) :translate (float-vector 0 0 -5)) + :parent *needle*)) +) diff --git a/jsk_2024_10_semi/pr2_surgery_dev2/removable/initial-task.l b/jsk_2024_10_semi/pr2_surgery_dev2/removable/initial-task.l new file mode 100644 index 000000000..2c738d791 --- /dev/null +++ b/jsk_2024_10_semi/pr2_surgery_dev2/removable/initial-task.l @@ -0,0 +1,36 @@ +(defun initial-task() + (require "package://pr2eus/pr2.l") + (require "package://pr2eus/pr2-utils.l") + (require "package://pr2eus/pr2-interface.l") + (require "package://pr2eus/speak.l") + + (send *ri* :speak-jp "初期姿勢に戻ります。" :wait t) + (send *pr2* :reset-pose) + (send *ri* :start-grasp :arms) + (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + + (send *pr2* :larm :inverse-kinematics + (send (send (send *needle* :get :left-coords) + :copy-worldcoords) + :rotate (deg2rad 90) :z) + :rotation-axis :z + :debug-view t) + (send *pr2* :larm :end-coords :assoc *needle*) + (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + + (send *ri* :speak-jp "左手を開きます。針を持たせてください。") + (send *ri* :stop-grasp :larm :wait t) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + + (send *ri* :speak-jp "閉じます。" :wait t) + (send *ri* :start-grasp :larm :wait t) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + (send *ri* :speak-jp "これから針を持って作業します.離れてください." :wait t) + (unix:sleep 2) +) diff --git a/jsk_2024_10_semi/pr2_surgery_dev2/removable/trajectory.l b/jsk_2024_10_semi/pr2_surgery_dev2/removable/trajectory.l new file mode 100644 index 000000000..e48645d80 --- /dev/null +++ b/jsk_2024_10_semi/pr2_surgery_dev2/removable/trajectory.l @@ -0,0 +1,16 @@ +(defclass traj + :super cascaded-coords + :slots (points)) +(defmethod traj + (:init (&rest args) + (send-super* :init args) + (dotimes (i 10) + (push + (make-cube 10 10 10 :pos (float-vector (* (- i 5) 20) 0 0)) + points)) + (dotimes (i (- (length points) 1)) + (send (elt points i) :assoc (elt points (+ 1 i)))) + (send self :assoc (car points)) + self) ;; :init + (:points () points) + ) ;; defmethod diff --git a/jsk_2024_10_semi/pr2_tubes/.catkin_workspace b/jsk_2024_10_semi/pr2_tubes/.catkin_workspace new file mode 100644 index 000000000..52fd97e7e --- /dev/null +++ b/jsk_2024_10_semi/pr2_tubes/.catkin_workspace @@ -0,0 +1 @@ +# This file currently only serves to mark the location of a catkin workspace for tool integration diff --git a/jsk_2024_10_semi/pr2_tubes/CMakeLists.txt b/jsk_2024_10_semi/pr2_tubes/CMakeLists.txt new file mode 100644 index 000000000..7593a6efa --- /dev/null +++ b/jsk_2024_10_semi/pr2_tubes/CMakeLists.txt @@ -0,0 +1,208 @@ +cmake_minimum_required(VERSION 3.0.2) +project(pr2_tubes) + +## Compile as C++11, supported in ROS Kinetic and newer +# add_compile_options(-std=c++11) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package(catkin REQUIRED COMPONENTS + jsk_recognition_msgs + roscpp + roseus + rospy + std_msgs +) + +## System dependencies are found with CMake's conventions +# find_package(Boost REQUIRED COMPONENTS system) + + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################################ +## Declare ROS messages, services and actions ## +################################################ + +## To declare and build messages, services or actions from within this +## package, follow these steps: +## * Let MSG_DEP_SET be the set of packages whose message types you use in +## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). +## * In the file package.xml: +## * add a build_depend tag for "message_generation" +## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET +## * If MSG_DEP_SET isn't empty the following dependency has been pulled in +## but can be declared for certainty nonetheless: +## * add a exec_depend tag for "message_runtime" +## * In this file (CMakeLists.txt): +## * add "message_generation" and every package in MSG_DEP_SET to +## find_package(catkin REQUIRED COMPONENTS ...) +## * add "message_runtime" and every package in MSG_DEP_SET to +## catkin_package(CATKIN_DEPENDS ...) +## * uncomment the add_*_files sections below as needed +## and list every .msg/.srv/.action file to be processed +## * uncomment the generate_messages entry below +## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) + +## Generate messages in the 'msg' folder +# add_message_files( +# FILES +# Message1.msg +# Message2.msg +# ) + +## Generate services in the 'srv' folder +# add_service_files( +# FILES +# Service1.srv +# Service2.srv +# ) + +## Generate actions in the 'action' folder +# add_action_files( +# FILES +# Action1.action +# Action2.action +# ) + +## Generate added messages and services with any dependencies listed here +# generate_messages( +# DEPENDENCIES +# jsk_recognition_msgs# std_msgs +# ) + +################################################ +## Declare ROS dynamic reconfigure parameters ## +################################################ + +## To declare and build dynamic reconfigure parameters within this +## package, follow these steps: +## * In the file package.xml: +## * add a build_depend and a exec_depend tag for "dynamic_reconfigure" +## * In this file (CMakeLists.txt): +## * add "dynamic_reconfigure" to +## find_package(catkin REQUIRED COMPONENTS ...) +## * uncomment the "generate_dynamic_reconfigure_options" section below +## and list every .cfg file to be processed + +## Generate dynamic reconfigure parameters in the 'cfg' folder +# generate_dynamic_reconfigure_options( +# cfg/DynReconf1.cfg +# cfg/DynReconf2.cfg +# ) + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if your package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES pr2_surgery +# CATKIN_DEPENDS jsk_recognition_msgs roscpp roseus rospy std_msgs +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +include_directories( +# include + ${catkin_INCLUDE_DIRS} +) + +## Declare a C++ library +# add_library(${PROJECT_NAME} +# src/${PROJECT_NAME}/pr2_surgery.cpp +# ) + +## Add cmake target dependencies of the library +## as an example, code may need to be generated before libraries +## either from message generation or dynamic reconfigure +# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Declare a C++ executable +## With catkin_make all packages are built within a single CMake context +## The recommended prefix ensures that target names across packages don't collide +# add_executable(${PROJECT_NAME}_node src/pr2_surgery_node.cpp) + +## Rename C++ executable without prefix +## The above recommended prefix causes long target names, the following renames the +## target back to the shorter version for ease of user use +## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" +# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") + +## Add cmake target dependencies of the executable +## same as for the library above +# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) + +## Specify libraries to link a library or executable target against +# target_link_libraries(${PROJECT_NAME}_node +# ${catkin_LIBRARIES} +# ) + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# catkin_install_python(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html +# install(TARGETS ${PROJECT_NAME}_node +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark libraries for installation +## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html +# install(TARGETS ${PROJECT_NAME} +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_pr2_surgery.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/jsk_2024_10_semi/pr2_tubes/config/table_marker.yaml b/jsk_2024_10_semi/pr2_tubes/config/table_marker.yaml new file mode 100644 index 000000000..0db13fdb8 --- /dev/null +++ b/jsk_2024_10_semi/pr2_tubes/config/table_marker.yaml @@ -0,0 +1,16 @@ +boxes: +- dimensions: + - 0.5 + - 0.3 + - 0.2 + frame_id: base_footprint + name: table + orientation: + - 3.9531047036326084e-10 + - 0.008311730048626616 + - 4.293287988035861e-12 + - 0.9999654569751891 + position: + - 0.7592881917953491 + - 0.015209555625915527 + - 0.849845826625824 diff --git a/jsk_2024_10_semi/pr2_tubes/launch/recognize_wound.launch b/jsk_2024_10_semi/pr2_tubes/launch/recognize_wound.launch new file mode 100755 index 000000000..a8459f8e7 --- /dev/null +++ b/jsk_2024_10_semi/pr2_tubes/launch/recognize_wound.launch @@ -0,0 +1,157 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + queue_size: 100 + + + + + + display_interactive_manipulator: true + display_interactive_manipulator_only_selected: true + display_description_only_selected: true + + + + + + + config_file: $(find pr2_surgery)/config/table_marker.yaml + config_auto_save: true + + + + + + + index: 0 + + + + + + + + + use_multiple_attention: false + + + + + + + keep_organized: true + approximate_sync: true + max_queue_size: 100 + + + + + + + use_indices: false + keep_organized: true + h_limit_max: 10 + h_limit_min: -10 + s_limit_max: 255 + s_limit_min: 35 + i_limit_max: 255 + i_limit_min: 0 + + + + + + + tolerance: 0.02 + min_size: 10 + downsample_enable: true + cluster_filter: 1 + + + + + + + + align_boxes: true + align_boxes_with_plane: false + force_to_flip_z_axis: false + use_pca: false + target_frame_id: base_footprint + + + + + diff --git a/jsk_2024_10_semi/pr2_tubes/package.xml b/jsk_2024_10_semi/pr2_tubes/package.xml new file mode 100644 index 000000000..729260608 --- /dev/null +++ b/jsk_2024_10_semi/pr2_tubes/package.xml @@ -0,0 +1,74 @@ + + + pr2_tubes + 0.0.0 + The pr2_tubes package + + + + + mech-user + + + + + + TODO + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + catkin + jsk_recognition_msgs + roscpp + roseus + rospy + std_msgs + jsk_recognition_msgs + roscpp + roseus + rospy + std_msgs + jsk_recognition_msgs + roscpp + roseus + rospy + std_msgs + + + + + + + + diff --git a/jsk_2024_10_semi/pr2_tubes/src/CMakeLists.txt b/jsk_2024_10_semi/pr2_tubes/src/CMakeLists.txt new file mode 120000 index 000000000..201681686 --- /dev/null +++ b/jsk_2024_10_semi/pr2_tubes/src/CMakeLists.txt @@ -0,0 +1 @@ +/opt/ros/noetic/share/catkin/cmake/toplevel.cmake \ No newline at end of file diff --git a/jsk_2024_10_semi/pr2_tubes/src/main.l b/jsk_2024_10_semi/pr2_tubes/src/main.l new file mode 100755 index 000000000..0c882993f --- /dev/null +++ b/jsk_2024_10_semi/pr2_tubes/src/main.l @@ -0,0 +1,246 @@ +#!/usr/bin/env roseus + +#| DESCRIPTION +PR2で血管モデルを縫合する. +|# + +;; PR2のインタフェースをロードする +(require "package://pr2eus/pr2.l") +(require "package://pr2eus/pr2-utils.l") +(require "package://pr2eus/pr2-interface.l") ;;*ri* +(require "package://pr2eus/speak.l") ;;pkg for speaking + +;; jskのメッセージ型をロードする +(ros::load-ros-package "jsk_recognition_msgs") +(ros::roseus-add-msgs "speech_recognition_msgs") +(ros::roseus-add-msgs "geometry_msgs") + +;; PR2の初期化 +(if (not (boundp '*pr2*)) + (pr2-init) + ) ;; 変数*pr2*が存在しなければ(pr2-init)を実行する + + +;; 実験環境の中心の設定 +(setq *centerx* 700) +(setq *centery* 0) +(setq *centerz* 755) +(setq *center* (make-cube 10 10 10)) +(send *center* :translate (float-vector *centerx* *centery* *centerz*)) +(send *center* :set-color :black) +(setq *o* (send *center* :copy-worldcoords)) + +;; 実験机の設定 +(setq *deskw* 500) +(setq *deskd* 800) +(setq *deskh* *centerz*) +(setq *desk* (make-cube *deskw* *deskd* *deskh*)) +(send *desk* :translate (float-vector *centerx* *centery* (* *centerz* 0.5))) +(send *desk* :set-color :white) + +;; 血管実験台 +(setq *tablew* 50) +(setq *tabled* 80) +(setq *tableh* 10) +(setq *table* (make-cube *tablew* *tabled* *tableh*)) +(send *table* :translate (float-vector (- *centerx* 200) *centery* (+ *centerz* (* *tableh* 0.5)) )) +(send *table* :set-color :red) + +;; ベンド針モデル ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +(setq *needle-radius* 15) +(setq *needle-thickness* 2) +(setq *needle-angle* pi) + +;; 針を構成する微小片を作る +(setq segments 40) +(setq theta-step (/ *needle-angle* segments)) +(setq points nil) +(dotimes (i (+ segments 1)) + (let ((theta (* i theta-step))) + (push (float-vector + (* *needle-radius* (- 1 (cos theta))) ; x + 0 ; y + (* *needle-radius* (sin theta))) ; z + points))) +(setq points (reverse points)) + +(defun make-rotation-matrix (p1 p2) + (let* ((diff (v- p2 p1)) + (z-axis (normalize-vector diff)) + (y-axis (float-vector 0 1 0)) + (x-axis (v* y-axis z-axis))) + (setq y-axis (v* z-axis x-axis)) ; ensure orthogonality + (transpose (matrix (normalize-vector x-axis) + (normalize-vector y-axis) + (normalize-vector z-axis))))) + +;; アーチ状にシリンダーを作っていく +(setq needle-parts nil) +(let ((prev-point (car points))) + (dolist (point (cdr points)) + (let* ((diff (v- point prev-point)) + (height (norm diff)) + (center (midpoint 0.5 prev-point point)) + (cylinder (make-cylinder *needle-thickness* height :segments 12)) + (rot-mat (make-rotation-matrix prev-point point))) + (setq coords (make-coords :pos center :rot rot-mat)) + (send cylinder :transform coords) + (push cylinder needle-parts) + (setq prev-point point)))) + +;; bodysetにする +(setq needle-bodies (reverse needle-parts)) + +;; assocする +(dolist (body (cdr needle-bodies)) + (send (car needle-bodies) :assoc body)) + +;; 針の色(銀色)にする +(dolist (body needle-bodies) + (send body :set-color :yellow)) + +;; needleをbodyset-linkとして定義する +(setq *needle* + (instance bodyset-link :init (make-cascoords) + :bodies needle-bodies)) + +(send *needle* :translate (float-vector (- *centerx* 200) *centery* (+ *centerz* 40))) +(send *needle* :rotate #d180 :y) +(send *needle* :rotate #d90 :z) + + +;; メモ: euslispのscriptで作れる基本的な幾何構造 +;; --> https://euslisp.github.io/jskeus/jmanual-node118.html + +;; 復習: euslispの座標系 +;; 右手座標系 red-> x, green-> y, blue-> z + +;; 左血管 +(setq *left-tube* (make-cylinder 2.5 20)) +(send *left-tube* :translate (float-vector (- *centerx* 200) *centery* (+ *centerz* 10))) +(send *left-tube* :rotate #d90 :x) +(send *left-tube* :translate (float-vector 0 0 -21)) +(send *left-tube* :set-color :white) +(send (send *left-tube* :copy-worldcoords) :draw-on :flush t :size 100) +(setq *left-tube-rc* (send (send *left-tube* :copy-worldcoords) :translate (float-vector 0 0 20))) +(send *left-tube-rc* :draw-on :flush t :size 100) + +;; 右血管 +(setq *right-tube* (make-cylinder 2.5 20)) +(send *right-tube* :translate (float-vector (- *centerx* 200) *centery* (+ *centerz* 10))) +(send *right-tube* :rotate #d90 :x) +(send *right-tube* :translate (float-vector 0 0 1)) +(send *right-tube* :set-color :white) +(send (send *right-tube* :copy-worldcoords) :draw-on :flush t :size 100) +(setq *right-tube-lc* (send (send *right-tube* :copy-worldcoords) :translate (float-vector 0 0 0))) +(send *right-tube-lc* :draw-on :flush t :size 100) + +;; pr2 の左腕の座標系の確認 +(send (send *pr2* :larm :end-coords) :draw-on :flush t :size 100) +(send (send *pr2* :rarm :end-coords) :draw-on :flush t :size 100) + + + +(make-irtviewer) + +(objects (list *pr2* *center* *desk* *table* *needle* *left-tube* *right-tube*)) + +(send *irtviewer* :draw-objects) + + +;; 針をもたせる + +;; まず座標系をコピー +(setq *larm-coords* (send *pr2* :larm :end-coords :copy-worldcoords)) + +;; 座標系自体を回転させる +(send *larm-coords* :rotate (deg2rad 90) :y) +(send *larm-coords* :translate #f(0 0 20)) + +;; 回転させた座標系に針を移動 +(send *needle* :move-to *larm-coords* :world) + +;; 針をPR2の左腕にassocする +(send (send *pr2* :larm :end-coords) :assoc *needle*) + +;; 描画を更新 +(send *irtviewer* :draw-objects) + + +;; 縫い始める +;; 針の端に座標系を作成 +(setq *needle-tip-coords* (make-cascoords :pos (send (elt needle-bodies (1- (length needle-bodies))) :worldpos))) +(send *needle* :assoc *needle-tip-coords*) + +;; 目標位置(左血管)の座標を設定 + +;;todo この設定 +(setq *target-coords* (send *left-tube-rc* :copy-worldcoords)) +;; IKを解く(torsoを使用) +(send *pr2* :larm :inverse-kinematics *target-coords* + :move-target *needle-tip-coords* + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :use-torso t + :debug-view t) + +(send *irtviewer* :draw-objects) + + + +;; 計画中 +;; 曲率を持ったtrajectory +;; 軌道のパラメータ設定 +(setq *needle_len* 70) +(setq *interval* 10) +(setq *traj_num* 10) +(setq *traj_len* (* *interval* *traj_num*)) + +;; 曲線的な軌道のためのtrajクラスを定義 +(defclass curved-traj + :super cascaded-coords + :slots (points)) + +(defmethod curved-traj + (:init (&key (radius 30.0) (start-angle -45) (end-angle 45)) + (send-super :init) ;; 修正:argumentsなしで初期化 + (let* ((angle-step (/ (- end-angle start-angle) (1- *traj_num*))) + (current-angle start-angle)) + ;; 円弧上の点を生成 + (setq points nil) ;; pointsを初期化 + (dotimes (i *traj_num*) + (let* ((theta (deg2rad current-angle)) + (x (* radius (sin theta))) + (z (* radius (cos theta))) + (point (make-cube 10 10 10 + :pos (float-vector x 0 z)))) + (push point points) + (setq current-angle (+ current-angle angle-step)))) + (setq points (reverse points))) + ;; 点同士を関連付け + (dotimes (i (1- (length points))) + (send (elt points i) :assoc (elt points (1+ i)))) + (send self :assoc (car points)) + self) + (:points () points)) + +;; 血管縫合のための関数 +(defun stitch-blood-vessels () + ;; 針の端に座標系を作成 + (setq *needle-tip-coords* (make-cascoords :pos (send (elt needle-bodies (1- (length needle-bodies))) :worldpos))) + (send *needle* :assoc *needle-tip-coords*) + + ;; 最初の血管(左)への軌道 + (setq *target-coords* (send *left-tube-rc* :copy-worldcoords)) + + ;; 曲線軌道を生成 + (setq *curved-path* (instance curved-traj :init)) + (send *curved-path* :translate (send *target-coords* :worldpos)) + + ;; すべてのオブジェクトを表示(軌道の点を含む) + (objects (append (list *pr2* *center* *desk* *table* *needle* *left-tube* *right-tube*) + (send *curved-path* :points))) +) + +;; 実行 +(stitch-blood-vessels) diff --git a/jsk_2024_10_semi/pr2_tubes/src/needle.l b/jsk_2024_10_semi/pr2_tubes/src/needle.l new file mode 100644 index 000000000..eec03ccc7 --- /dev/null +++ b/jsk_2024_10_semi/pr2_tubes/src/needle.l @@ -0,0 +1,82 @@ +#| +Desctiption : +Make a bend needle model here! + +Author : +@Michi-Tsubaki +|# + +;; Load irteus visualization +(require "package://pr2eus/pr2.l") +(require "package://pr2eus/pr2-utils.l") +(require "package://pr2eus/pr2-interface.l") +(require "package://pr2eus/speak.l") + +; Define needle parameters +(setq *needle-radius* 35) ; radius of curvature +(setq *needle-thickness* 0.5) ; thickness of the needle +(setq *needle-angle* (/ pi 2)) ; angle of the arc + +;; Create points for the needle path +(setq segments 40) +(setq theta-step (/ *needle-angle* segments)) +(setq points nil) +(dotimes (i (+ segments 1)) + (let ((theta (* i theta-step))) + (push (float-vector + (* *needle-radius* (- 1 (cos theta))) ; x + 0 ; y + (* *needle-radius* (sin theta))) ; z + points))) +(setq points (reverse points)) + +;; Function to calculate rotation matrix from two points +(defun make-rotation-matrix (p1 p2) + (let* ((diff (v- p2 p1)) + (z-axis (normalize-vector diff)) + (y-axis (float-vector 0 1 0)) + (x-axis (v* y-axis z-axis))) + (setq y-axis (v* z-axis x-axis)) ; ensure orthogonality + (transpose (matrix (normalize-vector x-axis) + (normalize-vector y-axis) + (normalize-vector z-axis))))) + +;; Create cylinders along the arc +(setq needle-parts nil) +(let ((prev-point (car points))) + (dolist (point (cdr points)) + (let* ((diff (v- point prev-point)) + (height (norm diff)) + (center (midpoint 0.5 prev-point point)) + (cylinder (make-cylinder *needle-thickness* height :segments 12)) + (rot-mat (make-rotation-matrix prev-point point))) + ;; Create coordinates at center with proper orientation + (setq coords (make-coords :pos center :rot rot-mat)) + ;; Orient and position cylinder + (send cylinder :transform coords) + (push cylinder needle-parts) + (setq prev-point point)))) + +;; Create the bodyset +(setq needle-bodies (reverse needle-parts)) + +;; Associate all parts with the first one +(dolist (body (cdr needle-bodies)) + (send (car needle-bodies) :assoc body)) + +;; 針の色(銀色)にする +(dolist (body needle-bodies) + (send body :set-color :silver)) + +;; needleをbodyset-linkとして定義する +(setq *needle* + (instance bodyset-link :init (make-cascoords) + :bodies needle-bodies)) + +;; 表示する +(make-irtviewer) +(objects (list *needle*)) + +;; Optional: rotate the view to better see the needle +(send *irtviewer* :viewing :look #f(0 -1 0.1)) +(send *irtviewer* :draw-objects) diff --git a/jsk_2024_10_semi/presentation/uml.act b/jsk_2024_10_semi/presentation/uml.act new file mode 100644 index 000000000..18cf68cd2 --- /dev/null +++ b/jsk_2024_10_semi/presentation/uml.act @@ -0,0 +1,74 @@ +@startuml +|医者(PR2)| + start + :「手術開始」を宣言(speak); + :針を受け取りに行く(IK); + :「針をください」と言う(speak); + +|看護師| + :針をPR2に渡す; + :「どうぞ」と言う; + +|医者(PR2)| +repeat + :指を開いて針を待つ(start-grasp); +repeat while (「どうぞ」という音声入力(speech_to_text)を受けるまで) + +|医者の左腕(PR2 larm)| +:指を閉じて針を受け取る(start-grasp); + +|医者(PR2)| + +repeat +:「傷口を探しています」と言う(speak); + :HSIフィルタで赤色を抽出する; + :Euclidean Clusteringしてバウンディングボックスをつける; + :傷口の座標を取得する; +repeat while (傷口を見つけるまで繰り返し,待機) + +:傷口の位置に縫合する針の経路を生成する; + +repeat + +|医者の右腕(PR2 rarm)| + +:経路の最終地点に移動する(IK); +:指を開いて待機する(stop-grasp); + + +|医者の左腕(PR2 larm)| +:経路の最初の地点に移動する(IK); +:経路に従って縫い進める(angle-vector-sequence); +:経路の最終地点で停止する; + +|医者の右腕(PR2 rarm)| +:指を閉じて針を受け取る(start-grasp); +|医者の左腕(PR2 larm)| +:指を開いて針を離す(stop-grasp); + +|医者の右腕(PR2 rarm)| +:腕を右に引いて余分な針を傷口から引き出す(move-pos); + +|医者の左腕(PR2 larm)| +:針の受け渡しポイントに腕を動かす(IK); + +|医者の右腕(PR2 rarm)| +:針の受け渡しポイントに腕を動かす(IK); + +|医者の左腕(PR2 larm)| +:指を閉じて針を受け取る(start-grasp); + +|医者の右腕(PR2 rarm)| +:指を開いて針を離す(stop-grasp); + +|医者(PR2)| +:経路を5mmずらして生成する; + + +repeat while (5針縫って傷口が閉じるまで続ける) + +|医者(PR2)| +:「手術終了」と宣言する(speak); + +end +@enduml diff --git a/jsk_2024_10_semi/presentation/uml.png b/jsk_2024_10_semi/presentation/uml.png new file mode 100644 index 000000000..58fc6e177 Binary files /dev/null and b/jsk_2024_10_semi/presentation/uml.png differ diff --git a/jsk_2024_10_semi/sample/demo-box.l b/jsk_2024_10_semi/sample/demo-box.l new file mode 100644 index 000000000..a5fa73035 --- /dev/null +++ b/jsk_2024_10_semi/sample/demo-box.l @@ -0,0 +1,41 @@ +(require "package://pr2eus/pr2-interface.l") +(pr2-init) + +(defclass box-label-synchronizer + :super exact-time-message-filter) + +(defmethod box-label-synchronizer + (:callback (box label) + (print (list box label)) + (print (send-all (list box label) :header :stamp)) + )) + +;; ;; test +;; (setq *box-label* (instance box-label-synchronizer :init +;; (list (list "/docker/detic_segmentor/output/boxes" jsk_recognition_msgs::BoundingBoxArray) +;; (list "/docker/detic_segmentor/detected_classes" jsk_recognition_msgs::LabelArray)))) + +(ros::load-ros-manifest "jsk_recognition_msgs") +(setq *target-box* (make-cube 100 100 100)) +(objects (list *pr2* *target-box*)) +(defun box-cb (msg) + (ros::ros-info "received ~A boxes" (length (send msg :boxes))) + (dolist (box (send msg :boxes)) + (when (= (send box :label) 41) ;; 41 -> ball + (setq *target-coords* (send (ros::tf-pose->coords (send box :pose)) :copy-worldcoords)) + (setq *target-dimensions* (send box :dimensions)) + (format t "coords ~A, dimension ~A~%" (send *target-coords* :worldcoords) (* (send *target-dimensions* :x) (send *target-dimensions* :y) (send *target-dimensions* :z))) + (when (and (< (elt (send *target-coords* :worldpos) 2) 1000) + (> (elt (send *target-coords* :worldpos) 2) 600)) + (send *target-box* :move-to *target-coords* :world) + (print "update target position") + )))) + +(ros::subscribe "/synchronized_detic_label_boxes" jsk_recognition_msgs::BoundingBoxArray #'box-cb) +;;(ros::subscribe "/kinect_head/depth_registered/boxes" jsk_recognition_msgs::BoundingBoxArray #'box-cb) +(do-until-key + (send *pr2* :angle-vector (send *ri* :state :potentio-vector)) + (send *irtviewer* :draw-objects) + (x::window-main-one) + (ros::spin-once) + ) diff --git a/jsk_2024_10_semi/sample/demo-set-trajectory.l b/jsk_2024_10_semi/sample/demo-set-trajectory.l new file mode 100644 index 000000000..63c94e9e4 --- /dev/null +++ b/jsk_2024_10_semi/sample/demo-set-trajectory.l @@ -0,0 +1,47 @@ +;; (defun test () +;; (let ((r nil)) +;; (dotimes (i 10) +;; (push +;; (make-cube 10 10 10 :pos (float-vector (* (- i 5) 20) 0 0)) +;; r)) +;; (dotimes (i (- (length r) 1)) +;; (send (elt r i) :assoc (elt r (+ 1 i)))) +;; r)) +(require "package://pr2eus/pr2.l") +(require "package://pr2eus/pr2-utils.l") +(require "package://pr2eus/pr2-interface.l") +(if (not (boundp '*pr2*)) (pr2-init)) + +(defclass test1 + :super cascaded-coords + :slots (points)) +(defmethod test1 + (:init (&rest args) + (send-super* :init args) + (dotimes (i 10) + (push + (make-cube 10 10 10 :pos (float-vector (* (- i 5) 20) 0 0)) + points)) + (dotimes (i (- (length points) 1)) + (send (elt points i) :assoc (elt points (+ 1 i)))) + (send self :assoc (car points)) + self) + (:points () points) + ) + + + +;;(setq r (test)) +;;(send (car r) :rotate pi/2 :z) +;;(send (car r) :locate #f(800 0 900) :world) +(setq r (instance test1 :init)) +(send r :rotate pi/2 :z) +(send r :locate #f(800 0 900) :world) +(objects (append (list *pr2*) (send r :points))) +(send *irtviewer* :draw-objects) +;;(objects (list *pr2* (elt (send r :points) 0) (elt (send r :points) 1) (elt (send r :points) 2) +;(dolist (e (send r :points) +; (send *pr2* :rarm :inverse-kinematics e +; :rotation-axis nil +; :debug-view t) +; (send *irtviewer* :draw-objects)) diff --git a/jsk_2024_10_semi/sample/demo_solve-ik.l b/jsk_2024_10_semi/sample/demo_solve-ik.l new file mode 100755 index 000000000..95750df78 --- /dev/null +++ b/jsk_2024_10_semi/sample/demo_solve-ik.l @@ -0,0 +1,45 @@ +#!/usr/bin/env roseus + +;; PR2のモデルを読み込む +(require "package://pr2eus/pr2.l") + +;; PR2のインスタンスを作成 +(if (not (boundp '*pr2*)) (setq *pr2* (pr2))) + +;; 1辺200mmの立方体を出現させる +(setq *cube* (make-cube 200 200 200)) ;; NOTE 実際はハンガーなど,デモに使用するモデルを作って出現させるとよいかもしれない +;; 立方体を(400, 0, 800)移動 +(send *cube* :translate (float-vector 400 0 800)) ;; NOTE 画像認識結果から,ハンガーの位置を取得して移動するとよいかもしれない + +;; 立方体の左側面に座標系を設定 +(send *cube* :put :left-coords + (make-cascoords + :coords (send (send *cube* :copy-worldcoords) :translate (float-vector 0 100 0)) + :parent *cube*)) + +;; ビューワを表示 +(objects (list *pr2* *cube*)) + +;; 左腕について,立方体の両側面に向かって逆運動学を解く +(send *pr2* :larm :inverse-kinematics + (send (send *cube* :get :left-coords) :copy-worldcoords) + :rotation-axis :z) + +;; PR2の左腕で立方体を持ち上げて前に突き出す +;; PR2の左腕と立方体の左側を連結する. +(send *pr2* :larm :end-coords :assoc *cube*) +;; 立方体が現在の位置から相対で(100, 0, 200)に移動するように逆運動学を解く +(send *pr2* + :inverse-kinematics (send (send (send *cube* :get :left-coords) :copy-worldcoords) + :translate (float-vector 100.0 0.0 100.0)) + :move-target (send *cube* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :debug-view t) + +;;(send *ri* :angle-vector (send *pr2* :angle-vector) 2000) +;;(send *ri* :wait-interpolation) + + +;; NOTE 両腕で持って渡すみたいな動作は,結構難しい? ref: https://github.com/euslisp/jskeus/issues/582 +;; :assocは閉リンクを形成できないので,1つの箱に両腕を連結することはできない? diff --git a/jsk_2024_10_semi/sample/okadasensei_shell_nov27.txt b/jsk_2024_10_semi/sample/okadasensei_shell_nov27.txt new file mode 100644 index 000000000..f158267f6 --- /dev/null +++ b/jsk_2024_10_semi/sample/okadasensei_shell_nov27.txt @@ -0,0 +1,8472 @@ +mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi$ rossetip +Could not resolve ip from address. Subnet may be different +set ROS_IP and ROS_HOSTNAME to 133.11.216.48 +[http://pr1040:11311][133.11.216.48] ]0;mech-user@ki00119: ~/semi_ws/jsk_demos/jsk_2024_10_semimech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi$ rossetmaster pr1040 +set ROS_MASTER_URI to http://pr1040:11311 +[http://pr1040:11311][133.11.216.48] ]0;mech-user@ki00119: ~/semi_ws/jsk_demos/jsk_2024_10_semimech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi$ load "pingpong.l" + +Command 'load' not found, did you mean: + + command 'tload' from deb procps (2:3.3.16-1ubuntu2.4) + command 'xload' from deb x11-apps (7.7+8) + command 'nload' from deb nload (0.7.4-2build3) + +Try: sudo apt install + +[http://pr1040:11311][133.11.216.48] ]0;mech-user@ki00119: ~/semi_ws/jsk_demos/jsk_2024_10_semimech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi$ roseus +configuring by "/opt/ros/noetic/share/euslisp/jskeus/eus//lib/eusrt.l" +;; readmacro ;; object ;; packsym ;; common ;; constants ;; stream ;; string ;; loader ;; pprint ;; process ;; hashtab ;; array ;; mathtran ;; eusdebug ;; eusforeign ;; extnum ;; coordinates ;; tty ;; history ;; toplevel ;; trans ;; comp ;; builtins ;; par ;; intersection ;; geoclasses ;; geopack ;; geobody ;; primt ;; compose ;; polygon ;; viewing ;; viewport ;; viewsurface ;; hid ;; shadow ;; bodyrel ;; dda ;; helpsub ;; eushelp ;; xforeign ;; Xdecl ;; Xgraphics ;; Xcolor ;; Xeus ;; Xevent ;; Xpanel ;; Xitem ;; Xtext ;; Xmenu ;; Xscroll ;; Xcanvas ;; Xtop ;; Xapplwin +connected to Xserver DISPLAY=:0 +X events are being asynchronously monitored. +;; pixword ;; RGBHLS ;; convolve ;; piximage ;; pbmfile ;; image_correlation ;; oglforeign ;; gldecl ;; glconst ;; glforeign ;; gluconst ;; gluforeign ;; glxconst ;; glxforeign ;; eglforeign ;; eglfunc ;; glutil ;; gltexture ;; glprim ;; gleus ;; glview ;; toiv-undefined ;; fstringdouble irtmath irtutil irtc irtgeoc irtgraph gnuplotlib ___time ___pgsql irtgeo euspqp pqp irtscene irtmodel irtdyna irtrobot irtsensor irtbvh irtcollada irtstl irtwrl irtpointcloud eusbullet bullet irtcollision irtx eusjpeg euspng png irtimage irtglrgb +;; extending gcstack 0x556794e30680[16374] --> 0x5567952c0c90[32748] top=3d4b +irtgl irtglc irtviewer +EusLisp 9.29( 1.2.5) for Linux64 created on ip-10-0-1-5(Tue Jun 20 10:34:21 PST 2023) +roseus ;; loading roseus("1.7.5") on euslisp((9.29 ip-10-0-1-5 Tue Jun 20 10:34:21 PST 2023 1.2.5)) +eustf roseus_c_util 1.irteusgl$ load "pingpong.l" +;; roseus_resume is disabled. + +;; extending gcstack 0x5567952c0c90[32738] --> 0x556796ddb9a0[65476] top=7fe1 +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.96783) violate max-angle(-5.72958) +;; (make-irtviewer) executed +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.96783) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.96783) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.96783) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.96783) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.96783) violate max-angle(-5.72958) +;; # :joint-angle(-4.59888) violate max-angle(-5.72958) +;; # :joint-angle(75.594) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.96783) violate max-angle(-5.72958) +[ INFO] [1732707742.306886327]: wait-interpolation debug: start +[ INFO] [1732707743.315019931]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.05258) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.05258) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.05258) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.05258) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.05258) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.05258) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.05258) violate max-angle(-5.72958) +[ INFO] [1732707743.335499426]: wait-interpolation debug: start +[ INFO] [1732707744.354520044]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.06505) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.06505) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.06505) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.06505) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.06505) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.06505) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.06505) violate max-angle(-5.72958) +[ INFO] [1732707744.366554349]: wait-interpolation debug: start +[ INFO] [1732707745.375057597]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.08499) violate max-angle(-5.72958) +t +2.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(-5.72958) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +[ INFO] [1732707810.453381121]: wait-interpolation debug: start +[ INFO] [1732707811.459139841]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +[ INFO] [1732707811.473578570]: wait-interpolation debug: start +[ INFO] [1732707812.483626484]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12986) violate max-angle(-5.72958) +[ INFO] [1732707812.491995110]: wait-interpolation debug: start +[ INFO] [1732707813.505161832]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12737) violate max-angle(-5.72958) +t +3.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.11989) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.11989) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.11989) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.11989) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.11989) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.11989) violate max-angle(-5.72958) +[ INFO] [1732707841.244457442]: wait-interpolation debug: start +[ INFO] [1732707842.257130351]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12238) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12238) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12238) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12238) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12238) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12238) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12238) violate max-angle(-5.72958) +[ INFO] [1732707842.272871936]: wait-interpolation debug: start +[ INFO] [1732707843.305809811]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.14981) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.14981) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.14981) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.14981) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.14981) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.14981) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.14981) violate max-angle(-5.72958) +[ INFO] [1732707843.314797683]: wait-interpolation debug: start +[ INFO] [1732707844.326204536]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.15728) violate max-angle(-5.72958) +t +4.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +[ WARN] [1732707873.422799543]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +[ WARN] [1732707873.425223518]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +t +5.irteusgl$ load "pingpong.l" +[ERROR] [1732707876.028249782]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707876.028670876]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707876.028762863]: expected goal id 1732707873429079059_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_11 +[ WARN] [1732707876.028817245]: received goal id 1732707873413885671_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_9 +[ERROR] [1732707876.030359361]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707876.030537932]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707876.030590208]: expected goal id 1732707873429432346_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_11 +[ WARN] [1732707876.030748561]: received goal id 1732707873414263721_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_9 +[ERROR] [1732707876.032521642]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707876.032693916]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707876.032759401]: expected goal id 1732707873429702276_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_11 +[ WARN] [1732707876.032834180]: received goal id 1732707873414569754_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_9 +[ERROR] [1732707876.036808422]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707876.036983347]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707876.037020922]: expected goal id 1732707873429986685_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_11 +[ WARN] [1732707876.037080137]: received goal id 1732707873414776809_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_9 +[ERROR] [1732707876.045830334]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707876.045942077]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707876.045998992]: expected goal id 1732707873429079059_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_11 +[ WARN] [1732707876.046057074]: received goal id 1732707873420707965_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_10 +[ERROR] [1732707876.046368257]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707876.046458282]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707876.046506447]: expected goal id 1732707873429702276_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_11 +[ WARN] [1732707876.046545467]: received goal id 1732707873421381036_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_10 +[ERROR] [1732707876.046848122]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707876.046950635]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707876.046988882]: expected goal id 1732707873429432346_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_11 +[ WARN] [1732707876.047035376]: received goal id 1732707873421063669_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_10 +[ERROR] [1732707876.048353753]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707876.048436220]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707876.048460368]: expected goal id 1732707873429986685_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_11 +[ WARN] [1732707876.048482733]: received goal id 1732707873421623302_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_10 +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +[ WARN] [1732707876.094061009]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732707876.094406220]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732707876.094643211]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732707876.095320977]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +[ERROR] [1732707876.098336864]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707876.098398167]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707876.098416343]: expected goal id 1732707876089124373_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_13 +[ WARN] [1732707876.098431718]: received goal id 1732707876078464214_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_12 +[ERROR] [1732707876.099145249]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707876.099218219]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707876.099234964]: expected goal id 1732707876089924390_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_13 +[ WARN] [1732707876.099250672]: received goal id 1732707876078886410_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_12 +[ERROR] [1732707876.099815144]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707876.099867850]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707876.099885331]: expected goal id 1732707876090268390_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_13 +[ WARN] [1732707876.099901396]: received goal id 1732707876079274646_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_12 +[ERROR] [1732707876.100611720]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707876.100670376]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707876.100687965]: expected goal id 1732707876090513136_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_13 +[ WARN] [1732707876.100703762]: received goal id 1732707876079760006_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_12 +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +[ WARN] [1732707876.109713885]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732707876.112784941]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ERROR] [1732707876.115630883]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707876.115733189]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707876.115764017]: expected goal id 1732707876108292421_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_14 +[ WARN] [1732707876.115792324]: received goal id 1732707876089124373_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_13 +[ERROR] [1732707876.118302942]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707876.118410239]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707876.118438881]: expected goal id 1732707876111107803_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_14 +[ WARN] [1732707876.118465291]: received goal id 1732707876089924390_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_13 +t +6.irteusgl$ load "pingpong.l" +[ERROR] [1732707888.656514142]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707888.656647409]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707888.656703773]: expected goal id 1732707876116828875_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_14 +[ WARN] [1732707888.656761637]: received goal id 1732707876090268390_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_13 +[ERROR] [1732707888.657698079]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707888.657798199]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707888.657844494]: expected goal id 1732707876119307255_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_14 +[ WARN] [1732707888.657880011]: received goal id 1732707876090513136_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_13 +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +[ WARN] [1732707888.708813698]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ERROR] [1732707888.709290925]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707888.709345125]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707888.709364260]: expected goal id 1732707888703614775_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_16 +[ WARN] [1732707888.709381086]: received goal id 1732707888687304944_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_15 +[ WARN] [1732707888.710011778]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732707888.710259130]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ERROR] [1732707888.710338795]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707888.710401663]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707888.710420860]: expected goal id 1732707888703972520_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_16 +[ WARN] [1732707888.710439180]: received goal id 1732707888688487834_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_15 +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +[ERROR] [1732707888.711788588]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707888.711849565]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707888.711867679]: expected goal id 1732707888704254243_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_16 +[ WARN] [1732707888.711884191]: received goal id 1732707888691019663_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_15 +[ERROR] [1732707888.715124597]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707888.715188305]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707888.715213518]: expected goal id 1732707888704464166_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_16 +[ WARN] [1732707888.715245355]: received goal id 1732707888692427193_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_15 +[ WARN] [1732707888.717094625]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +t +7.irteusgl$ load "pingpong.l" +[ERROR] [1732707902.298920662]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707902.299059266]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707902.299101635]: expected goal id 1732707888714651268_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_17 +[ WARN] [1732707902.299143331]: received goal id 1732707888703614775_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_16 +[ERROR] [1732707902.300490687]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707902.300600229]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707902.300624930]: expected goal id 1732707888716151357_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_17 +[ WARN] [1732707902.300647082]: received goal id 1732707888703972520_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_16 +[ERROR] [1732707902.302836005]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707902.302892263]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707902.302917270]: expected goal id 1732707888717147062_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_17 +[ WARN] [1732707902.302935610]: received goal id 1732707888704254243_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_16 +[ERROR] [1732707902.303130668]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707902.303169453]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707902.303184879]: expected goal id 1732707888717895577_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_17 +[ WARN] [1732707902.303199010]: received goal id 1732707888704464166_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_16 +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12488) violate max-angle(-5.72958) +[ INFO] [1732707902.329879314]: wait-interpolation debug: start +[ INFO] [1732707903.343949916]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12737) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12737) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12737) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12737) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12737) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12737) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12737) violate max-angle(-5.72958) +[ INFO] [1732707903.354361772]: wait-interpolation debug: start +[ INFO] [1732707904.367733191]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.15479) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.15479) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.15479) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.15479) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.15479) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.15479) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.15479) violate max-angle(-5.72958) +[ INFO] [1732707904.385128885]: wait-interpolation debug: start +[ INFO] [1732707905.403685439]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.15978) violate max-angle(-5.72958) +t +8.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12238) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12238) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12238) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12238) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12238) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.12238) violate max-angle(-5.72958) +[ INFO] [1732707945.558491068]: wait-interpolation debug: start +[ INFO] [1732707946.577597367]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.14482) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.14482) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.14731) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.14731) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.14731) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.14731) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.14731) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.14731) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.14731) violate max-angle(-5.72958) +[ INFO] [1732707946.595920839]: wait-interpolation debug: start +[ INFO] [1732707947.605676930]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.47139) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.47139) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.47139) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.47139) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.47139) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.47139) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.47139) violate max-angle(-5.72958) +[ INFO] [1732707947.615379022]: wait-interpolation debug: start +[ INFO] [1732707948.627857417]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.64838) violate max-angle(-5.72958) +t +9.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +[ INFO] [1732707993.519543964]: wait-interpolation debug: start +[ WARN] [1732707993.530944548]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732707993.531451346]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732707993.532319125]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ERROR] [1732707993.534144511]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707993.534241508]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707993.534270633]: expected goal id 1732707993517599333_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_25 +[ WARN] [1732707993.534287353]: received goal id 1732707993499349777_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_24 +[ERROR] [1732707993.534755608]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707993.534864060]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707993.534886725]: expected goal id 1732707993518468297_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_25 +[ WARN] [1732707993.534919031]: received goal id 1732707993503339276_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_24 +[ERROR] [1732707993.535403729]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707993.535449789]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707993.535472186]: expected goal id 1732707993519022362_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_25 +[ WARN] [1732707993.535507498]: received goal id 1732707993503866378_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_24 +[ERROR] [1732707993.536064938]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732707993.536163140]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732707993.536196973]: expected goal id 1732707993519363079_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_25 +[ WARN] [1732707993.536230651]: received goal id 1732707993504126612_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_24 +[ERROR] [1732707995.366795477]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732707995.366848455]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732707995.367320511]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72317) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +t +10.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +[ WARN] [1732708003.709315265]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732708003.711801551]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ERROR] [1732708003.713675501]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732708003.713725064]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732708003.713742378]: expected goal id 1732708003707588755_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_27 +[ WARN] [1732708003.713757139]: received goal id 1732708003695013835_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_26 +[ INFO] [1732708003.714340233]: wait-interpolation debug: start +[ERROR] [1732708003.714432982]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732708003.714477700]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732708003.714494432]: expected goal id 1732708003710373657_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_27 +[ WARN] [1732708003.714510697]: received goal id 1732708003695531012_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_26 +[ERROR] [1732708003.724786976]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732708003.724912867]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732708003.724947533]: expected goal id 1732708003713208707_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_27 +[ WARN] [1732708003.724978934]: received goal id 1732708003696308816_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_26 +[ERROR] [1732708003.726864413]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732708003.726969098]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732708003.727007545]: expected goal id 1732708003714171620_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_27 +[ WARN] [1732708003.727037872]: received goal id 1732708003696804003_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_26 +[ERROR] [1732708005.027605681]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732708005.027650763]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732708005.629599049]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732708005.629646724]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732708005.634241477]: wait-interpolation debug: end +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.64838) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.64838) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.64838) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.64838) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.64838) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.64838) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.64838) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.64838) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.64838) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.64838) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.64838) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.64838) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.64838) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.64838) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.64838) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.63841) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.6409) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.6409) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.6409) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.6409) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.6409) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.6409) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.6409) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.6409) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.6409) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.66583) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.66583) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.66583) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.66583) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.576) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.72067) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +t +11.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +[ WARN] [1732708010.661593626]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ INFO] [1732708010.664422318]: wait-interpolation debug: start +[ERROR] [1732708010.664614758]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732708010.664707146]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732708010.664749448]: expected goal id 1732708010656975415_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_29 +[ WARN] [1732708010.664771949]: received goal id 1732708010645419083_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_28 +[ERROR] [1732708010.665245430]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732708010.665308064]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732708010.665326290]: expected goal id 1732708010658154278_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_29 +[ WARN] [1732708010.665342483]: received goal id 1732708010645880214_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_28 +[ERROR] [1732708010.674722732]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732708010.674797132]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732708010.674816157]: expected goal id 1732708010660436847_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_29 +[ WARN] [1732708010.674834074]: received goal id 1732708010646192257_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_28 +[ERROR] [1732708010.677691890]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732708010.677777138]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732708010.677797166]: expected goal id 1732708010664188470_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_29 +[ WARN] [1732708010.677815118]: received goal id 1732708010646434227_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_28 +[ERROR] [1732708012.775791597]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732708012.775846045]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732708012.776954961]: wait-interpolation debug: end +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68328) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.69076) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +t +12.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +[ WARN] [1732708015.848684606]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732708015.854875858]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732708015.857200098]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732708015.858798169]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732708015.861645640]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ERROR] [1732708015.862337120]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732708015.862438764]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732708015.862471211]: expected goal id 1732708015847359543_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_31 +[ WARN] [1732708015.862502076]: received goal id 1732708015797329419_/pr2_eus_interface_1732707739851283021_85558_l_arm_controller/follow_joint_trajectory_30 +[ WARN] [1732708015.867034965]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ERROR] [1732708015.870132005]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732708015.870232825]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732708015.870271401]: expected goal id 1732708015859521284_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_31 +[ WARN] [1732708015.870299651]: received goal id 1732708015799206936_/pr2_eus_interface_1732707739851283021_85558_r_arm_controller/follow_joint_trajectory_30 +[ INFO] [1732708015.871267322]: wait-interpolation debug: start +[ WARN] [1732708015.873450424]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732708015.873870027]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ERROR] [1732708015.881521253]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732708015.881615714]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732708015.881641538]: expected goal id 1732708015868905621_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_31 +[ WARN] [1732708015.881682753]: received goal id 1732708015802001130_/pr2_eus_interface_1732707739851283021_85558_head_traj_controller/follow_joint_trajectory_30 +[ERROR] [1732708015.882888787]: joint trajectory status: (2 . actionlib_msgs::goalstatus::*preempted*) + +[ WARN] [1732708015.883001290]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732708015.883038598]: expected goal id 1732708015870939104_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_31 +[ WARN] [1732708015.883068757]: received goal id 1732708015803209470_/pr2_eus_interface_1732707739851283021_85558_torso_controller/follow_joint_trajectory_30 +[ERROR] [1732708017.969279925]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732708017.969336324]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732708017.973105239]: wait-interpolation debug: end +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.66832) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.6783) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +t +13.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +[ INFO] [1732708033.652952316]: wait-interpolation debug: start +[ERROR] [1732708035.816983834]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732708035.817028438]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732708035.826810411]: wait-interpolation debug: end +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68827) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.69325) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.69325) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.69325) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.69325) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.69325) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.69325) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.69325) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.69325) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.69325) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.69325) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.69325) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.69325) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.69325) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.69325) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.69325) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.69325) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.70572) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +t +14.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +[ INFO] [1732708041.756115360]: wait-interpolation debug: start +[ERROR] [1732708043.360854417]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732708043.360895613]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732708043.842988966]: wait-interpolation debug: end +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65835) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.66334) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.67331) violate max-angle(-5.72958) +t +15.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.71569) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.71569) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.71569) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.71569) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.71569) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.71569) violate max-angle(-5.72958) +[ INFO] [1732708049.064590309]: wait-interpolation debug: start +[ INFO] [1732708053.058776449]: wait-interpolation debug: end +;; # :joint-angle(75.564) violate max-angle(74.2702) +t +16.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +[ INFO] [1732708061.314667546]: wait-interpolation debug: start +[ INFO] [1732708064.057583077]: wait-interpolation debug: end +;; # :joint-angle(75.564) violate max-angle(74.2702) +t +17.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +[ INFO] [1732708068.718583289]: wait-interpolation debug: start +[ERROR] [1732708070.711910771]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732708070.711971785]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732708070.717060566]: wait-interpolation debug: end +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65337) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.65586) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.66583) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.66583) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.66583) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.66583) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.66583) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.66583) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.66583) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.66583) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.66583) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.66583) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.66583) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.67082) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.6758) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.6758) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.6758) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.6758) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.6758) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.6758) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.6758) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.6758) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.6758) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.6758) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.6758) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.6758) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.6758) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.6758) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +;; # :joint-angle(75.558) violate max-angle(74.2702) +;; # :joint-angle(-5.68577) violate max-angle(-5.72958) +t +18.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +[ INFO] [1732708106.416118695]: wait-interpolation debug: start +[ INFO] [1732708121.933533495]: wait-interpolation debug: end +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +t +19.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +[ INFO] [1732708127.718945179]: wait-interpolation debug: start +[ INFO] [1732708128.730601212]: wait-interpolation debug: end +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +;; # :joint-angle(75.564) violate max-angle(74.2702) +[ INFO] [1732708128.750624819]: wait-interpolation debug: start +[ERROR] [1732708129.159087287]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732708129.159129527]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732708129.783776565]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732708129.783819052]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732708129.789446548]: wait-interpolation debug: end +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.54) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +t +20.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(75.534) violate max-angle(74.2702) +[ INFO] [1732708132.919670949]: wait-interpolation debug: start +[ INFO] [1732708133.929776070]: wait-interpolation debug: end +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69575) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69575) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69575) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69575) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69575) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69575) violate max-angle(-5.72958) +;; # :joint-angle(75.534) violate max-angle(74.2702) +;; # :joint-angle(-5.69575) violate max-angle(-5.72958) +[ INFO] [1732708133.958457576]: wait-interpolation debug: start +[ERROR] [1732708134.965530211]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732708134.965587640]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732708134.966967734]: wait-interpolation debug: end +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70322) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.69824) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.70073) violate max-angle(-5.72958) +t +21.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +[ INFO] [1732708142.429060359]: wait-interpolation debug: start +[ INFO] [1732708143.435187004]: wait-interpolation debug: end +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +[ INFO] [1732708143.445846072]: wait-interpolation debug: start +[ INFO] [1732708145.057517068]: wait-interpolation debug: end +;; # :joint-angle(75.528) violate max-angle(74.2702) +t +22.irteusgl$ (send *ri* :angle-vector-sequence (list r1 r2 r3 r1) (list 500 500 500 1000)) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +(#f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -36.0762 26.7834 -79.1134 -106.885 386.621 -5.72958 91.7235 3.47953 74.2702) #f(232.409 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.0287 20.0704 -75.42 -95.7531 397.257 -5.72958 91.8606 3.52153 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702)) +23.irteusgl$ (send *ri* :angle-vector-sequence (list r1 r2 r3 r1) (list 500 500 500 1000) :min-time 0.01) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; controller-type: :min-time not foundnil +24.irteusgl$ (send *ri* :controller-type) +Call Stack (max depth: 20): + 0: at (send *ri* :controller-type) + 1: at # +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: cannot find method :controller-type in (send *ri* :controller-type) +25.E1-irteusgl$ reset +26.irteusgl$ ( *ri* . :controller-type) +Call Stack (max depth: 20): + 0: at # +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: no such object variable # in # +27.E1-irteusgl$ reset +28.irteusgl$ (*ri* . controller-type) +:default-controller +29.irteusgl$ (send *ri* :angle-vector-sequence (list r1 r2 r3 r1) (list 500 500 500 1000) :default-controller 0.1 :min-time 0.01) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +(#f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -36.0762 26.7834 -79.1134 -106.885 386.621 -5.72958 91.7235 3.47953 74.2702) #f(232.409 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.0287 20.0704 -75.42 -95.7531 397.257 -5.72958 91.8606 3.52153 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702)) +30.irteusgl$ (send *ri* :angle-vector-sequence (list r1 r2 r3 r1) (list 500 500 500 1000) :default-controller 0.1 :min-time 0.001) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +(#f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -36.0762 26.7834 -79.1134 -106.885 386.621 -5.72958 91.7235 3.47953 74.2702) #f(232.409 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.0287 20.0704 -75.42 -95.7531 397.257 -5.72958 91.8606 3.52153 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702)) +31.irteusgl$ (send *ri* :angle-vector-sequence (list r1 r2 r3 r1) (list 500 500 500 1000) :default-controller 0.001 :min-time 0.001) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72067) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72067) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72067) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72067) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72067) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72067) violate max-angle(-5.72958) +(#f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -36.0762 26.7834 -79.1134 -106.885 386.621 -5.72958 91.7235 3.47953 74.2702) #f(232.409 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.0287 20.0704 -75.42 -95.7531 397.257 -5.72958 91.8606 3.52153 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702)) +32.irteusgl$ (send *ri* :angle-vector-sequence (list r1 r2 r3 r1) (list 200 200 500 1000) :default-controller 0.001 :min-time 0.001) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +(#f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -36.0762 26.7834 -79.1134 -106.885 386.621 -5.72958 91.7235 3.47953 74.2702) #f(232.409 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.0287 20.0704 -75.42 -95.7531 397.257 -5.72958 91.8606 3.52153 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702)) +33.irteusgl$ (send *ri* :angle-vector-sequence (list r1 r2 r3 r1) (list 200 200 500 1000) :default-controller 0.001 :min-time 0.0001) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.7132) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.71569) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.71569) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.71569) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.71569) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.71569) violate max-angle(-5.72958) +(#f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -36.0762 26.7834 -79.1134 -106.885 386.621 -5.72958 91.7235 3.47953 74.2702) #f(232.409 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.0287 20.0704 -75.42 -95.7531 397.257 -5.72958 91.8606 3.52153 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702)) +34.irteusgl$ (send *ri* :angle-vector-sequence (list r1 r2 r3 r1) (list 200 200 500 1000) :default-controller 0.001 :min-time 0.0001 :minjerk-interpolation t) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72566) violate max-angle(-5.72958) +(#f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -36.0762 26.7834 -79.1134 -106.885 386.621 -5.72958 91.7235 3.47953 74.2702) #f(232.409 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.0287 20.0704 -75.42 -95.7531 397.257 -5.72958 91.8606 3.52153 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702)) +35.irteusgl$ (send *ri* :angle-vector-sequence (list r1 r2 r3 r1) (list 200 200 500 1000) :default-controller 0.001 :min-time 0.0001 :minjerk-interpolation t) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.71818) violate max-angle(-5.72958) +(#f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -36.0762 26.7834 -79.1134 -106.885 386.621 -5.72958 91.7235 3.47953 74.2702) #f(232.409 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.0287 20.0704 -75.42 -95.7531 397.257 -5.72958 91.8606 3.52153 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702)) +36.irteusgl$ (send *ri* :angle-vector-sequence (list r1 r2 r3 r1) (list 200 200 500 1000) :default-controller 0.001 :min-time 0.0001 :minjerk-interpolation t) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) + +(#f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -36.0762 26.7834 -79.1134 -106.885 386.621 -5.72958 91.7235 3.47953 74.2702) #f(232.409 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.0287 20.0704 -75.42 -95.7531 397.257 -5.72958 91.8606 3.52153 74.2702) #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702)) +37.irteusgl$ nil +37.irteusgl$ load "pingpong.l" +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +[ INFO] [1732708472.161200304]: wait-interpolation debug: start +[ INFO] [1732708473.169482487]: wait-interpolation debug: end +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(-5.72815) violate max-angle(-5.72958) +[ INFO] [1732708473.179155735]: wait-interpolation debug: start +[ INFO] [1732708474.790581584]: wait-interpolation debug: end +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +;; # :joint-angle(75.528) violate max-angle(74.2702) +t +38.irteusgl$ \ No newline at end of file diff --git a/jsk_2024_10_semi/sample/okadasensei_shell_nov27_2.txt b/jsk_2024_10_semi/sample/okadasensei_shell_nov27_2.txt new file mode 100644 index 000000000..0c70aca95 --- /dev/null +++ b/jsk_2024_10_semi/sample/okadasensei_shell_nov27_2.txt @@ -0,0 +1,67686 @@ +mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ source ~/semi_ws/devel/setup.bash +mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rosseti@ +rosseti@: command not found +mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rossetip +set ROS_IP and ROS_HOSTNAME to 133.11.216.48 +mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rossetmaster pr1040 +set ROS_MASTER_URI to http://pr1040:11311 +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ roseus +configuring by "/opt/ros/noetic/share/euslisp/jskeus/eus//lib/eusrt.l" +;; readmacro ;; object ;; packsym ;; common ;; constants ;; stream ;; string ;; loader ;; pprint ;; process ;; hashtab ;; array ;; mathtran ;; eusdebug ;; eusforeign ;; extnum ;; coordinates ;; tty ;; history ;; toplevel ;; trans ;; comp ;; builtins ;; par ;; intersection ;; geoclasses ;; geopack ;; geobody ;; primt ;; compose ;; polygon ;; viewing ;; viewport ;; viewsurface ;; hid ;; shadow ;; bodyrel ;; dda ;; helpsub ;; eushelp ;; xforeign ;; Xdecl ;; Xgraphics ;; Xcolor ;; Xeus ;; Xevent ;; Xpanel ;; Xitem ;; Xtext ;; Xmenu ;; Xscroll ;; Xcanvas ;; Xtop ;; Xapplwin +connected to Xserver DISPLAY=:0 +X events are being asynchronously monitored. +;; pixword ;; RGBHLS ;; convolve ;; piximage ;; pbmfile ;; image_correlation ;; oglforeign ;; gldecl ;; glconst ;; glforeign ;; gluconst ;; gluforeign ;; glxconst ;; glxforeign ;; eglforeign ;; eglfunc ;; glutil ;; gltexture ;; glprim ;; gleus ;; glview ;; toiv-undefined ;; fstringdouble irtmath irtutil irtc irtgeoc irtgraph gnuplotlib ___time ___pgsql irtgeo euspqp pqp irtscene irtmodel irtdyna irtrobot irtsensor irtbvh irtcollada irtstl irtwrl irtpointcloud eusbullet bullet irtcollision irtx eusjpeg euspng png irtimage irtglrgb +;; extending gcstack 0x562238d9f680[16374] --> 0x56223922fc90[32748] top=3d4b +irtgl irtglc irtviewer +EusLisp 9.29( 1.2.5) for Linux64 created on ip-10-0-1-5(Tue Jun 20 10:34:21 PST 2023) +roseus ;; loading roseus("1.7.5") on euslisp((9.29 ip-10-0-1-5 Tue Jun 20 10:34:21 PST 2023 1.2.5)) +eustf roseus_c_util 1.irteusgl$ load "main.l" +;; roseus_resume is disabled. + +;; extending gcstack 0x56223922fc90[32738] --> 0x56223ad4d6e0[65476] top=7ed2 +;; # :joint-angle(-22.098) violate min-angle(-21.2682) +;; # :joint-angle(-122.247) violate min-angle(-121.542) +;; (make-irtviewer) executed +;; # :joint-angle(-22.098) violate min-angle(-21.2682) +;; # :joint-angle(-122.313) violate min-angle(-121.542) +;; # :joint-angle(-22.098) violate min-angle(-21.2682) +;; # :joint-angle(-122.313) violate min-angle(-121.542) +;; # :joint-angle(-22.098) violate min-angle(-21.2682) +;; # :joint-angle(-122.313) violate min-angle(-121.542) +;; # :joint-angle(-22.098) violate min-angle(-21.2682) +;; # :joint-angle(-122.313) violate min-angle(-121.542) +;; # :joint-angle(-22.098) violate min-angle(-21.2682) +;; # :joint-angle(-122.313) violate min-angle(-121.542) +;; # :joint-angle(-22.098) violate min-angle(-21.2682) +;; # :joint-angle(-122.313) violate min-angle(-121.542) +;; # :joint-angle(-22.098) violate min-angle(-21.2682) +;; # :joint-angle(-122.313) violate min-angle(-121.542) +;; # :joint-angle(-122.222) violate min-angle(-121.542) +;; # :joint-angle(-22.374) violate min-angle(-21.2682) +[ WARN] [1732679518.648006329]: continuous joint (l_wrist_roll_joint) moves 181.048 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(-22.098) violate min-angle(-21.2682) +;; # :joint-angle(-122.313) violate min-angle(-121.542) +;; # :joint-angle(-22.098) violate min-angle(-21.2682) +;; # :joint-angle(-122.313) violate min-angle(-121.542) +;; # :joint-angle(-22.098) violate min-angle(-21.2682) +;; # :joint-angle(-122.313) violate min-angle(-121.542) +;; # :joint-angle(-22.098) violate min-angle(-21.2682) +;; # :joint-angle(-122.313) violate min-angle(-121.542) +;; # :joint-angle(-22.098) violate min-angle(-21.2682) +;; # :joint-angle(-122.313) violate min-angle(-121.542) +;; # :joint-angle(-122.222) violate min-angle(-121.542) +;; # :joint-angle(-22.374) violate min-angle(-21.2682) +[ WARN] [1732679518.657880744]: continuous joint (l_wrist_roll_joint) moves 181.048 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732679518.657963047]: original trajectory command : +[ WARN] [1732679518.657987455]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732679518.658012099]: current angle vector : #f(210.125 -0.414716 68.738 106.189 -75.6383 -91.7774 -6.30247 -1.04803 -26.9001 65.1716 -122.713 -121.542 -130.668 -101.971 72.51 6.23139 -21.2682) +[ WARN] [1732679518.658027148]: new trajectory command : dvi = 2 +[ WARN] [1732679518.658055988]: : #f(130.062 29.7926 71.369 88.0946 -97.8191 -35.8887 -18.1512 89.476 -43.45 69.5858 -96.3567 -120.771 -75.3339 -65.9853 126.255 3.11569 -10.6341) 500 +[ WARN] [1732679518.658078815]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732679518.658093811]: new trajectory command : +[ WARN] [1732679518.658125369]: : (#f(130.062 29.7926 71.369 88.0946 -97.8191 -35.8887 -18.1512 89.476 -43.45 69.5858 -96.3567 -120.771 -75.3339 -65.9853 126.255 3.11569 -10.6341) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +;; # :joint-angle(-22.098) violate min-angle(-21.2682) +;; # :joint-angle(-122.313) violate min-angle(-121.542) +[ INFO] [1732679518.663385520]: wait-interpolation debug: start +[ERROR] [1732679531.082612266]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679531.082661685]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679531.083189855]: wait-interpolation debug: end +[ INFO] [1732679534.945214054]: wait-interpolation debug: start +[ERROR] [1732679536.556733579]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679536.556862244]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679536.576103553]: wait-interpolation debug: end +[ INFO] [1732679542.630818242]: wait-interpolation debug: start +[ INFO] [1732679542.636282325]: wait-interpolation debug: end +[ INFO] [1732679552.431040137]: wait-interpolation debug: start +[ INFO] [1732679552.433888541]: wait-interpolation debug: end +[ INFO] [1732679559.012689779]: wait-interpolation debug: start +[ INFO] [1732679560.016193529]: wait-interpolation debug: end +[ INFO] [1732679560.087337941]: wait-interpolation debug: start +[ERROR] [1732679561.686044619]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679561.686111143]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679561.689154284]: wait-interpolation debug: end +;; # :joint-angle(88.0116) violate max-angle(88.0) +;; # :joint-angle(88.0116) violate max-angle(88.0) +;; # :joint-angle(88.0116) violate max-angle(88.0) +;; # :joint-angle(88.0116) violate max-angle(88.0) +;; # :joint-angle(88.0116) violate max-angle(88.0) +;; # :joint-angle(88.0116) violate max-angle(88.0) +;; # :joint-angle(88.0116) violate max-angle(88.0) +;; # :joint-angle(88.0116) violate max-angle(88.0) +;; # :joint-angle(88.0116) violate max-angle(88.0) +;; # :joint-angle(88.0116) violate max-angle(88.0) +;; # :joint-angle(88.0116) violate max-angle(88.0) +;; # :joint-angle(88.0116) violate max-angle(88.0) +;; # :joint-angle(88.0116) violate max-angle(88.0) +;; # :joint-angle(88.0116) violate max-angle(88.0) +;; # :joint-angle(88.0116) violate max-angle(88.0) +;; # :joint-angle(88.0116) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0603) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0855) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0932) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0885) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +;; # :joint-angle(88.0727) violate max-angle(88.0) +[ INFO] [1732679562.549724953]: wait-interpolation debug: start +[ERROR] [1732679563.545611953]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679563.545655501]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732679564.150669169]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679564.150713728]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732679564.151073568]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679564.151093515]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679564.153472852]: wait-interpolation debug: end +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3539) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3681) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3634) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(32.3586) violate max-angle(32.3493) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +[ INFO] [1732679564.337737483]: wait-interpolation debug: start +[ INFO] [1732679565.345129527]: wait-interpolation debug: end +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +[ INFO] [1732679565.378366062]: wait-interpolation debug: start +[ INFO] [1732679566.378516359]: wait-interpolation debug: end +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +[ INFO] [1732679566.418232112]: wait-interpolation debug: start +[ INFO] [1732679567.422604034]: wait-interpolation debug: end +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +[ INFO] [1732679567.458185397]: wait-interpolation debug: start +[ INFO] [1732679568.455753095]: wait-interpolation debug: end +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +[ INFO] [1732679568.489512351]: wait-interpolation debug: start +[ INFO] [1732679569.495008978]: wait-interpolation debug: end +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +[ INFO] [1732679569.567555057]: wait-interpolation debug: start +[ INFO] [1732679567.422604034]: wait-interpolation debug: end C-c C-cinterrupt2.B1-irteusgl$ +nil +2.B1-irteusgl$ (send *ri* :stop-grasp) +(t t) +3.B1-irteusgl$ (setq current-coords (send (send *desk* :get :left-coords) :copy-worldcoords)) +(setq new-coords (send current-coords :translate (float-vector 0 100 50))) +(send *pr2* :larm :inverse-kinematics new-coords :rotation-axis :x) +(send *pr2* :larm :end-coords :assoc *needle*) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +# +4.B1-irteusgl$ # +5.B1-irteusgl$ nil +5.B1-irteusgl$ #f(50.0 24.8798 -20.2479 95.1785 -90.9951 162.261 -64.3744 239.495 32.3353 21.6722 34.6134 -87.3213 149.405 -84.3382 72.8274 0.0 0.0) +6.B1-irteusgl$ nil +7.B1-irteusgl$ ;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +;; # :joint-angle(88.0356) violate max-angle(88.0) +#f(50.0 24.8798 -20.2479 95.1785 -90.9951 162.261 -64.3744 239.495 32.3353 21.6722 34.6134 -87.3213 149.405 -84.3382 72.8274 0.0 0.0) +8.B1-irteusgl$ [ INFO] [1732679748.970562263]: wait-interpolation debug: start +[ INFO] [1732679749.974391822]: wait-interpolation debug: end +;; # :joint-angle(88.0356) violate max-angle(88.0) +(nil nil nil nil) +9.B1-irteusgl$ 1 +10.B1-irteusgl$ load "main.l" +[ INFO] [1732679776.593720121]: wait-interpolation debug: start +[ERROR] [1732679778.193909936]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679778.193961780]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732679778.194694926]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679778.194742983]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679778.203575649]: wait-interpolation debug: end +[ INFO] [1732679779.136016876]: wait-interpolation debug: start +[ERROR] [1732679780.735070000]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679780.735116444]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679780.738849930]: wait-interpolation debug: end +[ INFO] [1732679786.925616468]: wait-interpolation debug: start +[ INFO] [1732679786.926054282]: wait-interpolation debug: end +[ INFO] [1732679796.755660509]: wait-interpolation debug: start +[ INFO] [1732679796.757390323]: wait-interpolation debug: end +[ INFO] [1732679803.281649593]: wait-interpolation debug: start +[ INFO] [1732679804.321966482]: wait-interpolation debug: end +[ INFO] [1732679804.361126288]: wait-interpolation debug: start +[ INFO] [1732679805.501729864]: wait-interpolation debug: end +[ INFO] [1732679805.566526153]: wait-interpolation debug: start +[ERROR] [1732679807.163913444]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679807.163983252]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679807.168249020]: wait-interpolation debug: end +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.095) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0923) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +[ INFO] [1732679808.214267367]: wait-interpolation debug: start +[ INFO] [1732679809.215005172]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732679809.297210264]: wait-interpolation debug: start +[ INFO] [1732679810.307612260]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732679810.351465139]: wait-interpolation debug: start +[ INFO] [1732679811.354900836]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732679811.392911196]: wait-interpolation debug: start +[ INFO] [1732679812.396021799]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732679812.433663481]: wait-interpolation debug: start +[ INFO] [1732679813.433996809]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732679813.477224524]: wait-interpolation debug: start +[ INFO] [1732679814.481473528]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732679814.518329258]: wait-interpolation debug: start +[ INFO] [1732679815.524357107]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732679815.566797371]: wait-interpolation debug: start +[ INFO] [1732679816.568068985]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732679816.607845205]: wait-interpolation debug: start +[ INFO] [1732679817.608851875]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732679817.648397116]: wait-interpolation debug: start +[ERROR] [1732679819.246627738]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679819.246692168]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679819.250742207]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732679821.417221441]: wait-interpolation debug: start +[ INFO] [1732679821.424302583]: wait-interpolation debug: end +[ INFO] [1732679824.259956801]: wait-interpolation debug: start +[ INFO] [1732679824.260299728]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732679824.311515621]: wait-interpolation debug: start +[ INFO] [1732679825.317324829]: wait-interpolation debug: end +[ INFO] [1732679825.408921707]: wait-interpolation debug: start +[ERROR] [1732679831.850724990]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679831.850771622]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679831.852950898]: wait-interpolation debug: end +[ INFO] [1732679834.116725245]: wait-interpolation debug: start +[ERROR] [1732679835.716891802]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679835.716937416]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732679835.718924367]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679835.718957970]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679835.723606647]: wait-interpolation debug: end +[ INFO] [1732679837.570328730]: wait-interpolation debug: start +[ INFO] [1732679837.570553303]: wait-interpolation debug: end +[ INFO] [1732679838.579667772]: wait-interpolation debug: start +[ INFO] [1732679838.581489071]: wait-interpolation debug: end +;; # :joint-angle(88.0389) violate max-angle(88.0) +;; # :joint-angle(-20.2663) violate min-angle(-20.2598) +;; # :joint-angle(88.0389) violate max-angle(88.0) +;; # :joint-angle(-20.2663) violate min-angle(-20.2598) +;; # :joint-angle(88.0389) violate max-angle(88.0) +;; # :joint-angle(-20.2663) violate min-angle(-20.2598) +;; # :joint-angle(88.0389) violate max-angle(88.0) +;; # :joint-angle(-20.2663) violate min-angle(-20.2598) +;; # :joint-angle(88.0389) violate max-angle(88.0) +;; # :joint-angle(-20.2663) violate min-angle(-20.2598) +;; # :joint-angle(88.0389) violate max-angle(88.0) +;; # :joint-angle(-20.2663) violate min-angle(-20.2598) +[ INFO] [1732679844.035711510]: wait-interpolation debug: start +[ERROR] [1732679845.630529937]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679845.630583815]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732679845.631979002]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679845.632034777]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679845.638419256]: wait-interpolation debug: end +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(-20.2711) violate min-angle(-20.2598) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(-20.2856) violate min-angle(-20.2598) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(-20.2856) violate min-angle(-20.2598) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(-20.2856) violate min-angle(-20.2598) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(-20.2856) violate min-angle(-20.2598) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(-20.2856) violate min-angle(-20.2598) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(-20.2856) violate min-angle(-20.2598) +[ INFO] [1732679845.980690231]: wait-interpolation debug: start +[ INFO] [1732679846.978401940]: wait-interpolation debug: end +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +[ INFO] [1732679847.016767960]: wait-interpolation debug: start +[ INFO] [1732679848.024682283]: wait-interpolation debug: end +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +[ INFO] [1732679848.061764594]: wait-interpolation debug: start +[ INFO] [1732679849.064554931]: wait-interpolation debug: end +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +[ INFO] [1732679849.098050386]: wait-interpolation debug: start +[ INFO] [1732679850.108787612]: wait-interpolation debug: end +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +[ INFO] [1732679850.177531260]: wait-interpolation debug: start +[ INFO] [1732679851.187629740]: wait-interpolation debug: end +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +[ INFO] [1732679851.227797219]: wait-interpolation debug: start +[ INFO] [1732679852.224808229]: wait-interpolation debug: end +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +[ INFO] [1732679852.267388273]: wait-interpolation debug: start +[ INFO] [1732679853.267684561]: wait-interpolation debug: end +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +[ INFO] [1732679853.317212638]: wait-interpolation debug: start +[ INFO] [1732679854.323069355]: wait-interpolation debug: end +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +[ INFO] [1732679854.369581902]: wait-interpolation debug: start +[ERROR] [1732679855.968838510]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679855.968903857]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679855.976423644]: wait-interpolation debug: end +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +;; # :joint-angle(88.0327) violate max-angle(88.0) +[ INFO] [1732679856.015289826]: wait-interpolation debug: start +[ERROR] [1732679857.615497626]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679857.615539860]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679857.621139182]: wait-interpolation debug: end +;; # :joint-angle(88.0327) violate max-angle(88.0) +[ INFO] [1732679859.822042502]: wait-interpolation debug: start +[ INFO] [1732679859.824115471]: wait-interpolation debug: end +[ INFO] [1732679862.767818538]: wait-interpolation debug: start +[ INFO] [1732679862.768008663]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732679862.806844111]: wait-interpolation debug: start +[ INFO] [1732679863.807138655]: wait-interpolation debug: end +[ INFO] [1732679863.917478307]: wait-interpolation debug: start +[ERROR] [1732679867.230098808]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679867.230179306]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679867.239321722]: wait-interpolation debug: end +[ INFO] [1732679868.446663674]: wait-interpolation debug: start +[ERROR] [1732679870.043369220]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679870.043441190]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679870.048070703]: wait-interpolation debug: end +[ INFO] [1732679871.947144407]: wait-interpolation debug: start +[ INFO] [1732679871.947439499]: wait-interpolation debug: end +[ INFO] [1732679872.974325962]: wait-interpolation debug: start +[ INFO] [1732679872.988619073]: wait-interpolation debug: end +;; # :joint-angle(88.0273) violate max-angle(88.0) +;; # :joint-angle(88.0273) violate max-angle(88.0) +;; # :joint-angle(88.0273) violate max-angle(88.0) +;; # :joint-angle(88.0273) violate max-angle(88.0) +;; # :joint-angle(88.0273) violate max-angle(88.0) +;; # :joint-angle(88.0273) violate max-angle(88.0) +[ INFO] [1732679878.402002747]: wait-interpolation debug: start +[ERROR] [1732679880.001458515]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679880.001512628]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732679880.001886324]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679880.001920605]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679880.005478620]: wait-interpolation debug: end +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0258) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +[ INFO] [1732679880.653057789]: wait-interpolation debug: start +[ INFO] [1732679881.656925275]: wait-interpolation debug: end +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +[ INFO] [1732679881.705370879]: wait-interpolation debug: start +[ INFO] [1732679882.706775457]: wait-interpolation debug: end +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +[ INFO] [1732679882.745596891]: wait-interpolation debug: start +[ INFO] [1732679883.745640421]: wait-interpolation debug: end +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +[ INFO] [1732679883.782383528]: wait-interpolation debug: start +[ INFO] [1732679884.785208615]: wait-interpolation debug: end +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +[ INFO] [1732679884.821662879]: wait-interpolation debug: start +[ INFO] [1732679885.824067209]: wait-interpolation debug: end +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +[ INFO] [1732679885.861345760]: wait-interpolation debug: start +[ INFO] [1732679886.861423919]: wait-interpolation debug: end +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +[ INFO] [1732679886.903894701]: wait-interpolation debug: start +[ INFO] [1732679887.908195182]: wait-interpolation debug: end +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +[ INFO] [1732679887.947095133]: wait-interpolation debug: start +[ INFO] [1732679888.947847942]: wait-interpolation debug: end +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +[ INFO] [1732679888.984525118]: wait-interpolation debug: start +[ERROR] [1732679890.584519262]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679890.584560473]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679890.587334230]: wait-interpolation debug: end +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +[ INFO] [1732679890.626802610]: wait-interpolation debug: start +[ERROR] [1732679892.226185174]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679892.226321981]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679892.239205547]: wait-interpolation debug: end +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +;; # :joint-angle(88.0255) violate max-angle(88.0) +[ INFO] [1732679894.480943516]: wait-interpolation debug: start +[ INFO] [1732679894.485369305]: wait-interpolation debug: end +[ INFO] [1732679897.331208906]: wait-interpolation debug: start +[ INFO] [1732679897.373016641]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732679897.411239482]: wait-interpolation debug: start +[ INFO] [1732679898.416099139]: wait-interpolation debug: end +[ INFO] [1732679898.496029322]: wait-interpolation debug: start +[ERROR] [1732679899.734576567]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679899.734629875]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679899.742461925]: wait-interpolation debug: end +[ INFO] [1732679900.307544900]: wait-interpolation debug: start +[ERROR] [1732679901.901437670]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679901.901484416]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732679901.901888671]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732679901.901909757]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732679901.904944542]: wait-interpolation debug: end + + + C-c C-cinterrupt11.B2-irteusgl$ +nil +11.B2-irteusgl$ C-c C-cinterrupt11.B3-irteusgl$ (exit~ +) +Call Stack (max depth: 20): + 0: at sigint-handler + 1: at sigint-handler + 2: at sigint-handler + 3: at (while (ros::ok) (ros::ros-debug "[~A] :wait-for-result ~A ~A" ros::name-space (ros::simple-goal-states-to-string ros::simple-state) (send ros::comm-state :state)) (send self :spin-once) (if (= ros::simple-state ros::*simple-goal-state-done*) (return)) (if (> ros::timeout 0) (let* ((ros::tm (ros::time- (ros::time-now) ros::start))) (if (> (send ros::tm :to-sec) ros::timeout) (return-from :wait-for-result nil)))) (when ros::return-if-server-down (when (= (ros::get-num-publishers ros::result-topic) 0) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : no publishers found for ~A" ros::name-space ros::result-topic) (return-from :wait-for-result nil)) (when (and ros::status-stamp ros::maximum-status-interval (> (send (ros::time- (ros::time-now) ros::status-stamp) :to-sec) ros::maximum-status-interval)) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : status did not received for 5 seconds" ros::name-space) (return-from :wait-for-result nil))) (ros::sleep)) + 4: at (let ((ros::start (ros::time-now)) (ros::result-topic (format nil "~A/result" ros::name-space))) (ros::ros-debug "[~A] :wait-for-result ~A, timeout=~A" ros::name-space (if ros::goal_id (send ros::goal_id :id)) ros::timeout) (unless ros::goal_id (ros::ros-error "[~A] :wait-for-result (return nil when no goal exists)" ros::name-space) (return-from :wait-for-result nil)) (ros::rate ros::wait-rate) (while (ros::ok) (ros::ros-debug "[~A] :wait-for-result ~A ~A" ros::name-space (ros::simple-goal-states-to-string ros::simple-state) (send ros::comm-state :state)) (send self :spin-once) (if (= ros::simple-state ros::*simple-goal-state-done*) (return)) (if (> ros::timeout 0) (let* ((ros::tm (ros::time- (ros::time-now) ros::start))) (if (> (send ros::tm :to-sec) ros::timeout) (return-from :wait-for-result nil)))) (when ros::return-if-server-down (when (= (ros::get-num-publishers ros::result-topic) 0) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : no publishers found for ~A" ros::name-space ros::result-topic) (return-from :wait-for-result nil)) (when (and ros::status-stamp ros::maximum-status-interval (> (send (ros::time- (ros::time-now) ros::status-stamp) :to-sec) ros::maximum-status-interval)) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : status did not received for 5 seconds" ros::name-space) (return-from :wait-for-result nil))) (ros::sleep)) (ros::ros-debug "[~A] :wait-for-result finished ~A" ros::name-space (ros::goal-status-to-string (send self :get-state))) (if (eq (send self :get-state) actionlib_msgs::goalstatus::*preempted*) (ros::ros-warn "[~A] :wait-for-result finished with preempted status" ros::name-space)) (eq (send self :get-state) actionlib_msgs::goalstatus::*succeeded*)) + 5: at (send-all clients :wait-for-result) + 6: at (send-all clients :wait-for-result) + 7: at (send-all clients :wait-for-result) + 8: at (progn (send-all clients :wait-for-result) (mapcar #'(lambda (res) (or (if ignore-stall nil (send res :stalled)) (send res :reached_goal))) (send-all clients :get-result))) + 9: at (if wait (progn (send-all clients :wait-for-result) (mapcar #'(lambda (res) (or (if ignore-stall nil (send res :stalled)) (send res :reached_goal))) (send-all clients :get-result))) (mapcar #'(lambda (ac) (send ac :spin-once) (not (null (memq (send ac :get-state) (list actionlib_msgs::goalstatus::*pending* actionlib_msgs::goalstatus::*active* actionlib_msgs::goalstatus::*succeeded*))))) clients)) + 10: at (setq result (if wait (progn (send-all clients :wait-for-result) (mapcar #'(lambda (res) (or (if ignore-stall nil (send res :stalled)) (send res :reached_goal))) (send-all clients :get-result))) (mapcar #'(lambda (ac) (send ac :spin-once) (not (null (memq (send ac :get-state) (list actionlib_msgs::goalstatus::*pending* actionlib_msgs::goalstatus::*active* actionlib_msgs::goalstatus::*succeeded*))))) clients))) + 11: at (let* (goal (clients (case arm (:rarm (list r-gripper-action)) (:larm (list l-gripper-action)) (:arms (list r-gripper-action l-gripper-action)) (t (ros::ros-warn "arm[~a] in :move-gripper is invalid type" arm)))) result) (dolist (client clients) (setq goal (instance pr2_controllers_msgs::pr2grippercommandactiongoal :init)) (send goal :goal :command :position pos) (send goal :goal :command :max_effort effort) (send client :send-goal goal)) (setq result (if wait (progn (send-all clients :wait-for-result) (mapcar #'(lambda (res) (or (if ignore-stall nil (send res :stalled)) (send res :reached_goal))) (send-all clients :get-result))) (mapcar #'(lambda (ac) (send ac :spin-once) (not (null (memq (send ac :get-state) (list actionlib_msgs::goalstatus::*pending* actionlib_msgs::goalstatus::*active* actionlib_msgs::goalstatus::*succeeded*))))) clients))) (case arm (:arms result) (t (car result)))) + 12: at (send self :move-gripper arm 0.0 :effort (* 2000 g) :wait wait) + 13: at (send *ri* :start-grasp :larm) + 14: at (while (< i #:dotimes1362995) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (* *traj_len* 0.2) *target-zpos*))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -1 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (* *needle_len* 0.5) 200)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (- 0 (* *needle_len* 0.5)) 200)) :translate #f(-10.0 0.0 0.0)) :rotate pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1) (setq i (1+ i))) + 15: at (let ((i 0) (#:dotimes1362995 5)) (declare (integer i #:dotimes1362995)) (while (< i #:dotimes1362995) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (* *traj_len* 0.2) *target-zpos*))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -1 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (* *needle_len* 0.5) 200)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (- 0 (* *needle_len* 0.5)) 200)) :translate #f(-10.0 0.0 0.0)) :rotate pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1) (setq i (1+ i))) nil) + 16: at (dotimes (i 5) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (* *traj_len* 0.2) *target-zpos*))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -1 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (* *needle_len* 0.5) 200)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (- 0 (* *needle_len* 0.5)) 200)) :translate #f(-10.0 0.0 0.0)) :rotate pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1)) + 17: at (apply #'ros::load-org-for-ros ros::fullname args) + 18: at (apply #'ros::load-org-for-ros ros::fullname args) + 19: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + And more... +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: undefined function exit~ in sigint-handler +12.E4-irteusgl$ (exit) +[ INFO] [1732680008.876761008]: cell* ROSEUS_EXIT(context*, int, cell**) +[ INFO] [1732680008.876880092]: exiting roseus 0 +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rostopic list +/accelerometer/l_gripper_motor +/accelerometer/r_gripper_motor +/amcl/parameter_descriptions +/amcl/parameter_updates +/amcl_pose +/app_scheduler/app_schedules +/audible_warning/output/original_text +/audible_warning/output/text +/audible_warning/parameter_descriptions +/audible_warning/parameter_updates +/audio +/audio_info +/audio_info_raw +/audio_merged_playback +/audio_play/audio +/audio_raw +/base_controller/bl_caster_l_wheel_joint/parameter_descriptions +/base_controller/bl_caster_l_wheel_joint/parameter_updates +/base_controller/bl_caster_r_wheel_joint/parameter_descriptions +/base_controller/bl_caster_r_wheel_joint/parameter_updates +/base_controller/bl_caster_rotation_joint/position_controller/parameter_descriptions +/base_controller/bl_caster_rotation_joint/position_controller/parameter_updates +/base_controller/br_caster_l_wheel_joint/parameter_descriptions +/base_controller/br_caster_l_wheel_joint/parameter_updates +/base_controller/br_caster_r_wheel_joint/parameter_descriptions +/base_controller/br_caster_r_wheel_joint/parameter_updates +/base_controller/br_caster_rotation_joint/position_controller/parameter_descriptions +/base_controller/br_caster_rotation_joint/position_controller/parameter_updates +/base_controller/cmd_vel +/base_controller/command +/base_controller/command_unchecked +/base_controller/fl_caster_l_wheel_joint/parameter_descriptions +/base_controller/fl_caster_l_wheel_joint/parameter_updates +/base_controller/fl_caster_r_wheel_joint/parameter_descriptions +/base_controller/fl_caster_r_wheel_joint/parameter_updates +/base_controller/fl_caster_rotation_joint/position_controller/parameter_descriptions +/base_controller/fl_caster_rotation_joint/position_controller/parameter_updates +/base_controller/follow_joint_trajectory/cancel +/base_controller/follow_joint_trajectory/feedback +/base_controller/follow_joint_trajectory/goal +/base_controller/follow_joint_trajectory/result +/base_controller/follow_joint_trajectory/status +/base_controller/fr_caster_l_wheel_joint/parameter_descriptions +/base_controller/fr_caster_l_wheel_joint/parameter_updates +/base_controller/fr_caster_r_wheel_joint/parameter_descriptions +/base_controller/fr_caster_r_wheel_joint/parameter_updates +/base_controller/fr_caster_rotation_joint/position_controller/parameter_descriptions +/base_controller/fr_caster_rotation_joint/position_controller/parameter_updates +/base_controller/state +/base_hokuyo_node/parameter_descriptions +/base_hokuyo_node/parameter_updates +/base_odometry/odom +/base_odometry/odometer +/base_odometry/state +/base_scan +/base_scan_filtered +/base_scan_filtered/scan +/base_scan_shadow_filtered +/base_scan_throttled +/base_shadow_filter/dark_shadows/parameter_descriptions +/base_shadow_filter/dark_shadows/parameter_updates +/base_shadow_filter/shadows/parameter_descriptions +/base_shadow_filter/shadows/parameter_updates +/battery/server +/battery/server2 +/calibrated +/calibration_status +/camera_synchronizer_node/parameter_descriptions +/camera_synchronizer_node/parameter_updates +/check_room_light/output +/client_count +/cmd_vel_smoother/parameter_descriptions +/cmd_vel_smoother/parameter_updates +/connected_clients +/dashboard_agg +/ddwrt/accesspoint +/diagnostics +/diagnostics_agg +/diagnostics_toplevel_state +/dialog_response +/dialogflow_client/text_action/cancel +/dialogflow_client/text_action/feedback +/dialogflow_client/text_action/goal +/dialogflow_client/text_action/result +/dialogflow_client/text_action/status +/edgetpu_human_pose_estimator/output/class +/edgetpu_human_pose_estimator/output/image +/edgetpu_human_pose_estimator/output/image/compressed +/edgetpu_human_pose_estimator/output/poses +/edgetpu_human_pose_estimator/output/rects +/edgetpu_human_pose_estimator/parameter_descriptions +/edgetpu_human_pose_estimator/parameter_updates +/email +/empty_cloud +/eng2/1f +/eng2/1f_tf +/eng2/2f +/eng2/2f_tf +/eng2/3f +/eng2/3f_tf +/eng2/7f +/eng2/7f_tf +/eng2/8f +/eng2/8f_tf +/google_chat_ros/card_activity +/google_chat_ros/message_activity +/google_chat_ros/send/cancel +/google_chat_ros/send/feedback +/google_chat_ros/send/goal +/google_chat_ros/send/result +/google_chat_ros/send/status +/google_chat_ros/space_activity +/head_camera_trigger/trigger +/head_camera_trigger/waveform +/head_traj_controller/command +/head_traj_controller/command_deadman +/head_traj_controller/command_dummy +/head_traj_controller/follow_joint_trajectory/cancel +/head_traj_controller/follow_joint_trajectory/feedback +/head_traj_controller/follow_joint_trajectory/goal +/head_traj_controller/follow_joint_trajectory/result +/head_traj_controller/follow_joint_trajectory/status +/head_traj_controller/gains/head_pan_joint/parameter_descriptions +/head_traj_controller/gains/head_pan_joint/parameter_updates +/head_traj_controller/gains/head_tilt_joint/parameter_descriptions +/head_traj_controller/gains/head_tilt_joint/parameter_updates +/head_traj_controller/joint_trajectory_action/cancel +/head_traj_controller/joint_trajectory_action/feedback +/head_traj_controller/joint_trajectory_action/goal +/head_traj_controller/joint_trajectory_action/result +/head_traj_controller/joint_trajectory_action/status +/head_traj_controller/mux/selected +/head_traj_controller/point_head_action/cancel +/head_traj_controller/point_head_action/feedback +/head_traj_controller/point_head_action/goal +/head_traj_controller/point_head_action/result +/head_traj_controller/point_head_action/status +/head_traj_controller/state +/head_traj_controller_loose/command +/head_traj_controller_loose/follow_joint_trajectory/cancel +/head_traj_controller_loose/follow_joint_trajectory/feedback +/head_traj_controller_loose/follow_joint_trajectory/goal +/head_traj_controller_loose/follow_joint_trajectory/result +/head_traj_controller_loose/follow_joint_trajectory/status +/head_traj_controller_loose/gains/head_pan_joint/parameter_descriptions +/head_traj_controller_loose/gains/head_pan_joint/parameter_updates +/head_traj_controller_loose/gains/head_tilt_joint/parameter_descriptions +/head_traj_controller_loose/gains/head_tilt_joint/parameter_updates +/head_traj_controller_loose/joint_trajectory_action/cancel +/head_traj_controller_loose/joint_trajectory_action/feedback +/head_traj_controller_loose/joint_trajectory_action/goal +/head_traj_controller_loose/joint_trajectory_action/result +/head_traj_controller_loose/joint_trajectory_action/status +/head_traj_controller_loose/state +/initialpose +/initialpose3d +/input_vel +/input_vel_mux/selected +/is_speeching +/joint_states +/joy +/joy/set_feedback +/joy_org +/joy_org_ds3 +/joy_other +/joy_vel +/kinect_head/depth/camera_info +/kinect_head/depth/disparity +/kinect_head/depth/image +/kinect_head/depth/image/compressed +/kinect_head/depth/image/compressed/parameter_descriptions +/kinect_head/depth/image/compressed/parameter_updates +/kinect_head/depth/image/compressedDepth +/kinect_head/depth/image/compressedDepth/parameter_descriptions +/kinect_head/depth/image/compressedDepth/parameter_updates +/kinect_head/depth/image/theora +/kinect_head/depth/image/theora/parameter_descriptions +/kinect_head/depth/image/theora/parameter_updates +/kinect_head/depth/image/zdepth +/kinect_head/depth/image_raw +/kinect_head/depth/image_raw/compressed +/kinect_head/depth/image_raw/compressed/parameter_descriptions +/kinect_head/depth/image_raw/compressed/parameter_updates +/kinect_head/depth/image_raw/compressedDepth +/kinect_head/depth/image_raw/compressedDepth/parameter_descriptions +/kinect_head/depth/image_raw/compressedDepth/parameter_updates +/kinect_head/depth/image_raw/theora +/kinect_head/depth/image_raw/theora/parameter_descriptions +/kinect_head/depth/image_raw/theora/parameter_updates +/kinect_head/depth/image_raw/zdepth +/kinect_head/depth/image_rect +/kinect_head/depth/image_rect/compressed +/kinect_head/depth/image_rect/compressed/parameter_descriptions +/kinect_head/depth/image_rect/compressed/parameter_updates +/kinect_head/depth/image_rect/compressedDepth +/kinect_head/depth/image_rect/compressedDepth/parameter_descriptions +/kinect_head/depth/image_rect/compressedDepth/parameter_updates +/kinect_head/depth/image_rect/theora +/kinect_head/depth/image_rect/theora/parameter_descriptions +/kinect_head/depth/image_rect/theora/parameter_updates +/kinect_head/depth/image_rect/zdepth +/kinect_head/depth/image_rect_raw +/kinect_head/depth/image_rect_raw/compressed +/kinect_head/depth/image_rect_raw/compressed/parameter_descriptions +/kinect_head/depth/image_rect_raw/compressed/parameter_updates +/kinect_head/depth/image_rect_raw/compressedDepth +/kinect_head/depth/image_rect_raw/compressedDepth/parameter_descriptions +/kinect_head/depth/image_rect_raw/compressedDepth/parameter_updates +/kinect_head/depth/image_rect_raw/theora +/kinect_head/depth/image_rect_raw/theora/parameter_descriptions +/kinect_head/depth/image_rect_raw/theora/parameter_updates +/kinect_head/depth/image_rect_raw/zdepth +/kinect_head/depth/points +/kinect_head/depth_rectify_depth/parameter_descriptions +/kinect_head/depth_rectify_depth/parameter_updates +/kinect_head/depth_registered/camera_info +/kinect_head/depth_registered/disparity +/kinect_head/depth_registered/downsample_cloud_half/input/mask +/kinect_head/depth_registered/downsample_cloud_half/parameter_descriptions +/kinect_head/depth_registered/downsample_cloud_half/parameter_updates +/kinect_head/depth_registered/downsample_cloud_quater/input/mask +/kinect_head/depth_registered/downsample_cloud_quater/parameter_descriptions +/kinect_head/depth_registered/downsample_cloud_quater/parameter_updates +/kinect_head/depth_registered/half/points +/kinect_head/depth_registered/half/throttled/points +/kinect_head/depth_registered/hw_registered/image_rect +/kinect_head/depth_registered/hw_registered/image_rect/compressed +/kinect_head/depth_registered/hw_registered/image_rect/compressed/parameter_descriptions +/kinect_head/depth_registered/hw_registered/image_rect/compressed/parameter_updates +/kinect_head/depth_registered/hw_registered/image_rect/compressedDepth +/kinect_head/depth_registered/hw_registered/image_rect/compressedDepth/parameter_descriptions +/kinect_head/depth_registered/hw_registered/image_rect/compressedDepth/parameter_updates +/kinect_head/depth_registered/hw_registered/image_rect/theora +/kinect_head/depth_registered/hw_registered/image_rect/theora/parameter_descriptions +/kinect_head/depth_registered/hw_registered/image_rect/theora/parameter_updates +/kinect_head/depth_registered/hw_registered/image_rect/zdepth +/kinect_head/depth_registered/hw_registered/image_rect_raw +/kinect_head/depth_registered/hw_registered/image_rect_raw/compressed +/kinect_head/depth_registered/hw_registered/image_rect_raw/compressed/parameter_descriptions +/kinect_head/depth_registered/hw_registered/image_rect_raw/compressed/parameter_updates +/kinect_head/depth_registered/hw_registered/image_rect_raw/compressedDepth +/kinect_head/depth_registered/hw_registered/image_rect_raw/compressedDepth/parameter_descriptions +/kinect_head/depth_registered/hw_registered/image_rect_raw/compressedDepth/parameter_updates +/kinect_head/depth_registered/hw_registered/image_rect_raw/theora +/kinect_head/depth_registered/hw_registered/image_rect_raw/theora/parameter_descriptions +/kinect_head/depth_registered/hw_registered/image_rect_raw/theora/parameter_updates +/kinect_head/depth_registered/hw_registered/image_rect_raw/zdepth +/kinect_head/depth_registered/image +/kinect_head/depth_registered/image/compressed +/kinect_head/depth_registered/image/compressed/parameter_descriptions +/kinect_head/depth_registered/image/compressed/parameter_updates +/kinect_head/depth_registered/image/compressedDepth +/kinect_head/depth_registered/image/compressedDepth/parameter_descriptions +/kinect_head/depth_registered/image/compressedDepth/parameter_updates +/kinect_head/depth_registered/image/theora +/kinect_head/depth_registered/image/theora/parameter_descriptions +/kinect_head/depth_registered/image/theora/parameter_updates +/kinect_head/depth_registered/image/zdepth +/kinect_head/depth_registered/image_raw +/kinect_head/depth_registered/image_raw/compressed +/kinect_head/depth_registered/image_raw/compressed/parameter_descriptions +/kinect_head/depth_registered/image_raw/compressed/parameter_updates +/kinect_head/depth_registered/image_raw/compressedDepth +/kinect_head/depth_registered/image_raw/compressedDepth/parameter_descriptions +/kinect_head/depth_registered/image_raw/compressedDepth/parameter_updates +/kinect_head/depth_registered/image_raw/theora +/kinect_head/depth_registered/image_raw/theora/parameter_descriptions +/kinect_head/depth_registered/image_raw/theora/parameter_updates +/kinect_head/depth_registered/image_raw/zdepth +/kinect_head/depth_registered/image_rect +/kinect_head/depth_registered/image_rect/compressedDepth +/kinect_head/depth_registered/points +/kinect_head/depth_registered/points_self_filtered +/kinect_head/depth_registered/quater/points +/kinect_head/depth_registered/quater/throttled/points +/kinect_head/depth_registered/throttle_camera_info/parameter_descriptions +/kinect_head/depth_registered/throttle_camera_info/parameter_updates +/kinect_head/depth_registered/throttle_cloud/parameter_descriptions +/kinect_head/depth_registered/throttle_cloud/parameter_updates +/kinect_head/depth_registered/throttle_cloud_half/parameter_descriptions +/kinect_head/depth_registered/throttle_cloud_half/parameter_updates +/kinect_head/depth_registered/throttle_cloud_quater/parameter_descriptions +/kinect_head/depth_registered/throttle_cloud_quater/parameter_updates +/kinect_head/depth_registered/throttle_image/parameter_descriptions +/kinect_head/depth_registered/throttle_image/parameter_updates +/kinect_head/depth_registered/throttle_image_compressed/parameter_descriptions +/kinect_head/depth_registered/throttle_image_compressed/parameter_updates +/kinect_head/depth_registered/throttled/camera_info +/kinect_head/depth_registered/throttled/image_rect +/kinect_head/depth_registered/throttled/image_rect/compressedDepth +/kinect_head/depth_registered/throttled/points +/kinect_head/depth_registered_rectify_depth/parameter_descriptions +/kinect_head/depth_registered_rectify_depth/parameter_updates +/kinect_head/driver/parameter_descriptions +/kinect_head/driver/parameter_updates +/kinect_head/ir/camera_info +/kinect_head/ir/image_raw +/kinect_head/ir/image_raw/compressed +/kinect_head/ir/image_raw/compressed/parameter_descriptions +/kinect_head/ir/image_raw/compressed/parameter_updates +/kinect_head/ir/image_raw/compressedDepth +/kinect_head/ir/image_raw/compressedDepth/parameter_descriptions +/kinect_head/ir/image_raw/compressedDepth/parameter_updates +/kinect_head/ir/image_raw/theora +/kinect_head/ir/image_raw/theora/parameter_descriptions +/kinect_head/ir/image_raw/theora/parameter_updates +/kinect_head/ir/image_raw/zdepth +/kinect_head/ir/image_rect_ir +/kinect_head/ir/image_rect_ir/compressed +/kinect_head/ir/image_rect_ir/compressed/parameter_descriptions +/kinect_head/ir/image_rect_ir/compressed/parameter_updates +/kinect_head/ir/image_rect_ir/compressedDepth +/kinect_head/ir/image_rect_ir/compressedDepth/parameter_descriptions +/kinect_head/ir/image_rect_ir/compressedDepth/parameter_updates +/kinect_head/ir/image_rect_ir/theora +/kinect_head/ir/image_rect_ir/theora/parameter_descriptions +/kinect_head/ir/image_rect_ir/theora/parameter_updates +/kinect_head/ir/image_rect_ir/zdepth +/kinect_head/ir_rectify_ir/parameter_descriptions +/kinect_head/ir_rectify_ir/parameter_updates +/kinect_head/kinect_head_c2_nodelet_manager/bond +/kinect_head/kinect_head_nodelet_manager/bond +/kinect_head/projector/camera_info +/kinect_head/rgb/camera_info +/kinect_head/rgb/downsample_half/parameter_descriptions +/kinect_head/rgb/downsample_half/parameter_updates +/kinect_head/rgb/downsample_quater/parameter_descriptions +/kinect_head/rgb/downsample_quater/parameter_updates +/kinect_head/rgb/half/camera_info +/kinect_head/rgb/half/image_rect_color +/kinect_head/rgb/half/image_rect_color/compressed +/kinect_head/rgb/half/image_rect_color/compressed/parameter_descriptions +/kinect_head/rgb/half/image_rect_color/compressed/parameter_updates +/kinect_head/rgb/half/image_rect_color/compressedDepth +/kinect_head/rgb/half/image_rect_color/compressedDepth/parameter_descriptions +/kinect_head/rgb/half/image_rect_color/compressedDepth/parameter_updates +/kinect_head/rgb/half/image_rect_color/theora +/kinect_head/rgb/half/image_rect_color/theora/parameter_descriptions +/kinect_head/rgb/half/image_rect_color/theora/parameter_updates +/kinect_head/rgb/half/image_rect_color/zdepth +/kinect_head/rgb/image_color +/kinect_head/rgb/image_color/compressed +/kinect_head/rgb/image_color/compressed/parameter_descriptions +/kinect_head/rgb/image_color/compressed/parameter_updates +/kinect_head/rgb/image_color/compressedDepth +/kinect_head/rgb/image_color/compressedDepth/parameter_descriptions +/kinect_head/rgb/image_color/compressedDepth/parameter_updates +/kinect_head/rgb/image_color/theora +/kinect_head/rgb/image_color/theora/parameter_descriptions +/kinect_head/rgb/image_color/theora/parameter_updates +/kinect_head/rgb/image_color/zdepth +/kinect_head/rgb/image_mono +/kinect_head/rgb/image_mono/compressed +/kinect_head/rgb/image_mono/compressed/parameter_descriptions +/kinect_head/rgb/image_mono/compressed/parameter_updates +/kinect_head/rgb/image_mono/compressedDepth +/kinect_head/rgb/image_mono/compressedDepth/parameter_descriptions +/kinect_head/rgb/image_mono/compressedDepth/parameter_updates +/kinect_head/rgb/image_mono/theora +/kinect_head/rgb/image_mono/theora/parameter_descriptions +/kinect_head/rgb/image_mono/theora/parameter_updates +/kinect_head/rgb/image_mono/zdepth +/kinect_head/rgb/image_raw +/kinect_head/rgb/image_raw/compressed +/kinect_head/rgb/image_raw/compressed/parameter_descriptions +/kinect_head/rgb/image_raw/compressed/parameter_updates +/kinect_head/rgb/image_raw/compressedDepth +/kinect_head/rgb/image_raw/compressedDepth/parameter_descriptions +/kinect_head/rgb/image_raw/compressedDepth/parameter_updates +/kinect_head/rgb/image_raw/theora +/kinect_head/rgb/image_raw/theora/parameter_descriptions +/kinect_head/rgb/image_raw/theora/parameter_updates +/kinect_head/rgb/image_raw/zdepth +/kinect_head/rgb/image_rect_color +/kinect_head/rgb/image_rect_color/compressed +/kinect_head/rgb/image_rect_color/compressed/parameter_descriptions +/kinect_head/rgb/image_rect_color/compressed/parameter_updates +/kinect_head/rgb/image_rect_color/compressedDepth +/kinect_head/rgb/image_rect_color/compressedDepth/parameter_descriptions +/kinect_head/rgb/image_rect_color/compressedDepth/parameter_updates +/kinect_head/rgb/image_rect_color/theora +/kinect_head/rgb/image_rect_color/theora/parameter_descriptions +/kinect_head/rgb/image_rect_color/theora/parameter_updates +/kinect_head/rgb/image_rect_color/zdepth +/kinect_head/rgb/image_rect_mono +/kinect_head/rgb/image_rect_mono/compressed +/kinect_head/rgb/image_rect_mono/compressed/parameter_descriptions +/kinect_head/rgb/image_rect_mono/compressed/parameter_updates +/kinect_head/rgb/image_rect_mono/compressedDepth +/kinect_head/rgb/image_rect_mono/compressedDepth/parameter_descriptions +/kinect_head/rgb/image_rect_mono/compressedDepth/parameter_updates +/kinect_head/rgb/image_rect_mono/theora +/kinect_head/rgb/image_rect_mono/theora/parameter_descriptions +/kinect_head/rgb/image_rect_mono/theora/parameter_updates +/kinect_head/rgb/image_rect_mono/zdepth +/kinect_head/rgb/quater/camera_info +/kinect_head/rgb/quater/image_rect_color +/kinect_head/rgb/quater/image_rect_color/compressed +/kinect_head/rgb/quater/image_rect_color/compressed/parameter_descriptions +/kinect_head/rgb/quater/image_rect_color/compressed/parameter_updates +/kinect_head/rgb/quater/image_rect_color/compressedDepth +/kinect_head/rgb/quater/image_rect_color/compressedDepth/parameter_descriptions +/kinect_head/rgb/quater/image_rect_color/compressedDepth/parameter_updates +/kinect_head/rgb/quater/image_rect_color/theora +/kinect_head/rgb/quater/image_rect_color/theora/parameter_descriptions +/kinect_head/rgb/quater/image_rect_color/theora/parameter_updates +/kinect_head/rgb/quater/image_rect_color/zdepth +/kinect_head/rgb/throttle_camera_info/parameter_descriptions +/kinect_head/rgb/throttle_camera_info/parameter_updates +/kinect_head/rgb/throttle_rgb/parameter_descriptions +/kinect_head/rgb/throttle_rgb/parameter_updates +/kinect_head/rgb/throttle_rgb_compressed/parameter_descriptions +/kinect_head/rgb/throttle_rgb_compressed/parameter_updates +/kinect_head/rgb/throttled/camera_info +/kinect_head/rgb/throttled/image_rect_color +/kinect_head/rgb/throttled/image_rect_color/compressed +/kinect_head/rgb_debayer/parameter_descriptions +/kinect_head/rgb_debayer/parameter_updates +/kinect_head/rgb_rectify_color/parameter_descriptions +/kinect_head/rgb_rectify_color/parameter_updates +/kinect_head/rgb_rectify_mono/parameter_descriptions +/kinect_head/rgb_rectify_mono/parameter_updates +/kinect_head_c2/depth_registered/camera_info +/kinect_head_c2/depth_registered/points +/kinect_head_c2/rgb/camera_info +/kinect_head_c2/rgb/image_rect_color +/l_arm_controller/command +/l_arm_controller/follow_joint_trajectory/cancel +/l_arm_controller/follow_joint_trajectory/feedback +/l_arm_controller/follow_joint_trajectory/goal +/l_arm_controller/follow_joint_trajectory/result +/l_arm_controller/follow_joint_trajectory/status +/l_arm_controller/gains/l_elbow_flex_joint/parameter_descriptions +/l_arm_controller/gains/l_elbow_flex_joint/parameter_updates +/l_arm_controller/gains/l_forearm_roll_joint/parameter_descriptions +/l_arm_controller/gains/l_forearm_roll_joint/parameter_updates +/l_arm_controller/gains/l_shoulder_lift_joint/parameter_descriptions +/l_arm_controller/gains/l_shoulder_lift_joint/parameter_updates +/l_arm_controller/gains/l_shoulder_pan_joint/parameter_descriptions +/l_arm_controller/gains/l_shoulder_pan_joint/parameter_updates +/l_arm_controller/gains/l_upper_arm_roll_joint/parameter_descriptions +/l_arm_controller/gains/l_upper_arm_roll_joint/parameter_updates +/l_arm_controller/gains/l_wrist_flex_joint/parameter_descriptions +/l_arm_controller/gains/l_wrist_flex_joint/parameter_updates +/l_arm_controller/gains/l_wrist_roll_joint/parameter_descriptions +/l_arm_controller/gains/l_wrist_roll_joint/parameter_updates +/l_arm_controller/joint_trajectory_action/cancel +/l_arm_controller/joint_trajectory_action/feedback +/l_arm_controller/joint_trajectory_action/goal +/l_arm_controller/joint_trajectory_action/result +/l_arm_controller/joint_trajectory_action/status +/l_arm_controller/state +/l_arm_controller_loose/command +/l_arm_controller_loose/follow_joint_trajectory/cancel +/l_arm_controller_loose/follow_joint_trajectory/feedback +/l_arm_controller_loose/follow_joint_trajectory/goal +/l_arm_controller_loose/follow_joint_trajectory/result +/l_arm_controller_loose/follow_joint_trajectory/status +/l_arm_controller_loose/gains/l_elbow_flex_joint/parameter_descriptions +/l_arm_controller_loose/gains/l_elbow_flex_joint/parameter_updates +/l_arm_controller_loose/gains/l_forearm_roll_joint/parameter_descriptions +/l_arm_controller_loose/gains/l_forearm_roll_joint/parameter_updates +/l_arm_controller_loose/gains/l_shoulder_lift_joint/parameter_descriptions +/l_arm_controller_loose/gains/l_shoulder_lift_joint/parameter_updates +/l_arm_controller_loose/gains/l_shoulder_pan_joint/parameter_descriptions +/l_arm_controller_loose/gains/l_shoulder_pan_joint/parameter_updates +/l_arm_controller_loose/gains/l_upper_arm_roll_joint/parameter_descriptions +/l_arm_controller_loose/gains/l_upper_arm_roll_joint/parameter_updates +/l_arm_controller_loose/gains/l_wrist_flex_joint/parameter_descriptions +/l_arm_controller_loose/gains/l_wrist_flex_joint/parameter_updates +/l_arm_controller_loose/gains/l_wrist_roll_joint/parameter_descriptions +/l_arm_controller_loose/gains/l_wrist_roll_joint/parameter_updates +/l_arm_controller_loose/joint_trajectory_action/cancel +/l_arm_controller_loose/joint_trajectory_action/feedback +/l_arm_controller_loose/joint_trajectory_action/goal +/l_arm_controller_loose/joint_trajectory_action/result +/l_arm_controller_loose/joint_trajectory_action/status +/l_arm_controller_loose/state +/l_forearm_cam/camera_info +/l_forearm_cam/image_color +/l_forearm_cam/image_color/compressed +/l_forearm_cam/image_color/compressed/parameter_descriptions +/l_forearm_cam/image_color/compressed/parameter_updates +/l_forearm_cam/image_color/compressedDepth +/l_forearm_cam/image_color/compressedDepth/parameter_descriptions +/l_forearm_cam/image_color/compressedDepth/parameter_updates +/l_forearm_cam/image_color/theora +/l_forearm_cam/image_color/theora/parameter_descriptions +/l_forearm_cam/image_color/theora/parameter_updates +/l_forearm_cam/image_color/zdepth +/l_forearm_cam/image_mono +/l_forearm_cam/image_mono/compressed +/l_forearm_cam/image_mono/compressed/parameter_descriptions +/l_forearm_cam/image_mono/compressed/parameter_updates +/l_forearm_cam/image_mono/compressedDepth +/l_forearm_cam/image_mono/compressedDepth/parameter_descriptions +/l_forearm_cam/image_mono/compressedDepth/parameter_updates +/l_forearm_cam/image_mono/theora +/l_forearm_cam/image_mono/theora/parameter_descriptions +/l_forearm_cam/image_mono/theora/parameter_updates +/l_forearm_cam/image_mono/zdepth +/l_forearm_cam/image_proc_debayer/parameter_descriptions +/l_forearm_cam/image_proc_debayer/parameter_updates +/l_forearm_cam/image_proc_rectify_color/parameter_descriptions +/l_forearm_cam/image_proc_rectify_color/parameter_updates +/l_forearm_cam/image_proc_rectify_mono/parameter_descriptions +/l_forearm_cam/image_proc_rectify_mono/parameter_updates +/l_forearm_cam/image_raw +/l_forearm_cam/image_raw/compressed +/l_forearm_cam/image_raw/compressed/parameter_descriptions +/l_forearm_cam/image_raw/compressed/parameter_updates +/l_forearm_cam/image_raw/compressedDepth +/l_forearm_cam/image_raw/compressedDepth/parameter_descriptions +/l_forearm_cam/image_raw/compressedDepth/parameter_updates +/l_forearm_cam/image_raw/theora +/l_forearm_cam/image_raw/theora/parameter_descriptions +/l_forearm_cam/image_raw/theora/parameter_updates +/l_forearm_cam/image_raw/zdepth +/l_forearm_cam/image_rect +/l_forearm_cam/image_rect/compressed +/l_forearm_cam/image_rect/compressed/parameter_descriptions +/l_forearm_cam/image_rect/compressed/parameter_updates +/l_forearm_cam/image_rect/compressedDepth +/l_forearm_cam/image_rect/compressedDepth/parameter_descriptions +/l_forearm_cam/image_rect/compressedDepth/parameter_updates +/l_forearm_cam/image_rect/theora +/l_forearm_cam/image_rect/theora/parameter_descriptions +/l_forearm_cam/image_rect/theora/parameter_updates +/l_forearm_cam/image_rect/zdepth +/l_forearm_cam/image_rect_color +/l_forearm_cam/image_rect_color/compressed +/l_forearm_cam/image_rect_color/compressed/parameter_descriptions +/l_forearm_cam/image_rect_color/compressed/parameter_updates +/l_forearm_cam/image_rect_color/compressedDepth +/l_forearm_cam/image_rect_color/compressedDepth/parameter_descriptions +/l_forearm_cam/image_rect_color/compressedDepth/parameter_updates +/l_forearm_cam/image_rect_color/theora +/l_forearm_cam/image_rect_color/theora/parameter_descriptions +/l_forearm_cam/image_rect_color/theora/parameter_updates +/l_forearm_cam/image_rect_color/zdepth +/l_forearm_cam/parameter_descriptions +/l_forearm_cam/parameter_updates +/l_forearm_cam_trigger/waveform +/l_gripper_controller/command +/l_gripper_controller/gripper_action/cancel +/l_gripper_controller/gripper_action/feedback +/l_gripper_controller/gripper_action/goal +/l_gripper_controller/gripper_action/result +/l_gripper_controller/gripper_action/status +/l_gripper_controller/pid/parameter_descriptions +/l_gripper_controller/pid/parameter_updates +/l_gripper_controller/state +/l_gripper_sensor_controller/command +/l_gripper_sensor_controller/contact_state +/l_gripper_sensor_controller/event_detector +/l_gripper_sensor_controller/event_detector/cancel +/l_gripper_sensor_controller/event_detector/feedback +/l_gripper_sensor_controller/event_detector/goal +/l_gripper_sensor_controller/event_detector/result +/l_gripper_sensor_controller/event_detector/status +/l_gripper_sensor_controller/event_detector_state +/l_gripper_sensor_controller/find_contact +/l_gripper_sensor_controller/find_contact/cancel +/l_gripper_sensor_controller/find_contact/feedback +/l_gripper_sensor_controller/find_contact/goal +/l_gripper_sensor_controller/find_contact/result +/l_gripper_sensor_controller/find_contact/status +/l_gripper_sensor_controller/force_servo +/l_gripper_sensor_controller/force_servo/cancel +/l_gripper_sensor_controller/force_servo/feedback +/l_gripper_sensor_controller/force_servo/goal +/l_gripper_sensor_controller/force_servo/result +/l_gripper_sensor_controller/force_servo/status +/l_gripper_sensor_controller/force_servo_state +/l_gripper_sensor_controller/grab/cancel +/l_gripper_sensor_controller/grab/feedback +/l_gripper_sensor_controller/grab/goal +/l_gripper_sensor_controller/grab/result +/l_gripper_sensor_controller/grab/status +/l_gripper_sensor_controller/gripper_action/cancel +/l_gripper_sensor_controller/gripper_action/feedback +/l_gripper_sensor_controller/gripper_action/goal +/l_gripper_sensor_controller/gripper_action/result +/l_gripper_sensor_controller/gripper_action/status +/l_gripper_sensor_controller/release/cancel +/l_gripper_sensor_controller/release/feedback +/l_gripper_sensor_controller/release/goal +/l_gripper_sensor_controller/release/result +/l_gripper_sensor_controller/release/status +/l_gripper_sensor_controller/slip_servo +/l_gripper_sensor_controller/slip_servo/cancel +/l_gripper_sensor_controller/slip_servo/feedback +/l_gripper_sensor_controller/slip_servo/goal +/l_gripper_sensor_controller/slip_servo/result +/l_gripper_sensor_controller/slip_servo/status +/l_gripper_sensor_controller/slip_servo_state +/l_gripper_sensor_controller/state +/laser_tilt_controller/gains/parameter_descriptions +/laser_tilt_controller/gains/parameter_updates +/laser_tilt_controller/laser_scanner_signal +/laser_tilt_controller/set_periodic_cmd +/laser_tilt_controller/set_traj_cmd +/lifelog/joint_states_logger/output +/lifelog/joint_states_logger/parameter_descriptions +/lifelog/joint_states_logger/parameter_updates +/lifelog/joint_states_throttle/output +/lifelog/joint_states_throttle/parameter_descriptions +/lifelog/joint_states_throttle/parameter_updates +/look_at_human/enabled +/map +/map_keepout +/map_metadata +/map_reload +/map_tf_mux/selected +/map_updates +/mechanism_statistics +/message_store/insert +/motor_trace/bl_caster_l_wheel_motor +/motor_trace/bl_caster_r_wheel_motor +/motor_trace/bl_caster_rotation_motor +/motor_trace/br_caster_l_wheel_motor +/motor_trace/br_caster_r_wheel_motor +/motor_trace/br_caster_rotation_motor +/motor_trace/fl_caster_l_wheel_motor +/motor_trace/fl_caster_r_wheel_motor +/motor_trace/fl_caster_rotation_motor +/motor_trace/fr_caster_l_wheel_motor +/motor_trace/fr_caster_r_wheel_motor +/motor_trace/fr_caster_rotation_motor +/motor_trace/head_pan_motor +/motor_trace/head_tilt_motor +/motor_trace/l_elbow_flex_motor +/motor_trace/l_forearm_roll_motor +/motor_trace/l_gripper_motor +/motor_trace/l_shoulder_lift_motor +/motor_trace/l_shoulder_pan_motor +/motor_trace/l_upper_arm_roll_motor +/motor_trace/l_wrist_l_motor +/motor_trace/l_wrist_r_motor +/motor_trace/laser_tilt_mount_motor +/motor_trace/r_elbow_flex_motor +/motor_trace/r_forearm_roll_motor +/motor_trace/r_gripper_motor +/motor_trace/r_shoulder_lift_motor +/motor_trace/r_shoulder_pan_motor +/motor_trace/r_upper_arm_roll_motor +/motor_trace/r_wrist_l_motor +/motor_trace/r_wrist_r_motor +/motor_trace/torso_lift_motor +/move_base/cancel +/move_base/feedback +/move_base/goal +/move_base/recovery_status +/move_base/result +/move_base/status +/move_base_node/DWAPlannerROS/cost_cloud +/move_base_node/DWAPlannerROS/global_plan +/move_base_node/DWAPlannerROS/local_plan +/move_base_node/DWAPlannerROS/parameter_descriptions +/move_base_node/DWAPlannerROS/parameter_updates +/move_base_node/DWAPlannerROS/trajectory_cloud +/move_base_node/NavfnROS/plan +/move_base_node/current_goal +/move_base_node/global_costmap/costmap +/move_base_node/global_costmap/costmap_updates +/move_base_node/global_costmap/footprint +/move_base_node/global_costmap/inflation_layer/parameter_descriptions +/move_base_node/global_costmap/inflation_layer/parameter_updates +/move_base_node/global_costmap/obstacle_layer/parameter_descriptions +/move_base_node/global_costmap/obstacle_layer/parameter_updates +/move_base_node/global_costmap/parameter_descriptions +/move_base_node/global_costmap/parameter_updates +/move_base_node/global_costmap/static_layer/parameter_descriptions +/move_base_node/global_costmap/static_layer/parameter_updates +/move_base_node/local_costmap/costmap +/move_base_node/local_costmap/costmap_updates +/move_base_node/local_costmap/footprint +/move_base_node/local_costmap/inflation_layer/parameter_descriptions +/move_base_node/local_costmap/inflation_layer/parameter_updates +/move_base_node/local_costmap/obstacle_layer/parameter_descriptions +/move_base_node/local_costmap/obstacle_layer/parameter_updates +/move_base_node/local_costmap/parameter_descriptions +/move_base_node/local_costmap/parameter_updates +/move_base_node/parameter_descriptions +/move_base_node/parameter_updates +/move_base_simple/goal +/move_mongodb_entries/cancel +/move_mongodb_entries/feedback +/move_mongodb_entries/goal +/move_mongodb_entries/result +/move_mongodb_entries/status +/multiple_joystick_mux/selected +/narrow_stereo/disparity +/narrow_stereo/left/camera_info +/narrow_stereo/left/image_color +/narrow_stereo/left/image_color/compressed +/narrow_stereo/left/image_color/compressed/parameter_descriptions +/narrow_stereo/left/image_color/compressed/parameter_updates +/narrow_stereo/left/image_color/compressedDepth +/narrow_stereo/left/image_color/compressedDepth/parameter_descriptions +/narrow_stereo/left/image_color/compressedDepth/parameter_updates +/narrow_stereo/left/image_color/theora +/narrow_stereo/left/image_color/theora/parameter_descriptions +/narrow_stereo/left/image_color/theora/parameter_updates +/narrow_stereo/left/image_color/zdepth +/narrow_stereo/left/image_mono +/narrow_stereo/left/image_mono/compressed +/narrow_stereo/left/image_mono/compressed/parameter_descriptions +/narrow_stereo/left/image_mono/compressed/parameter_updates +/narrow_stereo/left/image_mono/compressedDepth +/narrow_stereo/left/image_mono/compressedDepth/parameter_descriptions +/narrow_stereo/left/image_mono/compressedDepth/parameter_updates +/narrow_stereo/left/image_mono/theora +/narrow_stereo/left/image_mono/theora/parameter_descriptions +/narrow_stereo/left/image_mono/theora/parameter_updates +/narrow_stereo/left/image_mono/zdepth +/narrow_stereo/left/image_raw +/narrow_stereo/left/image_raw/compressed +/narrow_stereo/left/image_raw/compressed/parameter_descriptions +/narrow_stereo/left/image_raw/compressed/parameter_updates +/narrow_stereo/left/image_raw/compressedDepth +/narrow_stereo/left/image_raw/compressedDepth/parameter_descriptions +/narrow_stereo/left/image_raw/compressedDepth/parameter_updates +/narrow_stereo/left/image_raw/theora +/narrow_stereo/left/image_raw/theora/parameter_descriptions +/narrow_stereo/left/image_raw/theora/parameter_updates +/narrow_stereo/left/image_raw/zdepth +/narrow_stereo/left/image_rect +/narrow_stereo/left/image_rect/compressed +/narrow_stereo/left/image_rect/compressed/parameter_descriptions +/narrow_stereo/left/image_rect/compressed/parameter_updates +/narrow_stereo/left/image_rect/compressedDepth +/narrow_stereo/left/image_rect/compressedDepth/parameter_descriptions +/narrow_stereo/left/image_rect/compressedDepth/parameter_updates +/narrow_stereo/left/image_rect/theora +/narrow_stereo/left/image_rect/theora/parameter_descriptions +/narrow_stereo/left/image_rect/theora/parameter_updates +/narrow_stereo/left/image_rect/zdepth +/narrow_stereo/left/image_rect_color +/narrow_stereo/left/image_rect_color/compressed +/narrow_stereo/left/image_rect_color/compressed/parameter_descriptions +/narrow_stereo/left/image_rect_color/compressed/parameter_updates +/narrow_stereo/left/image_rect_color/compressedDepth +/narrow_stereo/left/image_rect_color/compressedDepth/parameter_descriptions +/narrow_stereo/left/image_rect_color/compressedDepth/parameter_updates +/narrow_stereo/left/image_rect_color/theora +/narrow_stereo/left/image_rect_color/theora/parameter_descriptions +/narrow_stereo/left/image_rect_color/theora/parameter_updates +/narrow_stereo/left/image_rect_color/zdepth +/narrow_stereo/narrow_stereo_proc/parameter_descriptions +/narrow_stereo/narrow_stereo_proc/parameter_updates +/narrow_stereo/narrow_stereo_proc_debayer_left/parameter_descriptions +/narrow_stereo/narrow_stereo_proc_debayer_left/parameter_updates +/narrow_stereo/narrow_stereo_proc_debayer_right/parameter_descriptions +/narrow_stereo/narrow_stereo_proc_debayer_right/parameter_updates +/narrow_stereo/narrow_stereo_proc_rectify_color_left/parameter_descriptions +/narrow_stereo/narrow_stereo_proc_rectify_color_left/parameter_updates +/narrow_stereo/narrow_stereo_proc_rectify_color_right/parameter_descriptions +/narrow_stereo/narrow_stereo_proc_rectify_color_right/parameter_updates +/narrow_stereo/narrow_stereo_proc_rectify_mono_left/parameter_descriptions +/narrow_stereo/narrow_stereo_proc_rectify_mono_left/parameter_updates +/narrow_stereo/narrow_stereo_proc_rectify_mono_right/parameter_descriptions +/narrow_stereo/narrow_stereo_proc_rectify_mono_right/parameter_updates +/narrow_stereo/points2 +/narrow_stereo/right/camera_info +/narrow_stereo/right/image_color +/narrow_stereo/right/image_color/compressed +/narrow_stereo/right/image_color/compressed/parameter_descriptions +/narrow_stereo/right/image_color/compressed/parameter_updates +/narrow_stereo/right/image_color/compressedDepth +/narrow_stereo/right/image_color/compressedDepth/parameter_descriptions +/narrow_stereo/right/image_color/compressedDepth/parameter_updates +/narrow_stereo/right/image_color/theora +/narrow_stereo/right/image_color/theora/parameter_descriptions +/narrow_stereo/right/image_color/theora/parameter_updates +/narrow_stereo/right/image_color/zdepth +/narrow_stereo/right/image_mono +/narrow_stereo/right/image_mono/compressed +/narrow_stereo/right/image_mono/compressed/parameter_descriptions +/narrow_stereo/right/image_mono/compressed/parameter_updates +/narrow_stereo/right/image_mono/compressedDepth +/narrow_stereo/right/image_mono/compressedDepth/parameter_descriptions +/narrow_stereo/right/image_mono/compressedDepth/parameter_updates +/narrow_stereo/right/image_mono/theora +/narrow_stereo/right/image_mono/theora/parameter_descriptions +/narrow_stereo/right/image_mono/theora/parameter_updates +/narrow_stereo/right/image_mono/zdepth +/narrow_stereo/right/image_raw +/narrow_stereo/right/image_raw/compressed +/narrow_stereo/right/image_raw/compressed/parameter_descriptions +/narrow_stereo/right/image_raw/compressed/parameter_updates +/narrow_stereo/right/image_raw/compressedDepth +/narrow_stereo/right/image_raw/compressedDepth/parameter_descriptions +/narrow_stereo/right/image_raw/compressedDepth/parameter_updates +/narrow_stereo/right/image_raw/theora +/narrow_stereo/right/image_raw/theora/parameter_descriptions +/narrow_stereo/right/image_raw/theora/parameter_updates +/narrow_stereo/right/image_raw/zdepth +/narrow_stereo/right/image_rect +/narrow_stereo/right/image_rect/compressed +/narrow_stereo/right/image_rect/compressed/parameter_descriptions +/narrow_stereo/right/image_rect/compressed/parameter_updates +/narrow_stereo/right/image_rect/compressedDepth +/narrow_stereo/right/image_rect/compressedDepth/parameter_descriptions +/narrow_stereo/right/image_rect/compressedDepth/parameter_updates +/narrow_stereo/right/image_rect/theora +/narrow_stereo/right/image_rect/theora/parameter_descriptions +/narrow_stereo/right/image_rect/theora/parameter_updates +/narrow_stereo/right/image_rect/zdepth +/narrow_stereo/right/image_rect_color +/narrow_stereo/right/image_rect_color/compressed +/narrow_stereo/right/image_rect_color/compressed/parameter_descriptions +/narrow_stereo/right/image_rect_color/compressed/parameter_updates +/narrow_stereo/right/image_rect_color/compressedDepth +/narrow_stereo/right/image_rect_color/compressedDepth/parameter_descriptions +/narrow_stereo/right/image_rect_color/compressedDepth/parameter_updates +/narrow_stereo/right/image_rect_color/theora +/narrow_stereo/right/image_rect_color/theora/parameter_descriptions +/narrow_stereo/right/image_rect_color/theora/parameter_updates +/narrow_stereo/right/image_rect_color/zdepth +/narrow_stereo_both/parameter_descriptions +/narrow_stereo_both/parameter_updates +/narrow_stereo_left/parameter_descriptions +/narrow_stereo_left/parameter_updates +/narrow_stereo_right/parameter_descriptions +/narrow_stereo_right/parameter_updates +/narrow_stereo_textured/disparity +/narrow_stereo_textured/left/camera_info +/narrow_stereo_textured/left/image_color +/narrow_stereo_textured/left/image_color/compressed +/narrow_stereo_textured/left/image_color/compressed/parameter_descriptions +/narrow_stereo_textured/left/image_color/compressed/parameter_updates +/narrow_stereo_textured/left/image_color/compressedDepth +/narrow_stereo_textured/left/image_color/compressedDepth/parameter_descriptions +/narrow_stereo_textured/left/image_color/compressedDepth/parameter_updates +/narrow_stereo_textured/left/image_color/theora +/narrow_stereo_textured/left/image_color/theora/parameter_descriptions +/narrow_stereo_textured/left/image_color/theora/parameter_updates +/narrow_stereo_textured/left/image_color/zdepth +/narrow_stereo_textured/left/image_mono +/narrow_stereo_textured/left/image_mono/compressed +/narrow_stereo_textured/left/image_mono/compressed/parameter_descriptions +/narrow_stereo_textured/left/image_mono/compressed/parameter_updates +/narrow_stereo_textured/left/image_mono/compressedDepth +/narrow_stereo_textured/left/image_mono/compressedDepth/parameter_descriptions +/narrow_stereo_textured/left/image_mono/compressedDepth/parameter_updates +/narrow_stereo_textured/left/image_mono/theora +/narrow_stereo_textured/left/image_mono/theora/parameter_descriptions +/narrow_stereo_textured/left/image_mono/theora/parameter_updates +/narrow_stereo_textured/left/image_mono/zdepth +/narrow_stereo_textured/left/image_raw +/narrow_stereo_textured/left/image_raw/compressed +/narrow_stereo_textured/left/image_raw/compressed/parameter_descriptions +/narrow_stereo_textured/left/image_raw/compressed/parameter_updates +/narrow_stereo_textured/left/image_raw/compressedDepth +/narrow_stereo_textured/left/image_raw/compressedDepth/parameter_descriptions +/narrow_stereo_textured/left/image_raw/compressedDepth/parameter_updates +/narrow_stereo_textured/left/image_raw/theora +/narrow_stereo_textured/left/image_raw/theora/parameter_descriptions +/narrow_stereo_textured/left/image_raw/theora/parameter_updates +/narrow_stereo_textured/left/image_raw/zdepth +/narrow_stereo_textured/left/image_rect +/narrow_stereo_textured/left/image_rect/compressed +/narrow_stereo_textured/left/image_rect/compressed/parameter_descriptions +/narrow_stereo_textured/left/image_rect/compressed/parameter_updates +/narrow_stereo_textured/left/image_rect/compressedDepth +/narrow_stereo_textured/left/image_rect/compressedDepth/parameter_descriptions +/narrow_stereo_textured/left/image_rect/compressedDepth/parameter_updates +/narrow_stereo_textured/left/image_rect/theora +/narrow_stereo_textured/left/image_rect/theora/parameter_descriptions +/narrow_stereo_textured/left/image_rect/theora/parameter_updates +/narrow_stereo_textured/left/image_rect/zdepth +/narrow_stereo_textured/left/image_rect_color +/narrow_stereo_textured/left/image_rect_color/compressed +/narrow_stereo_textured/left/image_rect_color/compressed/parameter_descriptions +/narrow_stereo_textured/left/image_rect_color/compressed/parameter_updates +/narrow_stereo_textured/left/image_rect_color/compressedDepth +/narrow_stereo_textured/left/image_rect_color/compressedDepth/parameter_descriptions +/narrow_stereo_textured/left/image_rect_color/compressedDepth/parameter_updates +/narrow_stereo_textured/left/image_rect_color/theora +/narrow_stereo_textured/left/image_rect_color/theora/parameter_descriptions +/narrow_stereo_textured/left/image_rect_color/theora/parameter_updates +/narrow_stereo_textured/left/image_rect_color/zdepth +/narrow_stereo_textured/narrow_stereo_textured_proc/parameter_descriptions +/narrow_stereo_textured/narrow_stereo_textured_proc/parameter_updates +/narrow_stereo_textured/narrow_stereo_textured_proc_debayer_left/parameter_descriptions +/narrow_stereo_textured/narrow_stereo_textured_proc_debayer_left/parameter_updates +/narrow_stereo_textured/narrow_stereo_textured_proc_debayer_right/parameter_descriptions +/narrow_stereo_textured/narrow_stereo_textured_proc_debayer_right/parameter_updates +/narrow_stereo_textured/narrow_stereo_textured_proc_rectify_color_left/parameter_descriptions +/narrow_stereo_textured/narrow_stereo_textured_proc_rectify_color_left/parameter_updates +/narrow_stereo_textured/narrow_stereo_textured_proc_rectify_color_right/parameter_descriptions +/narrow_stereo_textured/narrow_stereo_textured_proc_rectify_color_right/parameter_updates +/narrow_stereo_textured/narrow_stereo_textured_proc_rectify_mono_left/parameter_descriptions +/narrow_stereo_textured/narrow_stereo_textured_proc_rectify_mono_left/parameter_updates +/narrow_stereo_textured/narrow_stereo_textured_proc_rectify_mono_right/parameter_descriptions +/narrow_stereo_textured/narrow_stereo_textured_proc_rectify_mono_right/parameter_updates +/narrow_stereo_textured/points2 +/narrow_stereo_textured/right/camera_info +/narrow_stereo_textured/right/image_color +/narrow_stereo_textured/right/image_color/compressed +/narrow_stereo_textured/right/image_color/compressed/parameter_descriptions +/narrow_stereo_textured/right/image_color/compressed/parameter_updates +/narrow_stereo_textured/right/image_color/compressedDepth +/narrow_stereo_textured/right/image_color/compressedDepth/parameter_descriptions +/narrow_stereo_textured/right/image_color/compressedDepth/parameter_updates +/narrow_stereo_textured/right/image_color/theora +/narrow_stereo_textured/right/image_color/theora/parameter_descriptions +/narrow_stereo_textured/right/image_color/theora/parameter_updates +/narrow_stereo_textured/right/image_color/zdepth +/narrow_stereo_textured/right/image_mono +/narrow_stereo_textured/right/image_mono/compressed +/narrow_stereo_textured/right/image_mono/compressed/parameter_descriptions +/narrow_stereo_textured/right/image_mono/compressed/parameter_updates +/narrow_stereo_textured/right/image_mono/compressedDepth +/narrow_stereo_textured/right/image_mono/compressedDepth/parameter_descriptions +/narrow_stereo_textured/right/image_mono/compressedDepth/parameter_updates +/narrow_stereo_textured/right/image_mono/theora +/narrow_stereo_textured/right/image_mono/theora/parameter_descriptions +/narrow_stereo_textured/right/image_mono/theora/parameter_updates +/narrow_stereo_textured/right/image_mono/zdepth +/narrow_stereo_textured/right/image_raw +/narrow_stereo_textured/right/image_raw/compressed +/narrow_stereo_textured/right/image_raw/compressed/parameter_descriptions +/narrow_stereo_textured/right/image_raw/compressed/parameter_updates +/narrow_stereo_textured/right/image_raw/compressedDepth +/narrow_stereo_textured/right/image_raw/compressedDepth/parameter_descriptions +/narrow_stereo_textured/right/image_raw/compressedDepth/parameter_updates +/narrow_stereo_textured/right/image_raw/theora +/narrow_stereo_textured/right/image_raw/theora/parameter_descriptions +/narrow_stereo_textured/right/image_raw/theora/parameter_updates +/narrow_stereo_textured/right/image_raw/zdepth +/narrow_stereo_textured/right/image_rect +/narrow_stereo_textured/right/image_rect/compressed +/narrow_stereo_textured/right/image_rect/compressed/parameter_descriptions +/narrow_stereo_textured/right/image_rect/compressed/parameter_updates +/narrow_stereo_textured/right/image_rect/compressedDepth +/narrow_stereo_textured/right/image_rect/compressedDepth/parameter_descriptions +/narrow_stereo_textured/right/image_rect/compressedDepth/parameter_updates +/narrow_stereo_textured/right/image_rect/theora +/narrow_stereo_textured/right/image_rect/theora/parameter_descriptions +/narrow_stereo_textured/right/image_rect/theora/parameter_updates +/narrow_stereo_textured/right/image_rect/zdepth +/narrow_stereo_textured/right/image_rect_color +/narrow_stereo_textured/right/image_rect_color/compressed +/narrow_stereo_textured/right/image_rect_color/compressed/parameter_descriptions +/narrow_stereo_textured/right/image_rect_color/compressed/parameter_updates +/narrow_stereo_textured/right/image_rect_color/compressedDepth +/narrow_stereo_textured/right/image_rect_color/compressedDepth/parameter_descriptions +/narrow_stereo_textured/right/image_rect_color/compressedDepth/parameter_updates +/narrow_stereo_textured/right/image_rect_color/theora +/narrow_stereo_textured/right/image_rect_color/theora/parameter_descriptions +/narrow_stereo_textured/right/image_rect_color/theora/parameter_updates +/narrow_stereo_textured/right/image_rect_color/zdepth +/navigation/cmd_vel +/navigation/cmd_vel/raw +/network/connected +/odom_teleop +/particlecloud +/power_board/state +/power_monitor/parameter_descriptions +/power_monitor/parameter_updates +/power_state +/pr1040/app_list +/pr1040/application/app_status +/pr1040/bond0/receive +/pr1040/bond0/receive_kbps +/pr1040/bond0/receive_mbps +/pr1040/bond0/transmit +/pr1040/bond0/transmit_kbps +/pr1040/bond0/transmit_mbps +/pr1040/lan0/receive +/pr1040/lan0/receive_kbps +/pr1040/lan0/receive_mbps +/pr1040/lan0/transmit +/pr1040/lan0/transmit_kbps +/pr1040/lan0/transmit_mbps +/pr1040/lan1/receive +/pr1040/lan1/receive_kbps +/pr1040/lan1/receive_mbps +/pr1040/lan1/transmit +/pr1040/lan1/transmit_kbps +/pr1040/lan1/transmit_mbps +/pr1040/lan2/receive +/pr1040/lan2/receive_kbps +/pr1040/lan2/receive_mbps +/pr1040/lan2/transmit +/pr1040/lan2/transmit_kbps +/pr1040/lan2/transmit_mbps +/pr1040/lan3/receive +/pr1040/lan3/receive_kbps +/pr1040/lan3/receive_mbps +/pr1040/lan3/transmit +/pr1040/lan3/transmit_kbps +/pr1040/lan3/transmit_mbps +/pr1040/lo/receive +/pr1040/lo/receive_kbps +/pr1040/lo/receive_mbps +/pr1040/lo/transmit +/pr1040/lo/transmit_kbps +/pr1040/lo/transmit_mbps +/pr1040/nonlocal/receive +/pr1040/nonlocal/receive_kbps +/pr1040/nonlocal/receive_mbps +/pr1040/nonlocal/transmit +/pr1040/nonlocal/transmit_kbps +/pr1040/nonlocal/transmit_mbps +/pr1040/wan0/receive +/pr1040/wan0/receive_kbps +/pr1040/wan0/receive_mbps +/pr1040/wan0/transmit +/pr1040/wan0/transmit_kbps +/pr1040/wan0/transmit_mbps +/pr2_ethercat/motors_halted +/pr2_move_base/cancel +/pr2_move_base/feedback +/pr2_move_base/goal +/pr2_move_base/result +/pr2_move_base/status +/pr2twit_from_tablet +/pressure/l_gripper_motor +/pressure/r_gripper_motor +/projector_controller/falling_edge_timestamps +/projector_controller/rising_edge_timestamps +/projector_trigger/off_time +/projector_trigger/on_time +/projector_trigger/waveform +/prosilica_inhibit_projector_controller/waveform +/r_arm_controller/command +/r_arm_controller/follow_joint_trajectory/cancel +/r_arm_controller/follow_joint_trajectory/feedback +/r_arm_controller/follow_joint_trajectory/goal +/r_arm_controller/follow_joint_trajectory/result +/r_arm_controller/follow_joint_trajectory/status +/r_arm_controller/gains/r_elbow_flex_joint/parameter_descriptions +/r_arm_controller/gains/r_elbow_flex_joint/parameter_updates +/r_arm_controller/gains/r_forearm_roll_joint/parameter_descriptions +/r_arm_controller/gains/r_forearm_roll_joint/parameter_updates +/r_arm_controller/gains/r_shoulder_lift_joint/parameter_descriptions +/r_arm_controller/gains/r_shoulder_lift_joint/parameter_updates +/r_arm_controller/gains/r_shoulder_pan_joint/parameter_descriptions +/r_arm_controller/gains/r_shoulder_pan_joint/parameter_updates +/r_arm_controller/gains/r_upper_arm_roll_joint/parameter_descriptions +/r_arm_controller/gains/r_upper_arm_roll_joint/parameter_updates +/r_arm_controller/gains/r_wrist_flex_joint/parameter_descriptions +/r_arm_controller/gains/r_wrist_flex_joint/parameter_updates +/r_arm_controller/gains/r_wrist_roll_joint/parameter_descriptions +/r_arm_controller/gains/r_wrist_roll_joint/parameter_updates +/r_arm_controller/joint_trajectory_action/cancel +/r_arm_controller/joint_trajectory_action/feedback +/r_arm_controller/joint_trajectory_action/goal +/r_arm_controller/joint_trajectory_action/result +/r_arm_controller/joint_trajectory_action/status +/r_arm_controller/state +/r_arm_controller_loose/command +/r_arm_controller_loose/follow_joint_trajectory/cancel +/r_arm_controller_loose/follow_joint_trajectory/feedback +/r_arm_controller_loose/follow_joint_trajectory/goal +/r_arm_controller_loose/follow_joint_trajectory/result +/r_arm_controller_loose/follow_joint_trajectory/status +/r_arm_controller_loose/gains/r_elbow_flex_joint/parameter_descriptions +/r_arm_controller_loose/gains/r_elbow_flex_joint/parameter_updates +/r_arm_controller_loose/gains/r_forearm_roll_joint/parameter_descriptions +/r_arm_controller_loose/gains/r_forearm_roll_joint/parameter_updates +/r_arm_controller_loose/gains/r_shoulder_lift_joint/parameter_descriptions +/r_arm_controller_loose/gains/r_shoulder_lift_joint/parameter_updates +/r_arm_controller_loose/gains/r_shoulder_pan_joint/parameter_descriptions +/r_arm_controller_loose/gains/r_shoulder_pan_joint/parameter_updates +/r_arm_controller_loose/gains/r_upper_arm_roll_joint/parameter_descriptions +/r_arm_controller_loose/gains/r_upper_arm_roll_joint/parameter_updates +/r_arm_controller_loose/gains/r_wrist_flex_joint/parameter_descriptions +/r_arm_controller_loose/gains/r_wrist_flex_joint/parameter_updates +/r_arm_controller_loose/gains/r_wrist_roll_joint/parameter_descriptions +/r_arm_controller_loose/gains/r_wrist_roll_joint/parameter_updates +/r_arm_controller_loose/joint_trajectory_action/cancel +/r_arm_controller_loose/joint_trajectory_action/feedback +/r_arm_controller_loose/joint_trajectory_action/goal +/r_arm_controller_loose/joint_trajectory_action/result +/r_arm_controller_loose/joint_trajectory_action/status +/r_arm_controller_loose/state +/r_forearm_cam/camera_info +/r_forearm_cam/image_color +/r_forearm_cam/image_color/compressed +/r_forearm_cam/image_color/compressed/parameter_descriptions +/r_forearm_cam/image_color/compressed/parameter_updates +/r_forearm_cam/image_color/compressedDepth +/r_forearm_cam/image_color/compressedDepth/parameter_descriptions +/r_forearm_cam/image_color/compressedDepth/parameter_updates +/r_forearm_cam/image_color/theora +/r_forearm_cam/image_color/theora/parameter_descriptions +/r_forearm_cam/image_color/theora/parameter_updates +/r_forearm_cam/image_color/zdepth +/r_forearm_cam/image_mono +/r_forearm_cam/image_mono/compressed +/r_forearm_cam/image_mono/compressed/parameter_descriptions +/r_forearm_cam/image_mono/compressed/parameter_updates +/r_forearm_cam/image_mono/compressedDepth +/r_forearm_cam/image_mono/compressedDepth/parameter_descriptions +/r_forearm_cam/image_mono/compressedDepth/parameter_updates +/r_forearm_cam/image_mono/theora +/r_forearm_cam/image_mono/theora/parameter_descriptions +/r_forearm_cam/image_mono/theora/parameter_updates +/r_forearm_cam/image_mono/zdepth +/r_forearm_cam/image_proc_debayer/parameter_descriptions +/r_forearm_cam/image_proc_debayer/parameter_updates +/r_forearm_cam/image_proc_rectify_color/parameter_descriptions +/r_forearm_cam/image_proc_rectify_color/parameter_updates +/r_forearm_cam/image_proc_rectify_mono/parameter_descriptions +/r_forearm_cam/image_proc_rectify_mono/parameter_updates +/r_forearm_cam/image_raw +/r_forearm_cam/image_raw/compressed +/r_forearm_cam/image_raw/compressed/parameter_descriptions +/r_forearm_cam/image_raw/compressed/parameter_updates +/r_forearm_cam/image_raw/compressedDepth +/r_forearm_cam/image_raw/compressedDepth/parameter_descriptions +/r_forearm_cam/image_raw/compressedDepth/parameter_updates +/r_forearm_cam/image_raw/theora +/r_forearm_cam/image_raw/theora/parameter_descriptions +/r_forearm_cam/image_raw/theora/parameter_updates +/r_forearm_cam/image_raw/zdepth +/r_forearm_cam/image_rect +/r_forearm_cam/image_rect/compressed +/r_forearm_cam/image_rect/compressed/parameter_descriptions +/r_forearm_cam/image_rect/compressed/parameter_updates +/r_forearm_cam/image_rect/compressedDepth +/r_forearm_cam/image_rect/compressedDepth/parameter_descriptions +/r_forearm_cam/image_rect/compressedDepth/parameter_updates +/r_forearm_cam/image_rect/theora +/r_forearm_cam/image_rect/theora/parameter_descriptions +/r_forearm_cam/image_rect/theora/parameter_updates +/r_forearm_cam/image_rect/zdepth +/r_forearm_cam/image_rect_color +/r_forearm_cam/image_rect_color/compressed +/r_forearm_cam/image_rect_color/compressed/parameter_descriptions +/r_forearm_cam/image_rect_color/compressed/parameter_updates +/r_forearm_cam/image_rect_color/compressedDepth +/r_forearm_cam/image_rect_color/compressedDepth/parameter_descriptions +/r_forearm_cam/image_rect_color/compressedDepth/parameter_updates +/r_forearm_cam/image_rect_color/theora +/r_forearm_cam/image_rect_color/theora/parameter_descriptions +/r_forearm_cam/image_rect_color/theora/parameter_updates +/r_forearm_cam/image_rect_color/zdepth +/r_forearm_cam/parameter_descriptions +/r_forearm_cam/parameter_updates +/r_forearm_cam_trigger/waveform +/r_gripper_controller/command +/r_gripper_controller/gripper_action/cancel +/r_gripper_controller/gripper_action/feedback +/r_gripper_controller/gripper_action/goal +/r_gripper_controller/gripper_action/result +/r_gripper_controller/gripper_action/status +/r_gripper_controller/pid/parameter_descriptions +/r_gripper_controller/pid/parameter_updates +/r_gripper_controller/state +/r_gripper_sensor_controller/command +/r_gripper_sensor_controller/contact_state +/r_gripper_sensor_controller/event_detector +/r_gripper_sensor_controller/event_detector/cancel +/r_gripper_sensor_controller/event_detector/feedback +/r_gripper_sensor_controller/event_detector/goal +/r_gripper_sensor_controller/event_detector/result +/r_gripper_sensor_controller/event_detector/status +/r_gripper_sensor_controller/event_detector_state +/r_gripper_sensor_controller/find_contact +/r_gripper_sensor_controller/find_contact/cancel +/r_gripper_sensor_controller/find_contact/feedback +/r_gripper_sensor_controller/find_contact/goal +/r_gripper_sensor_controller/find_contact/result +/r_gripper_sensor_controller/find_contact/status +/r_gripper_sensor_controller/force_servo +/r_gripper_sensor_controller/force_servo/cancel +/r_gripper_sensor_controller/force_servo/feedback +/r_gripper_sensor_controller/force_servo/goal +/r_gripper_sensor_controller/force_servo/result +/r_gripper_sensor_controller/force_servo/status +/r_gripper_sensor_controller/force_servo_state +/r_gripper_sensor_controller/grab/cancel +/r_gripper_sensor_controller/grab/feedback +/r_gripper_sensor_controller/grab/goal +/r_gripper_sensor_controller/grab/result +/r_gripper_sensor_controller/grab/status +/r_gripper_sensor_controller/gripper_action/cancel +/r_gripper_sensor_controller/gripper_action/feedback +/r_gripper_sensor_controller/gripper_action/goal +/r_gripper_sensor_controller/gripper_action/result +/r_gripper_sensor_controller/gripper_action/status +/r_gripper_sensor_controller/release/cancel +/r_gripper_sensor_controller/release/feedback +/r_gripper_sensor_controller/release/goal +/r_gripper_sensor_controller/release/result +/r_gripper_sensor_controller/release/status +/r_gripper_sensor_controller/slip_servo +/r_gripper_sensor_controller/slip_servo/cancel +/r_gripper_sensor_controller/slip_servo/feedback +/r_gripper_sensor_controller/slip_servo/goal +/r_gripper_sensor_controller/slip_servo/result +/r_gripper_sensor_controller/slip_servo/status +/r_gripper_sensor_controller/slip_servo_state +/r_gripper_sensor_controller/state +/respeaker_node/parameter_descriptions +/respeaker_node/parameter_updates +/robot_interface_marker_array +/robot_pose_ekf/odom_combined +/robotsound +/robotsound/cancel +/robotsound/feedback +/robotsound/goal +/robotsound/result +/robotsound/status +/robotsound_jp +/robotsound_jp/cancel +/robotsound_jp/feedback +/robotsound_jp/goal +/robotsound_jp/result +/robotsound_jp/status +/rosout +/rosout_agg +/safe_teleop_base/local_costmap/costmap +/safe_teleop_base/local_costmap/costmap_updates +/safe_teleop_base/local_costmap/footprint +/safe_teleop_base/local_costmap/inflation_layer/parameter_descriptions +/safe_teleop_base/local_costmap/inflation_layer/parameter_updates +/safe_teleop_base/local_costmap/obstacle_layer/parameter_descriptions +/safe_teleop_base/local_costmap/obstacle_layer/parameter_updates +/safe_teleop_base/local_costmap/parameter_descriptions +/safe_teleop_base/local_costmap/parameter_updates +/safe_teleop_base/local_plan +/safe_teleop_base/user_plan +/server_name/smach/container_status +/server_name/smach/container_structure +/smach_image_publisher/image +/smach_image_publisher/image/compressed +/sound_direction +/sound_localization +/sound_play/cancel +/sound_play/feedback +/sound_play/goal +/sound_play/result +/sound_play/status +/speech_audio +/speech_audio_raw +/speech_to_text +/speech_to_text_google +/speech_to_text_julius +/speech_to_text_mux/selected +/speech_to_text_other +/spots_marker_array +/status_led +/teleop/cmd_vel +/teleop/cmd_vel/safe +/teleop/cmd_vel/unsafe +/teleop/joy_vel +/tf +/tf2_buffer_server/cancel +/tf2_buffer_server/feedback +/tf2_buffer_server/goal +/tf2_buffer_server/result +/tf2_buffer_server/status +/tf_static +/tilt_hokuyo_node/parameter_descriptions +/tilt_hokuyo_node/parameter_updates +/tilt_laser_mux/selected +/tilt_scan +/tilt_scan_filtered +/tilt_scan_filtered/navigation +/tilt_scan_filtered/scan +/tilt_scan_interpolated +/tilt_scan_shadow_filtered +/tilt_scan_throttled +/tilt_shadow_filter/dark_shadows/parameter_descriptions +/tilt_shadow_filter/dark_shadows/parameter_updates +/tilt_shadow_filter/shadows/parameter_descriptions +/tilt_shadow_filter/shadows/parameter_updates +/torso_controller/command +/torso_controller/command_deadman +/torso_controller/command_dummy +/torso_controller/follow_joint_trajectory/cancel +/torso_controller/follow_joint_trajectory/feedback +/torso_controller/follow_joint_trajectory/goal +/torso_controller/follow_joint_trajectory/result +/torso_controller/follow_joint_trajectory/status +/torso_controller/gains/torso_lift_joint/parameter_descriptions +/torso_controller/gains/torso_lift_joint/parameter_updates +/torso_controller/joint_trajectory_action/cancel +/torso_controller/joint_trajectory_action/feedback +/torso_controller/joint_trajectory_action/goal +/torso_controller/joint_trajectory_action/result +/torso_controller/joint_trajectory_action/status +/torso_controller/mux/selected +/torso_controller/position_joint_action/cancel +/torso_controller/position_joint_action/feedback +/torso_controller/position_joint_action/goal +/torso_controller/position_joint_action/result +/torso_controller/position_joint_action/status +/torso_controller/state +/torso_lift_imu/data +/torso_lift_imu/is_calibrated +/tuck_arms/cancel +/tuck_arms/feedback +/tuck_arms/goal +/tuck_arms/result +/tuck_arms/status +/tweet +/tweet_client_tablet/parameter_descriptions +/tweet_client_tablet/parameter_updates +/tweet_client_uptime/parameter_descriptions +/tweet_client_uptime/parameter_updates +/tweet_client_warning/parameter_descriptions +/tweet_client_warning/parameter_updates +/tweet_client_worktime/parameter_descriptions +/tweet_client_worktime/parameter_updates +/tweet_compressed_image_mux/selected +/tweet_image +/tweet_image/compressed +/tweet_image_mux/selected +/tweet_image_server/parameter_descriptions +/tweet_image_server/parameter_updates +/tweet_image_server/tweet/cancel +/tweet_image_server/tweet/feedback +/tweet_image_server/tweet/goal +/tweet_image_server/tweet/result +/tweet_image_server/tweet/status +/unsafe_vel_mux/selected +/vel_type_mux/selected +/visualization/battery/value0 +/visualization/battery/value1 +/visualization/battery/value2 +/visualization/battery/value3 +/voice_text/parameter_descriptions +/voice_text/parameter_updates +/wide_stereo/disparity +/wide_stereo/left/camera_info +/wide_stereo/left/image_color +/wide_stereo/left/image_color/compressed +/wide_stereo/left/image_color/compressed/parameter_descriptions +/wide_stereo/left/image_color/compressed/parameter_updates +/wide_stereo/left/image_color/compressedDepth +/wide_stereo/left/image_color/compressedDepth/parameter_descriptions +/wide_stereo/left/image_color/compressedDepth/parameter_updates +/wide_stereo/left/image_color/theora +/wide_stereo/left/image_color/theora/parameter_descriptions +/wide_stereo/left/image_color/theora/parameter_updates +/wide_stereo/left/image_color/zdepth +/wide_stereo/left/image_mono +/wide_stereo/left/image_mono/compressed +/wide_stereo/left/image_mono/compressed/parameter_descriptions +/wide_stereo/left/image_mono/compressed/parameter_updates +/wide_stereo/left/image_mono/compressedDepth +/wide_stereo/left/image_mono/compressedDepth/parameter_descriptions +/wide_stereo/left/image_mono/compressedDepth/parameter_updates +/wide_stereo/left/image_mono/theora +/wide_stereo/left/image_mono/theora/parameter_descriptions +/wide_stereo/left/image_mono/theora/parameter_updates +/wide_stereo/left/image_mono/zdepth +/wide_stereo/left/image_raw +/wide_stereo/left/image_raw/compressed +/wide_stereo/left/image_raw/compressed/parameter_descriptions +/wide_stereo/left/image_raw/compressed/parameter_updates +/wide_stereo/left/image_raw/compressedDepth +/wide_stereo/left/image_raw/compressedDepth/parameter_descriptions +/wide_stereo/left/image_raw/compressedDepth/parameter_updates +/wide_stereo/left/image_raw/theora +/wide_stereo/left/image_raw/theora/parameter_descriptions +/wide_stereo/left/image_raw/theora/parameter_updates +/wide_stereo/left/image_raw/zdepth +/wide_stereo/left/image_rect +/wide_stereo/left/image_rect/compressed +/wide_stereo/left/image_rect/compressed/parameter_descriptions +/wide_stereo/left/image_rect/compressed/parameter_updates +/wide_stereo/left/image_rect/compressedDepth +/wide_stereo/left/image_rect/compressedDepth/parameter_descriptions +/wide_stereo/left/image_rect/compressedDepth/parameter_updates +/wide_stereo/left/image_rect/theora +/wide_stereo/left/image_rect/theora/parameter_descriptions +/wide_stereo/left/image_rect/theora/parameter_updates +/wide_stereo/left/image_rect/zdepth +/wide_stereo/left/image_rect_color +/wide_stereo/left/image_rect_color/compressed +/wide_stereo/left/image_rect_color/compressed/parameter_descriptions +/wide_stereo/left/image_rect_color/compressed/parameter_updates +/wide_stereo/left/image_rect_color/compressedDepth +/wide_stereo/left/image_rect_color/compressedDepth/parameter_descriptions +/wide_stereo/left/image_rect_color/compressedDepth/parameter_updates +/wide_stereo/left/image_rect_color/theora +/wide_stereo/left/image_rect_color/theora/parameter_descriptions +/wide_stereo/left/image_rect_color/theora/parameter_updates +/wide_stereo/left/image_rect_color/zdepth +/wide_stereo/points2 +/wide_stereo/right/camera_info +/wide_stereo/right/image_color +/wide_stereo/right/image_color/compressed +/wide_stereo/right/image_color/compressed/parameter_descriptions +/wide_stereo/right/image_color/compressed/parameter_updates +/wide_stereo/right/image_color/compressedDepth +/wide_stereo/right/image_color/compressedDepth/parameter_descriptions +/wide_stereo/right/image_color/compressedDepth/parameter_updates +/wide_stereo/right/image_color/theora +/wide_stereo/right/image_color/theora/parameter_descriptions +/wide_stereo/right/image_color/theora/parameter_updates +/wide_stereo/right/image_color/zdepth +/wide_stereo/right/image_mono +/wide_stereo/right/image_mono/compressed +/wide_stereo/right/image_mono/compressed/parameter_descriptions +/wide_stereo/right/image_mono/compressed/parameter_updates +/wide_stereo/right/image_mono/compressedDepth +/wide_stereo/right/image_mono/compressedDepth/parameter_descriptions +/wide_stereo/right/image_mono/compressedDepth/parameter_updates +/wide_stereo/right/image_mono/theora +/wide_stereo/right/image_mono/theora/parameter_descriptions +/wide_stereo/right/image_mono/theora/parameter_updates +/wide_stereo/right/image_mono/zdepth +/wide_stereo/right/image_raw +/wide_stereo/right/image_raw/compressed +/wide_stereo/right/image_raw/compressed/parameter_descriptions +/wide_stereo/right/image_raw/compressed/parameter_updates +/wide_stereo/right/image_raw/compressedDepth +/wide_stereo/right/image_raw/compressedDepth/parameter_descriptions +/wide_stereo/right/image_raw/compressedDepth/parameter_updates +/wide_stereo/right/image_raw/theora +/wide_stereo/right/image_raw/theora/parameter_descriptions +/wide_stereo/right/image_raw/theora/parameter_updates +/wide_stereo/right/image_raw/zdepth +/wide_stereo/right/image_rect +/wide_stereo/right/image_rect/compressed +/wide_stereo/right/image_rect/compressed/parameter_descriptions +/wide_stereo/right/image_rect/compressed/parameter_updates +/wide_stereo/right/image_rect/compressedDepth +/wide_stereo/right/image_rect/compressedDepth/parameter_descriptions +/wide_stereo/right/image_rect/compressedDepth/parameter_updates +/wide_stereo/right/image_rect/theora +/wide_stereo/right/image_rect/theora/parameter_descriptions +/wide_stereo/right/image_rect/theora/parameter_updates +/wide_stereo/right/image_rect/zdepth +/wide_stereo/right/image_rect_color +/wide_stereo/right/image_rect_color/compressed +/wide_stereo/right/image_rect_color/compressed/parameter_descriptions +/wide_stereo/right/image_rect_color/compressed/parameter_updates +/wide_stereo/right/image_rect_color/compressedDepth +/wide_stereo/right/image_rect_color/compressedDepth/parameter_descriptions +/wide_stereo/right/image_rect_color/compressedDepth/parameter_updates +/wide_stereo/right/image_rect_color/theora +/wide_stereo/right/image_rect_color/theora/parameter_descriptions +/wide_stereo/right/image_rect_color/theora/parameter_updates +/wide_stereo/right/image_rect_color/zdepth +/wide_stereo/wide_stereo_proc/parameter_descriptions +/wide_stereo/wide_stereo_proc/parameter_updates +/wide_stereo/wide_stereo_proc_debayer_left/parameter_descriptions +/wide_stereo/wide_stereo_proc_debayer_left/parameter_updates +/wide_stereo/wide_stereo_proc_debayer_right/parameter_descriptions +/wide_stereo/wide_stereo_proc_debayer_right/parameter_updates +/wide_stereo/wide_stereo_proc_rectify_color_left/parameter_descriptions +/wide_stereo/wide_stereo_proc_rectify_color_left/parameter_updates +/wide_stereo/wide_stereo_proc_rectify_color_right/parameter_descriptions +/wide_stereo/wide_stereo_proc_rectify_color_right/parameter_updates +/wide_stereo/wide_stereo_proc_rectify_mono_left/parameter_descriptions +/wide_stereo/wide_stereo_proc_rectify_mono_left/parameter_updates +/wide_stereo/wide_stereo_proc_rectify_mono_right/parameter_descriptions +/wide_stereo/wide_stereo_proc_rectify_mono_right/parameter_updates +/wide_stereo_both/parameter_descriptions +/wide_stereo_both/parameter_updates +/wide_stereo_left/parameter_descriptions +/wide_stereo_left/parameter_updates +/wide_stereo_right/parameter_descriptions +/wide_stereo_right/parameter_updates +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rostopic echo /speech_to_text + C-c C-c +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ [http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rostopic info /speech_to_text +Type: speech_recognition_msgs/SpeechRecognitionCandidates + +Publishers: + * /speech_to_text_mux (http://pr1040:41547/) + +Subscribers: + * /dialogflow_client (http://pr1040:36871/) + * /lifelog/speech_logger (http://pr1040s:34059/) + + +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rostopic echo /speech_to_text +transcript: + - "\u805E\u3053\u3048\u308B" +confidence: [1.0] +--- +--- C-c C-c[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rosesu +rosesu: command not found +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ load "main.l" + +Command 'load' not found, did you mean: + + command 'tload' from deb procps (2:3.3.16-1ubuntu2.4) + command 'xload' from deb x11-apps (7.7+8) + command 'nload' from deb nload (0.7.4-2build3) + +Try: sudo apt install + +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ roseus +configuring by "/opt/ros/noetic/share/euslisp/jskeus/eus//lib/eusrt.l" +;; readmacro ;; object ;; packsym ;; common ;; constants ;; stream ;; string ;; loader ;; pprint ;; process ;; hashtab ;; array ;; mathtran ;; eusdebug ;; eusforeign ;; extnum ;; coordinates ;; tty ;; history ;; toplevel ;; trans ;; comp ;; builtins ;; par ;; intersection ;; geoclasses ;; geopack ;; geobody ;; primt ;; compose ;; polygon ;; viewing ;; viewport ;; viewsurface ;; hid ;; shadow ;; bodyrel ;; dda ;; helpsub ;; eushelp ;; xforeign ;; Xdecl ;; Xgraphics ;; Xcolor ;; Xeus ;; Xevent ;; Xpanel ;; Xitem ;; Xtext ;; Xmenu ;; Xscroll ;; Xcanvas ;; Xtop ;; Xapplwin +connected to Xserver DISPLAY=:0 +X events are being asynchronously monitored. +;; pixword ;; RGBHLS ;; convolve ;; piximage ;; pbmfile ;; image_correlation ;; oglforeign ;; gldecl ;; glconst ;; glforeign ;; gluconst ;; gluforeign ;; glxconst ;; glxforeign ;; eglforeign ;; eglfunc ;; glutil ;; gltexture ;; glprim ;; gleus ;; glview ;; toiv-undefined ;; fstringdouble irtmath irtutil irtc irtgeoc irtgraph gnuplotlib ___time ___pgsql irtgeo euspqp pqp irtscene irtmodel irtdyna irtrobot irtsensor irtbvh irtcollada irtstl irtwrl irtpointcloud eusbullet bullet irtcollision irtx eusjpeg euspng png irtimage irtglrgb +;; extending gcstack 0x55f3ee64c680[16374] --> 0x55f3eeadcc90[32748] top=3d4b +irtgl irtglc irtviewer +EusLisp 9.29( 1.2.5) for Linux64 created on ip-10-0-1-5(Tue Jun 20 10:34:21 PST 2023) +roseus ;; loading roseus("1.7.5") on euslisp((9.29 ip-10-0-1-5 Tue Jun 20 10:34:21 PST 2023 1.2.5)) +eustf roseus_c_util 1.irteusgl$ load "main.l" +;; roseus_resume is disabled. + +;; extending gcstack 0x55f3eeadcc90[32738] --> 0x55f3f05fa6e0[65476] top=7ed2 +;; # :joint-angle(11.498) violate min-angle(11.5) +;; # :joint-angle(-22.47) violate min-angle(-21.2682) +;; (make-irtviewer) executed +;; # :joint-angle(11.498) violate min-angle(11.5) +;; # :joint-angle(-22.47) violate min-angle(-21.2682) +;; # :joint-angle(11.498) violate min-angle(11.5) +;; # :joint-angle(-22.47) violate min-angle(-21.2682) +;; # :joint-angle(11.498) violate min-angle(11.5) +;; # :joint-angle(-22.47) violate min-angle(-21.2682) +;; # :joint-angle(11.498) violate min-angle(11.5) +;; # :joint-angle(-22.47) violate min-angle(-21.2682) +;; # :joint-angle(11.498) violate min-angle(11.5) +;; # :joint-angle(-22.47) violate min-angle(-21.2682) +;; # :joint-angle(11.498) violate min-angle(11.5) +;; # :joint-angle(-22.47) violate min-angle(-21.2682) +;; # :joint-angle(11.498) violate min-angle(11.5) +;; # :joint-angle(-22.464) violate min-angle(-21.2682) +[ WARN] [1732680445.354428130]: continuous joint (l_wrist_roll_joint) moves 262.683 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732680445.358260911]: continuous joint (r_wrist_roll_joint) moves 262.537 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(11.498) violate min-angle(11.5) +;; # :joint-angle(-22.47) violate min-angle(-21.2682) +;; # :joint-angle(11.498) violate min-angle(11.5) +;; # :joint-angle(-22.47) violate min-angle(-21.2682) +;; # :joint-angle(11.498) violate min-angle(11.5) +;; # :joint-angle(-22.47) violate min-angle(-21.2682) +;; # :joint-angle(11.498) violate min-angle(11.5) +;; # :joint-angle(-22.47) violate min-angle(-21.2682) +;; # :joint-angle(11.498) violate min-angle(11.5) +;; # :joint-angle(-22.47) violate min-angle(-21.2682) +;; # :joint-angle(11.498) violate min-angle(11.5) +;; # :joint-angle(-22.464) violate min-angle(-21.2682) +[ WARN] [1732680445.366116476]: continuous joint (l_wrist_roll_joint) moves 262.683 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732680445.366231572]: continuous joint (r_wrist_roll_joint) moves 262.537 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732680445.366275431]: original trajectory command : +[ WARN] [1732680445.366315264]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732680445.366356499]: current angle vector : #f(11.5 42.0139 54.882 48.4774 -114.483 9.49731 -32.7332 -82.6834 -38.3183 57.7408 0.956988 -113.91 7.16945 -22.1737 -82.537 5.93953 -21.2682) +[ WARN] [1732680445.366408619]: new trajectory command : dvi = 2 +[ WARN] [1732680445.366488851]: : #f(30.75 51.0069 64.441 59.2387 -117.241 14.7487 -31.3666 48.6583 -49.1591 65.8704 -34.5215 -116.955 -6.41528 -26.0868 48.7315 2.96977 -10.6341) 500 +[ WARN] [1732680445.366559106]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732680445.366599827]: new trajectory command : +[ WARN] [1732680445.366666956]: : (#f(30.75 51.0069 64.441 59.2387 -117.241 14.7487 -31.3666 48.6583 -49.1591 65.8704 -34.5215 -116.955 -6.41528 -26.0868 48.7315 2.96977 -10.6341) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +;; # :joint-angle(11.498) violate min-angle(11.5) +;; # :joint-angle(-22.47) violate min-angle(-21.2682) +[ INFO] [1732680445.404807221]: wait-interpolation debug: start +[ERROR] [1732680448.461568450]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732680448.461628952]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732680448.468967629]: wait-interpolation debug: end +[ INFO] [1732680449.265460493]: wait-interpolation debug: start +[ERROR] [1732680450.863982138]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732680450.864109184]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732680450.875791843]: wait-interpolation debug: end +[ INFO] [1732680456.936541513]: wait-interpolation debug: start +[ INFO] [1732680456.944343402]: wait-interpolation debug: end +[ INFO] [1732680466.746616546]: wait-interpolation debug: start +[ INFO] [1732680466.748011050]: wait-interpolation debug: end + C-c C-cinterrupt2.B1-irteusgl$ load "main.l" +[ WARN] [1732680597.543717236]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732680597.543756620]: expected goal id 1732680466750360214_/pr2_eus_interface_1732680438716966801_7838_robotsound_jp_3 +[ WARN] [1732680597.543778956]: received goal id /pr2_calibration_warning-1-1732680579.005 +[ WARN] [1732680597.574985886]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732680597.575109875]: expected goal id 1732680597544001760_/pr2_eus_interface_1732680438716966801_7838_robotsound_jp_4 +[ WARN] [1732680597.575172401]: received goal id /pr2_calibration_warning-2-1732680591.185 +;; # :joint-angle(11.4983) violate min-angle(11.5) +;; # :joint-angle(-22.146) violate min-angle(-21.2682) +;; # :joint-angle(11.4983) violate min-angle(11.5) +;; # :joint-angle(-22.146) violate min-angle(-21.2682) +;; # :joint-angle(11.4983) violate min-angle(11.5) +;; # :joint-angle(-22.146) violate min-angle(-21.2682) +;; # :joint-angle(11.4983) violate min-angle(11.5) +;; # :joint-angle(-22.146) violate min-angle(-21.2682) +;; # :joint-angle(11.4983) violate min-angle(11.5) +;; # :joint-angle(-22.146) violate min-angle(-21.2682) +;; # :joint-angle(11.4983) violate min-angle(11.5) +;; # :joint-angle(-22.146) violate min-angle(-21.2682) +;; # :joint-angle(11.4982) violate min-angle(11.5) +;; # :joint-angle(-22.146) violate min-angle(-21.2682) +[ WARN] [1732680601.588656731]: continuous joint (l_wrist_roll_joint) moves 263.007 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732680601.588821981]: continuous joint (r_wrist_roll_joint) moves 262.97 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(11.4983) violate min-angle(11.5) +;; # :joint-angle(-22.146) violate min-angle(-21.2682) +;; # :joint-angle(11.4983) violate min-angle(11.5) +;; # :joint-angle(-22.146) violate min-angle(-21.2682) +;; # :joint-angle(11.4983) violate min-angle(11.5) +;; # :joint-angle(-22.146) violate min-angle(-21.2682) +;; # :joint-angle(11.4983) violate min-angle(11.5) +;; # :joint-angle(-22.146) violate min-angle(-21.2682) +;; # :joint-angle(11.4983) violate min-angle(11.5) +;; # :joint-angle(-22.146) violate min-angle(-21.2682) +;; # :joint-angle(11.4982) violate min-angle(11.5) +;; # :joint-angle(-22.146) violate min-angle(-21.2682) +[ WARN] [1732680601.597808776]: continuous joint (l_wrist_roll_joint) moves 263.007 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732680601.597936689]: continuous joint (r_wrist_roll_joint) moves 262.97 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732680601.598004893]: original trajectory command : +[ WARN] [1732680601.598054265]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732680601.598106757]: current angle vector : #f(11.5 40.1566 57.3637 2.5483 -114.574 10.2132 -31.7809 -83.0075 -40.0806 57.5857 0.561919 -114.391 8.11073 -21.867 -82.9698 6.63553 -21.2682) +[ WARN] [1732680601.598139494]: new trajectory command : dvi = 2 +[ WARN] [1732680601.598202567]: : #f(30.75 50.0783 65.6818 36.2742 -117.287 15.1066 -30.8904 48.4963 -50.0403 65.7928 -34.719 -117.196 -5.94463 -25.9335 48.5151 3.31777 -10.6341) 500 +[ WARN] [1732680601.598258348]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732680601.598287866]: new trajectory command : +[ WARN] [1732680601.598352168]: : (#f(30.75 50.0783 65.6818 36.2742 -117.287 15.1066 -30.8904 48.4963 -50.0403 65.7928 -34.719 -117.196 -5.94463 -25.9335 48.5151 3.31777 -10.6341) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +;; # :joint-angle(11.4983) violate min-angle(11.5) +;; # :joint-angle(-22.146) violate min-angle(-21.2682) +[ INFO] [1732680601.604550283]: wait-interpolation debug: start +[ERROR] [1732680604.667243682]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732680604.667294660]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732680604.667669027]: wait-interpolation debug: end +[ INFO] [1732680605.470119749]: wait-interpolation debug: start +[ERROR] [1732680607.070154229]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732680607.070245227]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732680607.079003049]: wait-interpolation debug: end +[ INFO] [1732680613.354621668]: wait-interpolation debug: start +[ INFO] [1732680613.355094431]: wait-interpolation debug: end +[ INFO] [1732680623.058016512]: wait-interpolation debug: start +[ INFO] [1732680623.064321015]: wait-interpolation debug: end +[ INFO] [1732680629.617541131]: wait-interpolation debug: start +[ INFO] [1732680630.620370017]: wait-interpolation debug: end +[ INFO] [1732680630.657386378]: wait-interpolation debug: start +[ INFO] [1732680631.798445433]: wait-interpolation debug: end +[ INFO] [1732680631.889460380]: wait-interpolation debug: start +[ERROR] [1732680633.495022228]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732680633.495095722]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732680633.505758819]: wait-interpolation debug: end +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0131) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0588) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.068) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732680634.391569599]: wait-interpolation debug: start +[ INFO] [1732680635.395833912]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732680635.437114854]: wait-interpolation debug: start +[ INFO] [1732680636.440220511]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732680636.484734056]: wait-interpolation debug: start +[ INFO] [1732680637.485572764]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732680637.525934037]: wait-interpolation debug: start +[ INFO] [1732680638.526264204]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732680638.564225251]: wait-interpolation debug: start +[ INFO] [1732680639.565766601]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732680639.602003182]: wait-interpolation debug: start +[ INFO] [1732680640.600140265]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732680640.657293768]: wait-interpolation debug: start +[ INFO] [1732680641.653812179]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732680641.689183900]: wait-interpolation debug: start +[ INFO] [1732680642.704729665]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732680642.740588757]: wait-interpolation debug: start +[ INFO] [1732680643.741364957]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732680643.776968501]: wait-interpolation debug: start +[ INFO] [1732680644.776592791]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732680646.887223219]: wait-interpolation debug: start +[ INFO] [1732680646.887619429]: wait-interpolation debug: end +[ INFO] [1732680649.705636718]: wait-interpolation debug: start +[ INFO] [1732680649.706443742]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732680649.745178314]: wait-interpolation debug: start +[ INFO] [1732680650.753578222]: wait-interpolation debug: end +[ INFO] [1732680650.834195710]: wait-interpolation debug: start +[ERROR] [1732680657.287315189]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732680657.287359515]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732680657.287866980]: wait-interpolation debug: end +[ INFO] [1732680659.326819960]: wait-interpolation debug: start +[ INFO] [1732680660.326464798]: wait-interpolation debug: end +[ INFO] [1732680662.277758758]: wait-interpolation debug: start +[ INFO] [1732680662.278126301]: wait-interpolation debug: end +[ INFO] [1732680663.292218806]: wait-interpolation debug: start +[ INFO] [1732680663.296388022]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732680668.691519350]: wait-interpolation debug: start +[ERROR] [1732680670.291482113]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732680670.291552321]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732680670.298069854]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(-20.26) violate min-angle(-20.2598) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(-20.26) violate min-angle(-20.2598) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(-20.26) violate min-angle(-20.2598) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(-20.26) violate min-angle(-20.2598) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(-20.26) violate min-angle(-20.2598) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(-20.26) violate min-angle(-20.2598) +[ INFO] [1732680670.380320773]: wait-interpolation debug: start +[ INFO] [1732680671.377761047]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732680671.416169729]: wait-interpolation debug: start +[ INFO] [1732680672.420760383]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732680672.461575047]: wait-interpolation debug: start +[ INFO] [1732680673.461423816]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732680673.496950772]: wait-interpolation debug: start +[ INFO] [1732680674.501348802]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732680674.547033726]: wait-interpolation debug: start +[ INFO] [1732680675.551538509]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732680675.586957745]: wait-interpolation debug: start +[ INFO] [1732680676.584657365]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732680676.633914980]: wait-interpolation debug: start +[ INFO] [1732680677.631771897]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732680677.666617003]: wait-interpolation debug: start +[ INFO] [1732680678.666659752]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732680678.707819678]: wait-interpolation debug: start +[ INFO] [1732680679.714328871]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732680679.753313702]: wait-interpolation debug: start +[ INFO] [1732680680.753314647]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732680682.925794411]: wait-interpolation debug: start +[ INFO] [1732680682.926105873]: wait-interpolation debug: end +[ INFO] [1732680685.743786057]: wait-interpolation debug: start +[ INFO] [1732680685.747170085]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732680685.787856301]: wait-interpolation debug: start +[ INFO] [1732680686.791373614]: wait-interpolation debug: end +[ INFO] [1732680686.852124640]: wait-interpolation debug: start +[ERROR] [1732680690.158374953]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732680690.158416618]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732680690.162565667]: wait-interpolation debug: end +[ INFO] [1732680691.304669266]: wait-interpolation debug: start +[ INFO] [1732680692.778143043]: wait-interpolation debug: end +[ INFO] [1732680694.774952748]: wait-interpolation debug: start +[ INFO] [1732680694.776595444]: wait-interpolation debug: end +[ INFO] [1732680695.806423924]: wait-interpolation debug: start +[ INFO] [1732680695.817585085]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732680701.222384921]: wait-interpolation debug: start +[ERROR] [1732680702.818076002]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732680702.818144698]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732680702.818835048]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732680702.818908493]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732680702.824492741]: wait-interpolation debug: end +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +[ INFO] [1732680703.904352999]: wait-interpolation debug: start +[ INFO] [1732680704.924771764]: wait-interpolation debug: end +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +[ INFO] [1732680705.036278750]: wait-interpolation debug: start +[ INFO] [1732680706.035160639]: wait-interpolation debug: end +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +[ INFO] [1732680706.073031268]: wait-interpolation debug: start +[ INFO] [1732680707.087165388]: wait-interpolation debug: end +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +[ INFO] [1732680707.126635463]: wait-interpolation debug: start +[ INFO] [1732680708.144175447]: wait-interpolation debug: end +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +[ INFO] [1732680708.185469633]: wait-interpolation debug: start +[ INFO] [1732680709.186284543]: wait-interpolation debug: end +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +[ INFO] [1732680709.222962149]: wait-interpolation debug: start +[ INFO] [1732680710.226026767]: wait-interpolation debug: end +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +[ INFO] [1732680710.263018508]: wait-interpolation debug: start +[ INFO] [1732680711.286149068]: wait-interpolation debug: end +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +[ INFO] [1732680711.326452975]: wait-interpolation debug: start +[ INFO] [1732680712.326775472]: wait-interpolation debug: end +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +[ INFO] [1732680712.377904385]: wait-interpolation debug: start +[ INFO] [1732680713.378413368]: wait-interpolation debug: end +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +[ INFO] [1732680713.415887442]: wait-interpolation debug: start +[ INFO] [1732680714.415176213]: wait-interpolation debug: end +;; # :joint-angle(88.0561) violate max-angle(88.0) +[ INFO] [1732680716.601814402]: wait-interpolation debug: start +[ INFO] [1732680716.602086062]: wait-interpolation debug: end +[ INFO] [1732680719.416554407]: wait-interpolation debug: start +[ INFO] [1732680719.417297438]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732680719.460149005]: wait-interpolation debug: start +[ INFO] [1732680720.464670207]: wait-interpolation debug: end +[ INFO] [1732680720.526457830]: wait-interpolation debug: start +[ERROR] [1732680721.764856135]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732680721.764906960]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732680721.765502627]: wait-interpolation debug: end +[ INFO] [1732680722.305170672]: wait-interpolation debug: start +[ INFO] [1732680723.784165726]: wait-interpolation debug: end +[ INFO] [1732680725.732124762]: wait-interpolation debug: start +[ INFO] [1732680725.732536256]: wait-interpolation debug: end +[ INFO] [1732680726.764136902]: wait-interpolation debug: start +[ INFO] [1732680726.777151864]: wait-interpolation debug: end +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +[ INFO] [1732680732.193317684]: wait-interpolation debug: start +[ERROR] [1732680733.790936393]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732680733.790982607]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732680733.791381771]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732680733.791405146]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732680733.795171047]: wait-interpolation debug: end +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +[ INFO] [1732680734.097420276]: wait-interpolation debug: start +[ INFO] [1732680735.104097099]: wait-interpolation debug: end +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +[ INFO] [1732680735.144790579]: wait-interpolation debug: start +[ INFO] [1732680736.145529516]: wait-interpolation debug: end +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +[ INFO] [1732680736.181907684]: wait-interpolation debug: start +[ INFO] [1732680737.181900533]: wait-interpolation debug: end +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +[ INFO] [1732680737.218112096]: wait-interpolation debug: start +[ INFO] [1732680738.236783101]: wait-interpolation debug: end +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +[ INFO] [1732680738.277419369]: wait-interpolation debug: start +[ INFO] [1732680739.276955039]: wait-interpolation debug: end +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +[ INFO] [1732680739.316051133]: wait-interpolation debug: start +[ INFO] [1732680740.317382854]: wait-interpolation debug: end +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +[ INFO] [1732680740.356845738]: wait-interpolation debug: start +[ INFO] [1732680741.358595546]: wait-interpolation debug: end +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +[ INFO] [1732680741.398654008]: wait-interpolation debug: start +[ INFO] [1732680742.400205591]: wait-interpolation debug: end +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +[ INFO] [1732680742.447124167]: wait-interpolation debug: start +[ INFO] [1732680743.446582685]: wait-interpolation debug: end +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +;; # :joint-angle(88.0552) violate max-angle(88.0) +[ INFO] [1732680743.486588112]: wait-interpolation debug: start +[ INFO] [1732680744.485481700]: wait-interpolation debug: end +;; # :joint-angle(88.0552) violate max-angle(88.0) +[ INFO] [1732680746.678451155]: wait-interpolation debug: start +[ INFO] [1732680746.678636747]: wait-interpolation debug: end +[ INFO] [1732680749.501698392]: wait-interpolation debug: start +[ INFO] [1732680749.506459666]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732680749.551382048]: wait-interpolation debug: start +[ INFO] [1732680750.554312786]: wait-interpolation debug: end +[ INFO] [1732680750.654383988]: wait-interpolation debug: start +[ INFO] [1732680751.656729255]: wait-interpolation debug: end +[ INFO] [1732680751.742193282]: wait-interpolation debug: start +[ INFO] [1732680753.182731558]: wait-interpolation debug: end +[ INFO] [1732680755.151025278]: wait-interpolation debug: start +[ INFO] [1732680755.152079008]: wait-interpolation debug: end +[ INFO] [1732680756.182906692]: wait-interpolation debug: start +[ INFO] [1732680756.194654782]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732680761.637592331]: wait-interpolation debug: start +[ERROR] [1732680763.237380990]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732680763.237433194]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732680763.238004791]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732680763.238039048]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732680763.245807668]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732680764.307377607]: wait-interpolation debug: start +[ INFO] [1732680765.314003290]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732680765.355682351]: wait-interpolation debug: start +[ INFO] [1732680766.356599846]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732680766.394472874]: wait-interpolation debug: start +[ INFO] [1732680767.396186763]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732680767.434287279]: wait-interpolation debug: start +[ INFO] [1732680768.436545051]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732680768.475340530]: wait-interpolation debug: start +[ INFO] [1732680769.476667155]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732680769.517494328]: wait-interpolation debug: start +[ INFO] [1732680770.517650320]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732680770.553377495]: wait-interpolation debug: start +[ INFO] [1732680771.557418328]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732680771.625061329]: wait-interpolation debug: start +[ INFO] [1732680772.673550685]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732680772.708289134]: wait-interpolation debug: start +[ INFO] [1732680773.715859826]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732680773.784904799]: wait-interpolation debug: start +[ INFO] [1732680774.786529098]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732680776.995041369]: wait-interpolation debug: start +[ INFO] [1732680776.995236283]: wait-interpolation debug: end +[ INFO] [1732680779.801626328]: wait-interpolation debug: start +[ INFO] [1732680779.807663234]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732680779.851819079]: wait-interpolation debug: start +[ INFO] [1732680780.857942197]: wait-interpolation debug: end +[ INFO] [1732680780.923934316]: wait-interpolation debug: start +[ INFO] [1732680781.924641827]: wait-interpolation debug: end +[ INFO] [1732680781.966495105]: wait-interpolation debug: start +[ INFO] [1732680783.437895985]: wait-interpolation debug: end +[ INFO] [1732680785.398971300]: wait-interpolation debug: start +[ INFO] [1732680785.404248181]: wait-interpolation debug: end +[ INFO] [1732680786.432714688]: wait-interpolation debug: start +[ INFO] [1732680786.447174857]: wait-interpolation debug: end +t +3.B1-irteusgl$ load "main.l" +[ WARN] [1732681258.970540439]: [/r_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732681258.970593154]: expected goal id 1732681258946866793_/pr2_eus_interface_1732680438716966801_7838_/r_gripper_controller/gripper_action_17 +[ WARN] [1732681258.970619520]: received goal id 1732680786405175558_/pr2_eus_interface_1732680438716966801_7838_/r_gripper_controller/gripper_action_16 +[ WARN] [1732681261.355281973]: continuous joint (r_forearm_roll_joint) moves -182.261 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681261.355340849]: continuous joint (r_wrist_roll_joint) moves 228.877 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681261.358459527]: continuous joint (r_forearm_roll_joint) moves -182.261 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681261.358589463]: continuous joint (r_wrist_roll_joint) moves 228.877 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681261.358699772]: original trajectory command : +[ WARN] [1732681261.358750394]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732681261.358814993]: current angle vector : #f(207.807 1.42207 -14.2526 84.3761 -32.4836 86.9082 -104.992 237.828 -5.36945 33.4079 -39.8484 -95.5138 162.261 -66.5007 -48.8775 0.0 0.0) +[ WARN] [1732681261.358874118]: new trajectory command : dvi = 2 +[ WARN] [1732681261.358997070]: : #f(128.903 30.711 29.8737 77.188 -76.2418 53.4541 -67.4962 208.914 -32.6847 53.7039 -54.9242 -107.757 71.1307 -48.2503 65.5613 0.0 0.0) 500 +[ WARN] [1732681261.359046458]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732681261.359091332]: new trajectory command : +[ WARN] [1732681261.359172101]: : (#f(128.903 30.711 29.8737 77.188 -76.2418 53.4541 -67.4962 208.914 -32.6847 53.7039 -54.9242 -107.757 71.1307 -48.2503 65.5613 0.0 0.0) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732681261.367007720]: wait-interpolation debug: start +[ERROR] [1732681273.614542678]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681273.614584865]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681273.614907077]: wait-interpolation debug: end +[ INFO] [1732681277.275355313]: wait-interpolation debug: start +[ERROR] [1732681278.882393201]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681278.882448341]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681278.887135802]: wait-interpolation debug: end +[ INFO] [1732681285.017178602]: wait-interpolation debug: start +[ INFO] [1732681285.017474074]: wait-interpolation debug: end +[ INFO] [1732681294.767670062]: wait-interpolation debug: start +[ INFO] [1732681294.768410727]: wait-interpolation debug: end +[ INFO] [1732681301.281347060]: wait-interpolation debug: start +[ INFO] [1732681302.278458300]: wait-interpolation debug: end +[ INFO] [1732681302.344669062]: wait-interpolation debug: start +[ INFO] [1732681303.476664608]: wait-interpolation debug: end +[ INFO] [1732681303.541789776]: wait-interpolation debug: start +[ERROR] [1732681305.136164546]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681305.136220849]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681305.141866513]: wait-interpolation debug: end +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0422) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0911) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0766) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0718) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0704) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +[ INFO] [1732681305.965201662]: wait-interpolation debug: start +[ INFO] [1732681307.017754793]: wait-interpolation debug: end +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +[ INFO] [1732681307.057065906]: wait-interpolation debug: start +[ INFO] [1732681308.062598450]: wait-interpolation debug: end +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +[ INFO] [1732681308.097930559]: wait-interpolation debug: start +[ INFO] [1732681309.110770475]: wait-interpolation debug: end +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +[ INFO] [1732681309.146343586]: wait-interpolation debug: start +[ INFO] [1732681310.163809056]: wait-interpolation debug: end +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +[ INFO] [1732681310.198077410]: wait-interpolation debug: start +[ INFO] [1732681311.213244200]: wait-interpolation debug: end +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +[ INFO] [1732681311.248187069]: wait-interpolation debug: start +[ INFO] [1732681312.285877272]: wait-interpolation debug: end +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +[ INFO] [1732681312.322624111]: wait-interpolation debug: start +[ INFO] [1732681313.365345252]: wait-interpolation debug: end +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +[ INFO] [1732681313.401840300]: wait-interpolation debug: start +[ INFO] [1732681314.414686803]: wait-interpolation debug: end +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +[ INFO] [1732681314.461899510]: wait-interpolation debug: start +[ INFO] [1732681315.471903999]: wait-interpolation debug: end +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +;; # :joint-angle(88.0689) violate max-angle(88.0) +[ INFO] [1732681315.507650827]: wait-interpolation debug: start +[ INFO] [1732681316.522163406]: wait-interpolation debug: end +;; # :joint-angle(88.0689) violate max-angle(88.0) +[ INFO] [1732681318.629355421]: wait-interpolation debug: start +[ INFO] [1732681318.633173678]: wait-interpolation debug: end +[ INFO] [1732681321.448147383]: wait-interpolation debug: start +[ INFO] [1732681321.448849275]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732681321.526074553]: wait-interpolation debug: start +[ INFO] [1732681322.536479071]: wait-interpolation debug: end +[ INFO] [1732681322.632310549]: wait-interpolation debug: start +[ERROR] [1732681329.073190996]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681329.073238392]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681329.077823284]: wait-interpolation debug: end +[ INFO] [1732681331.136409542]: wait-interpolation debug: start +[ INFO] [1732681332.146066290]: wait-interpolation debug: end +[ INFO] [1732681334.098212311]: wait-interpolation debug: start +[ INFO] [1732681334.098391502]: wait-interpolation debug: end +[ INFO] [1732681335.122901363]: wait-interpolation debug: start +[ INFO] [1732681335.134165065]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732681340.578667071]: wait-interpolation debug: start +[ERROR] [1732681342.174915889]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681342.174965672]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681342.176928125]: wait-interpolation debug: end +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(-20.2648) violate min-angle(-20.2598) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +[ INFO] [1732681342.754878879]: wait-interpolation debug: start +[ INFO] [1732681343.756789082]: wait-interpolation debug: end +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +[ INFO] [1732681343.798568589]: wait-interpolation debug: start +[ INFO] [1732681344.795171425]: wait-interpolation debug: end +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +[ INFO] [1732681344.836455881]: wait-interpolation debug: start +[ INFO] [1732681345.839019812]: wait-interpolation debug: end +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +[ INFO] [1732681345.880934104]: wait-interpolation debug: start +[ INFO] [1732681346.886703362]: wait-interpolation debug: end +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +[ INFO] [1732681346.927691185]: wait-interpolation debug: start +[ INFO] [1732681347.928103472]: wait-interpolation debug: end +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +[ INFO] [1732681347.967978492]: wait-interpolation debug: start +[ INFO] [1732681348.991422746]: wait-interpolation debug: end +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +[ INFO] [1732681349.026925219]: wait-interpolation debug: start +[ INFO] [1732681350.031277726]: wait-interpolation debug: end +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +[ INFO] [1732681350.068236943]: wait-interpolation debug: start +[ INFO] [1732681351.071340891]: wait-interpolation debug: end +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +[ INFO] [1732681351.109153756]: wait-interpolation debug: start +[ INFO] [1732681352.121513699]: wait-interpolation debug: end +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +;; # :joint-angle(88.0573) violate max-angle(88.0) +[ INFO] [1732681352.163614992]: wait-interpolation debug: start +[ INFO] [1732681353.161215811]: wait-interpolation debug: end +;; # :joint-angle(88.0573) violate max-angle(88.0) +[ INFO] [1732681355.396615653]: wait-interpolation debug: start +[ INFO] [1732681355.397146242]: wait-interpolation debug: end +[ INFO] [1732681358.207152310]: wait-interpolation debug: start +[ INFO] [1732681358.208453240]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732681358.278480199]: wait-interpolation debug: start +[ INFO] [1732681359.277645810]: wait-interpolation debug: end +[ INFO] [1732681359.372225401]: wait-interpolation debug: start +[ERROR] [1732681362.680727086]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681362.680784837]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681362.686356187]: wait-interpolation debug: end +[ INFO] [1732681363.818367415]: wait-interpolation debug: start +[ INFO] [1732681365.300144855]: wait-interpolation debug: end +[ INFO] [1732681367.279941006]: wait-interpolation debug: start +[ INFO] [1732681367.286329098]: wait-interpolation debug: end +[ INFO] [1732681368.298833707]: wait-interpolation debug: start +[ INFO] [1732681368.303735403]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732681373.726454496]: wait-interpolation debug: start +[ERROR] [1732681375.322703000]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681375.322753613]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732681375.323205898]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681375.323230694]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681375.327611981]: wait-interpolation debug: end +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732681376.348814654]: wait-interpolation debug: start +[ INFO] [1732681377.362195453]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732681377.425378897]: wait-interpolation debug: start +[ INFO] [1732681378.430773987]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732681378.471987525]: wait-interpolation debug: start +[ INFO] [1732681379.478176706]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732681379.517774504]: wait-interpolation debug: start +[ INFO] [1732681380.522111847]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732681380.562658706]: wait-interpolation debug: start +[ INFO] [1732681381.565474315]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732681381.608035567]: wait-interpolation debug: start +[ INFO] [1732681382.610800321]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732681382.650818734]: wait-interpolation debug: start +[ INFO] [1732681383.666290107]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732681383.705343469]: wait-interpolation debug: start +[ INFO] [1732681384.710846381]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732681384.776619538]: wait-interpolation debug: start +[ INFO] [1732681385.779498300]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732681385.848262902]: wait-interpolation debug: start +[ INFO] [1732681386.858365026]: wait-interpolation debug: end +;; # :joint-angle(88.0555) violate max-angle(88.0) +[ INFO] [1732681389.136599133]: wait-interpolation debug: start +[ INFO] [1732681389.142559324]: wait-interpolation debug: end +[ INFO] [1732681391.962431652]: wait-interpolation debug: start +[ INFO] [1732681391.967763952]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732681392.008068651]: wait-interpolation debug: start +[ INFO] [1732681393.011319384]: wait-interpolation debug: end +[ INFO] [1732681393.086392897]: wait-interpolation debug: start +[ERROR] [1732681394.355751032]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681394.355805186]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681394.363142399]: wait-interpolation debug: end +[ INFO] [1732681394.886835889]: wait-interpolation debug: start +[ INFO] [1732681396.379131103]: wait-interpolation debug: end +[ INFO] [1732681398.332795063]: wait-interpolation debug: start +[ INFO] [1732681398.333115820]: wait-interpolation debug: end +[ INFO] [1732681399.361782864]: wait-interpolation debug: start +[ INFO] [1732681399.376917131]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732681404.788462482]: wait-interpolation debug: start +[ERROR] [1732681406.387396970]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681406.387452128]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732681406.387883423]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681406.387910862]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681406.388757665]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732681406.433732375]: wait-interpolation debug: start +[ INFO] [1732681407.644426301]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732681407.711604504]: wait-interpolation debug: start +[ INFO] [1732681408.713799528]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732681408.756778841]: wait-interpolation debug: start +[ INFO] [1732681409.756568600]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732681409.812971259]: wait-interpolation debug: start +[ INFO] [1732681410.811525510]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732681410.854948572]: wait-interpolation debug: start +[ INFO] [1732681411.862932659]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732681411.904508553]: wait-interpolation debug: start +[ INFO] [1732681412.913602618]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732681412.955465844]: wait-interpolation debug: start +[ INFO] [1732681413.964347106]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732681414.004105550]: wait-interpolation debug: start +[ INFO] [1732681415.010806845]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732681415.052215365]: wait-interpolation debug: start +[ INFO] [1732681416.053815559]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732681416.093811428]: wait-interpolation debug: start +[ INFO] [1732681417.093263262]: wait-interpolation debug: end +;; # :joint-angle(88.0567) violate max-angle(88.0) +[ INFO] [1732681419.354755981]: wait-interpolation debug: start +[ INFO] [1732681419.356576224]: wait-interpolation debug: end +[ INFO] [1732681422.176577438]: wait-interpolation debug: start +[ INFO] [1732681422.177441911]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732681422.214650325]: wait-interpolation debug: start +[ INFO] [1732681423.242508969]: wait-interpolation debug: end +[ INFO] [1732681423.308774383]: wait-interpolation debug: start +[ INFO] [1732681424.313721175]: wait-interpolation debug: end +[ INFO] [1732681424.389906983]: wait-interpolation debug: start +[ INFO] [1732681425.855420369]: wait-interpolation debug: end +[ INFO] [1732681427.803682865]: wait-interpolation debug: start +[ INFO] [1732681427.805226489]: wait-interpolation debug: end +[ INFO] [1732681428.839090643]: wait-interpolation debug: start +[ INFO] [1732681428.847071201]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732681434.281422485]: wait-interpolation debug: start +[ERROR] [1732681435.903428726]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681435.903469839]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732681435.903786656]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681435.903808229]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681435.904440006]: wait-interpolation debug: end +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +[ INFO] [1732681436.928186389]: wait-interpolation debug: start +[ INFO] [1732681437.931241329]: wait-interpolation debug: end +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +[ INFO] [1732681437.978587815]: wait-interpolation debug: start +[ INFO] [1732681438.982455981]: wait-interpolation debug: end +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +[ INFO] [1732681439.021248270]: wait-interpolation debug: start +[ INFO] [1732681440.026170303]: wait-interpolation debug: end +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +[ INFO] [1732681440.071567213]: wait-interpolation debug: start +[ INFO] [1732681441.077536887]: wait-interpolation debug: end +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +;; # :joint-angle(88.0543) violate max-angle(88.0) +[ INFO] [1732681441.117705378]: wait-interpolation debug: start +[ INFO] [1732681428.839090643]: wait-interpolation debug: start C-c C-cinterrupt4.B2-irteusgl$ +nil +4.B2-irteusgl$ load "main.l" +[ WARN] [1732681551.028756962]: continuous joint (r_forearm_roll_joint) moves -236.136 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681551.028827046]: continuous joint (r_wrist_roll_joint) moves 356.376 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681551.036984026]: continuous joint (r_forearm_roll_joint) moves -236.136 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681551.037052539]: continuous joint (r_wrist_roll_joint) moves 356.376 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681551.037088787]: original trajectory command : +[ WARN] [1732681551.037123513]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732681551.037154807]: current angle vector : #f(201.076 8.79185 -0.969142 88.0156 -42.1518 90.8208 -92.0501 236.638 -14.3392 -5.57095 -108.641 -83.4894 216.136 -61.435 -176.376 0.0 0.0) +[ WARN] [1732681551.037176212]: new trajectory command : dvi = 3 +[ WARN] [1732681551.037225873]: : #f(150.717 25.8612 24.0206 82.0104 -68.1012 67.2139 -71.3668 217.759 -29.5595 20.9527 -95.7604 -95.6596 137.424 -50.9567 -57.584 0.0 0.0) 333 +[ WARN] [1732681551.037259523]: : #f(100.359 42.9306 49.0103 76.0052 -94.0506 43.6069 -50.6834 198.879 -44.7797 47.4763 -82.8802 -107.83 58.712 -40.4783 61.208 0.0 0.0) 333 +[ WARN] [1732681551.037285679]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 333 +[ WARN] [1732681551.037304187]: new trajectory command : +[ WARN] [1732681551.037355852]: : (#f(150.717 25.8612 24.0206 82.0104 -68.1012 67.2139 -71.3668 217.759 -29.5595 20.9527 -95.7604 -95.6596 137.424 -50.9567 -57.584 0.0 0.0) #f(100.359 42.9306 49.0103 76.0052 -94.0506 43.6069 -50.6834 198.879 -44.7797 47.4763 -82.8802 -107.83 58.712 -40.4783 61.208 0.0 0.0) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (333 333 333) +[ INFO] [1732681551.046013294]: wait-interpolation debug: start +[ERROR] [1732681562.751162197]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681562.751207462]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681562.754118323]: wait-interpolation debug: end +[ INFO] [1732681565.916262737]: wait-interpolation debug: start +[ERROR] [1732681567.511059001]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681567.511108543]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681567.513882265]: wait-interpolation debug: end +[ INFO] [1732681573.670989521]: wait-interpolation debug: start +[ INFO] [1732681573.673593813]: wait-interpolation debug: end +[ INFO] [1732681583.362935577]: wait-interpolation debug: start +[ INFO] [1732681583.363199078]: wait-interpolation debug: end +[ INFO] [1732681589.864371572]: wait-interpolation debug: start +[ INFO] [1732681590.875571748]: wait-interpolation debug: end +[ WARN] [1732681590.907670180]: continuous joint (l_forearm_roll_joint) moves 186.488 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681590.909868002]: continuous joint (l_forearm_roll_joint) moves 186.488 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681590.909956417]: original trajectory command : +[ WARN] [1732681590.909992870]: : (#f(50.0 -11.0191 30.5161 -2.07694 -107.385 190.235 -76.7448 173.241 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732681590.910025537]: current angle vector : #f(50.0 13.3614 8.94588 42.6501 -66.1762 3.74639 -39.618 173.241 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732681590.910045838]: new trajectory command : dvi = 2 +[ WARN] [1732681590.910087192]: : #f(50.0 1.17112 19.731 20.2866 -86.7804 96.9906 -58.1814 173.241 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732681590.910120026]: : #f(50.0 -11.0191 30.5161 -2.07694 -107.385 190.235 -76.7448 173.241 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732681590.910143470]: new trajectory command : +[ WARN] [1732681590.910202665]: : (#f(50.0 1.17112 19.731 20.2866 -86.7804 96.9906 -58.1814 173.241 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) #f(50.0 -11.0191 30.5161 -2.07694 -107.385 190.235 -76.7448 173.241 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732681590.914184337]: wait-interpolation debug: start +[ INFO] [1732681592.118258037]: wait-interpolation debug: end +[ INFO] [1732681592.174031407]: wait-interpolation debug: start +[ERROR] [1732681593.176428553]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681593.176483092]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732681593.769206989]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681593.769263074]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681593.771269363]: wait-interpolation debug: end +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.006) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +[ INFO] [1732681594.269148964]: wait-interpolation debug: start +[ INFO] [1732681595.557805030]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732681595.605175138]: wait-interpolation debug: start +[ INFO] [1732681596.633761027]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732681596.673559564]: wait-interpolation debug: start +[ INFO] [1732681597.676067852]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732681597.715746370]: wait-interpolation debug: start +[ INFO] [1732681598.721490981]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732681598.767159988]: wait-interpolation debug: start +[ INFO] [1732681599.765721248]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732681599.817356406]: wait-interpolation debug: start +[ INFO] [1732681600.819621303]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732681600.857511177]: wait-interpolation debug: start +[ INFO] [1732681601.868085739]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732681601.908340620]: wait-interpolation debug: start +[ INFO] [1732681602.906948115]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732681602.943598770]: wait-interpolation debug: start +[ INFO] [1732681603.948651257]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732681604.004026484]: wait-interpolation debug: start +[ INFO] [1732681605.008511260]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732681607.133741281]: wait-interpolation debug: start +[ INFO] [1732681607.145998634]: wait-interpolation debug: end +[ INFO] [1732681609.963038527]: wait-interpolation debug: start +[ INFO] [1732681609.971598727]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732681610.006954345]: wait-interpolation debug: start +[ INFO] [1732681611.006450640]: wait-interpolation debug: end +[ INFO] [1732681611.094291305]: wait-interpolation debug: start +[ERROR] [1732681616.746134838]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681616.746179610]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681616.751118937]: wait-interpolation debug: end +[ INFO] [1732681604.004026484]: wait-interpolation debug: start C-c C-cinterrupt5.B3-irteusgl$ +nil +5.B3-irteusgl$ load "main.l" +[ WARN] [1732681679.603258379]: continuous joint (r_forearm_roll_joint) moves -198.115 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681679.608776673]: continuous joint (r_forearm_roll_joint) moves -198.115 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681679.608863939]: original trajectory command : +[ WARN] [1732681679.608910522]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732681679.608953953]: current angle vector : #f(123.614 5.52346 -19.8667 75.7634 -44.6609 85.3366 -113.847 227.372 -0.394102 27.8888 26.0573 -101.138 178.115 -105.604 63.3075 0.0 0.0) +[ WARN] [1732681679.608987491]: new trajectory command : dvi = 2 +[ WARN] [1732681679.609059614]: : #f(86.8069 32.7617 27.0666 72.8817 -82.3304 52.6683 -71.9234 203.686 -30.1971 50.9444 -21.9714 -110.569 79.0576 -67.802 121.654 0.0 0.0) 500 +[ WARN] [1732681679.609126633]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732681679.609166258]: new trajectory command : +[ WARN] [1732681679.609238068]: : (#f(86.8069 32.7617 27.0666 72.8817 -82.3304 52.6683 -71.9234 203.686 -30.1971 50.9444 -21.9714 -110.569 79.0576 -67.802 121.654 0.0 0.0) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732681679.614683599]: wait-interpolation debug: start +[ERROR] [1732681685.373830312]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681685.373869733]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681685.376338841]: wait-interpolation debug: end +[ INFO] [1732681687.193091254]: wait-interpolation debug: start +[ERROR] [1732681688.791478803]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681688.791541949]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681688.796110683]: wait-interpolation debug: end +[ INFO] [1732681695.636320155]: wait-interpolation debug: start +[ INFO] [1732681695.655582262]: wait-interpolation debug: end +[ INFO] [1732681705.337455899]: wait-interpolation debug: start +[ INFO] [1732681705.346503712]: wait-interpolation debug: end +[ INFO] [1732681711.904701279]: wait-interpolation debug: start +[ INFO] [1732681712.912583548]: wait-interpolation debug: end +[ INFO] [1732681712.985652276]: wait-interpolation debug: start +[ INFO] [1732681714.133305469]: wait-interpolation debug: end +[ WARN] [1732681714.182964044]: continuous joint (r_forearm_roll_joint) moves 182.726 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681714.185552536]: continuous joint (r_forearm_roll_joint) moves 182.726 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681714.185594993]: original trajectory command : +[ WARN] [1732681714.185619489]: : (#f(50.0 24.4499 -12.2645 99.4477 -93.5786 172.358 -67.4408 175.959 27.9743 56.4726 22.5595 -89.7952 162.726 -30.5055 92.6217 0.0 0.0)) (500) +[ WARN] [1732681714.185643185]: current angle vector : #f(50.0 24.4499 -12.2645 99.4477 -93.5786 172.358 -67.4408 175.959 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732681714.185655810]: new trajectory command : dvi = 2 +[ WARN] [1732681714.185681737]: : #f(50.0 24.4499 -12.2645 99.4477 -93.5786 172.358 -67.4408 175.959 -16.0128 65.2363 -23.7203 -104.898 71.3628 -30.2527 136.311 0.0 0.0) 250 +[ WARN] [1732681714.185712060]: : #f(50.0 24.4499 -12.2645 99.4477 -93.5786 172.358 -67.4408 175.959 27.9743 56.4726 22.5595 -89.7952 162.726 -30.5055 92.6217 0.0 0.0) 250 +[ WARN] [1732681714.185724197]: new trajectory command : +[ WARN] [1732681714.185754593]: : (#f(50.0 24.4499 -12.2645 99.4477 -93.5786 172.358 -67.4408 175.959 -16.0128 65.2363 -23.7203 -104.898 71.3628 -30.2527 136.311 0.0 0.0) #f(50.0 24.4499 -12.2645 99.4477 -93.5786 172.358 -67.4408 175.959 27.9743 56.4726 22.5595 -89.7952 162.726 -30.5055 92.6217 0.0 0.0)) (250 250) +[ INFO] [1732681714.188656996]: wait-interpolation debug: start +[ERROR] [1732681715.778457848]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681715.778508607]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681715.783132653]: wait-interpolation debug: end +;; # :joint-angle(88.0003) violate max-angle(88.0) +;; # :joint-angle(88.0003) violate max-angle(88.0) +;; # :joint-angle(88.0003) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0564) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0876) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0994) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0988) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0962) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0893) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.0834) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732681717.129166306]: wait-interpolation debug: start +[ INFO] [1732681718.127379537]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732681718.171451077]: wait-interpolation debug: start +[ INFO] [1732681719.173775718]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732681719.212890325]: wait-interpolation debug: start +[ INFO] [1732681720.212816998]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732681720.259087436]: wait-interpolation debug: start +[ INFO] [1732681721.265563387]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732681721.302460220]: wait-interpolation debug: start +[ INFO] [1732681722.360157018]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732681722.400552993]: wait-interpolation debug: start +[ INFO] [1732681723.433971156]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732681723.477715594]: wait-interpolation debug: start +[ INFO] [1732681724.481619617]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732681724.522000326]: wait-interpolation debug: start +[ INFO] [1732681724.522000326]: wait-interpolation debug: start C-c C-cinterrupt6.B4-irteusgl$ +nil +6.B4-irteusgl$ load "main.l" +[ WARN] [1732681737.191665304]: continuous joint (r_forearm_roll_joint) moves -182.726 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681737.197501243]: continuous joint (r_forearm_roll_joint) moves -182.726 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681737.197587971]: original trajectory command : +[ WARN] [1732681737.197625496]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732681737.197662222]: current angle vector : #f(50.0 7.06524 -5.86539 103.943 -45.2525 75.9664 -84.3592 233.225 27.9743 56.4726 22.5595 -89.7952 162.726 -30.5055 92.6217 0.0 0.0) +[ WARN] [1732681737.197681788]: new trajectory command : dvi = 2 +[ WARN] [1732681737.197727962]: : #f(50.0 33.5326 34.0673 86.9714 -82.6263 47.9832 -57.1796 206.613 -16.0128 65.2363 -23.7203 -104.898 71.3628 -30.2527 136.311 0.0 0.0) 500 +[ WARN] [1732681737.197777748]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732681737.197800528]: new trajectory command : +[ WARN] [1732681737.197842529]: : (#f(50.0 33.5326 34.0673 86.9714 -82.6263 47.9832 -57.1796 206.613 -16.0128 65.2363 -23.7203 -104.898 71.3628 -30.2527 136.311 0.0 0.0) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732681737.207080843]: wait-interpolation debug: start +[ERROR] [1732681738.896674404]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681738.896737676]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732681738.897628150]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681738.897656618]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681738.900402045]: wait-interpolation debug: end +[ INFO] [1732681739.957205914]: wait-interpolation debug: start +[ERROR] [1732681741.554598521]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681741.554727167]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681741.568613247]: wait-interpolation debug: end + C-c C-cinterrupt7.B5-irteusgl$ C-c C-cinterrupt7.B6-irteusgl$ C-c C-cinterrupt7.B7-irteusgl$ +nil +7.B7-irteusgl$ load "main.l" +[ WARN] [1732681824.098458437]: [/l_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732681824.098512205]: expected goal id 1732681824091128350_/pr2_eus_interface_1732680438716966801_7838_/l_gripper_controller/gripper_action_36 +[ WARN] [1732681824.098550923]: received goal id 1732681745785029217_/pr2_eus_interface_1732680438716966801_7838_/l_gripper_controller/gripper_action_35 +[ INFO] [1732681826.048573064]: wait-interpolation debug: start +[ERROR] [1732681827.647799306]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681827.647866721]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681827.652416278]: wait-interpolation debug: end +[ INFO] [1732681828.095016481]: wait-interpolation debug: start +[ERROR] [1732681829.698740412]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681829.698816874]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681829.706103405]: wait-interpolation debug: end +[ INFO] [1732681837.216377705]: wait-interpolation debug: start +[ INFO] [1732681837.217541745]: wait-interpolation debug: end +[ INFO] [1732681846.904453767]: wait-interpolation debug: start +[ INFO] [1732681846.904734860]: wait-interpolation debug: end +[ INFO] [1732681853.466693382]: wait-interpolation debug: start +[ INFO] [1732681854.471501542]: wait-interpolation debug: end +[ WARN] [1732681854.504051470]: continuous joint (l_forearm_roll_joint) moves 184.816 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681854.506558076]: continuous joint (l_forearm_roll_joint) moves 184.816 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681854.506631529]: original trajectory command : +[ WARN] [1732681854.506660897]: : (#f(50.0 -8.89275 31.8375 -0.210514 -96.5863 189.695 -65.0382 175.398 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732681854.506685842]: current angle vector : #f(50.0 11.057 8.64089 45.3085 -50.1497 4.87939 -53.9635 175.398 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732681854.506701731]: new trajectory command : dvi = 2 +[ WARN] [1732681854.506732318]: : #f(50.0 1.08212 20.2392 22.549 -73.368 97.2871 -59.5008 175.398 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732681854.506759509]: : #f(50.0 -8.89275 31.8375 -0.210514 -96.5863 189.695 -65.0382 175.398 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732681854.506785746]: new trajectory command : +[ WARN] [1732681854.506836454]: : (#f(50.0 1.08212 20.2392 22.549 -73.368 97.2871 -59.5008 175.398 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) #f(50.0 -8.89275 31.8375 -0.210514 -96.5863 189.695 -65.0382 175.398 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732681854.510403324]: wait-interpolation debug: start +[ INFO] [1732681855.696849539]: wait-interpolation debug: end +[ WARN] [1732681855.741975306]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681855.746338431]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681855.746387185]: original trajectory command : +[ WARN] [1732681855.746417476]: : (#f(50.0 -8.89275 31.8375 -0.210514 -96.5863 189.695 -65.0382 175.398 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (500) +[ WARN] [1732681855.746445873]: current angle vector : #f(50.0 -8.89275 31.8375 -0.210514 -96.5863 189.695 -65.0382 175.398 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732681855.746470928]: new trajectory command : dvi = 2 +[ WARN] [1732681855.746524892]: : #f(50.0 -8.89275 31.8375 -0.210514 -96.5863 189.695 -65.0382 175.398 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) 250 +[ WARN] [1732681855.746576628]: : #f(50.0 -8.89275 31.8375 -0.210514 -96.5863 189.695 -65.0382 175.398 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) 250 +[ WARN] [1732681855.746620634]: new trajectory command : +[ WARN] [1732681855.746676575]: : (#f(50.0 -8.89275 31.8375 -0.210514 -96.5863 189.695 -65.0382 175.398 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) #f(50.0 -8.89275 31.8375 -0.210514 -96.5863 189.695 -65.0382 175.398 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (250 250) +[ INFO] [1732681855.751269115]: wait-interpolation debug: start +[ERROR] [1732681857.386024548]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681857.386079009]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681857.391032108]: wait-interpolation debug: end +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0166) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.089) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.0831) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732681858.248135856]: wait-interpolation debug: start +[ INFO] [1732681859.212305803]: wait-interpolation debug: end +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +[ INFO] [1732681859.305091508]: wait-interpolation debug: start +[ INFO] [1732681860.327198983]: wait-interpolation debug: end +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +[ INFO] [1732681860.367375933]: wait-interpolation debug: start +[ INFO] [1732681861.386231851]: wait-interpolation debug: end +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +[ INFO] [1732681861.425461645]: wait-interpolation debug: start +[ INFO] [1732681862.433348860]: wait-interpolation debug: end +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +[ INFO] [1732681862.474132835]: wait-interpolation debug: start +[ INFO] [1732681863.489026794]: wait-interpolation debug: end +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +[ INFO] [1732681863.525404997]: wait-interpolation debug: start +[ INFO] [1732681864.537511596]: wait-interpolation debug: end +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +[ INFO] [1732681864.579454875]: wait-interpolation debug: start +[ WARN] [1732681866.650618483]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732681866.651185453]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ERROR] [1732681866.672562068]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681866.672608247]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681866.680136146]: wait-interpolation debug: end +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +[ INFO] [1732681866.836199897]: wait-interpolation debug: start +[ INFO] [1732681867.842547687]: wait-interpolation debug: end +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +[ INFO] [1732681867.878400301]: wait-interpolation debug: start +[ INFO] [1732681868.934565406]: wait-interpolation debug: end +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +;; # :joint-angle(88.0698) violate max-angle(88.0) +[ INFO] [1732681868.976244305]: wait-interpolation debug: start +[ INFO] [1732681869.985029781]: wait-interpolation debug: end +;; # :joint-angle(88.0698) violate max-angle(88.0) +[ INFO] [1732681872.170076497]: wait-interpolation debug: start +[ INFO] [1732681872.173860129]: wait-interpolation debug: end + C-c C-cinterrupt8.B8-irteusgl$ (send *ri* :stop-grasp) +[ WARN] [1732681891.345678609]: [/l_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732681891.345759279]: expected goal id 1732681891314180757_/pr2_eus_interface_1732680438716966801_7838_/l_gripper_controller/gripper_action_40 +[ WARN] [1732681891.345803531]: received goal id 1732681873174766516_/pr2_eus_interface_1732680438716966801_7838_/l_gripper_controller/gripper_action_39 +(t t) +9.B8-irteusgl$ load "main.l" +[ WARN] [1732681927.095521385]: [/r_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732681927.095568650]: expected goal id 1732681927075042014_/pr2_eus_interface_1732680438716966801_7838_/r_gripper_controller/gripper_action_41 +[ WARN] [1732681927.095589657]: received goal id 1732681891313722791_/pr2_eus_interface_1732680438716966801_7838_/r_gripper_controller/gripper_action_40 +[ WARN] [1732681929.267062639]: continuous joint (r_forearm_roll_joint) moves -187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681929.273248841]: continuous joint (r_forearm_roll_joint) moves -187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681929.273316863]: original trajectory command : +[ WARN] [1732681929.273344862]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732681929.273372475]: current angle vector : #f(50.0 3.83397 -4.91963 74.828 -40.1621 98.5148 -103.516 234.027 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +[ WARN] [1732681929.273388829]: new trajectory command : dvi = 2 +[ WARN] [1732681929.273423176]: : #f(50.0 31.917 34.5402 72.414 -80.081 59.2574 -66.7579 207.014 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) 500 +[ WARN] [1732681929.273459106]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732681929.273476003]: new trajectory command : +[ WARN] [1732681929.273509890]: : (#f(50.0 31.917 34.5402 72.414 -80.081 59.2574 -66.7579 207.014 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732681929.276104695]: wait-interpolation debug: start +[ERROR] [1732681930.977877356]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681930.977928972]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732681930.979829204]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681930.979864123]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681930.983052217]: wait-interpolation debug: end +[ INFO] [1732681931.825185568]: wait-interpolation debug: start +[ERROR] [1732681933.424866252]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681933.424926973]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681933.433148220]: wait-interpolation debug: end +[ INFO] [1732681939.496106999]: wait-interpolation debug: start +[ INFO] [1732681939.498798600]: wait-interpolation debug: end +[ INFO] [1732681949.153980586]: wait-interpolation debug: start +[ INFO] [1732681949.165072405]: wait-interpolation debug: end +[ INFO] [1732681955.716393911]: wait-interpolation debug: start +[ INFO] [1732681956.722686661]: wait-interpolation debug: end +[ INFO] [1732681956.758312708]: wait-interpolation debug: start +[ INFO] [1732681957.927369174]: wait-interpolation debug: end +[ WARN] [1732681957.977765773]: continuous joint (r_forearm_roll_joint) moves 187.084 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681957.981527031]: continuous joint (r_forearm_roll_joint) moves 187.084 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681957.981584559]: original trajectory command : +[ WARN] [1732681957.981620235]: : (#f(50.0 22.9164 2.76227 70.878 -92.476 174.772 -69.9805 175.363 32.3344 43.2804 31.283 -95.1188 167.084 -44.3717 76.806 0.0 0.0)) (500) +[ WARN] [1732681957.981651832]: current angle vector : #f(50.0 22.9164 2.76227 70.878 -92.476 174.772 -69.9805 175.363 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732681957.981672760]: new trajectory command : dvi = 2 +[ WARN] [1732681957.981714778]: : #f(50.0 22.9164 2.76227 70.878 -92.476 174.772 -69.9805 175.363 -13.8328 58.6402 -19.3585 -107.559 73.5422 -37.1859 128.403 0.0 0.0) 250 +[ WARN] [1732681957.981757061]: : #f(50.0 22.9164 2.76227 70.878 -92.476 174.772 -69.9805 175.363 32.3344 43.2804 31.283 -95.1188 167.084 -44.3717 76.806 0.0 0.0) 250 +[ WARN] [1732681957.981779846]: new trajectory command : +[ WARN] [1732681957.981840423]: : (#f(50.0 22.9164 2.76227 70.878 -92.476 174.772 -69.9805 175.363 -13.8328 58.6402 -19.3585 -107.559 73.5422 -37.1859 128.403 0.0 0.0) #f(50.0 22.9164 2.76227 70.878 -92.476 174.772 -69.9805 175.363 32.3344 43.2804 31.283 -95.1188 167.084 -44.3717 76.806 0.0 0.0)) (250 250) +[ INFO] [1732681957.985953181]: wait-interpolation debug: start +[ERROR] [1732681959.595329362]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681959.595398924]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681959.604509941]: wait-interpolation debug: end +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0015) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0561) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0965) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732681960.717240499]: wait-interpolation debug: start +[ INFO] [1732681961.722602874]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732681961.766334889]: wait-interpolation debug: start +[ INFO] [1732681962.798269002]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732681962.858798996]: wait-interpolation debug: start +[ INFO] [1732681963.863655093]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732681963.935451477]: wait-interpolation debug: start +[ INFO] [1732681964.952902824]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732681965.026252769]: wait-interpolation debug: start +[ INFO] [1732681966.025630365]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732681966.067847067]: wait-interpolation debug: start +[ INFO] [1732681967.074616626]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732681967.113244951]: wait-interpolation debug: start +[ INFO] [1732681968.120706542]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732681968.156134137]: wait-interpolation debug: start +[ INFO] [1732681969.162793920]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732681969.199216538]: wait-interpolation debug: start +[ INFO] [1732681970.227137882]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732681970.272595838]: wait-interpolation debug: start +[ INFO] [1732681971.282848678]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732681973.444643994]: wait-interpolation debug: start +[ INFO] [1732681973.444787754]: wait-interpolation debug: end +[ INFO] [1732681976.250855661]: wait-interpolation debug: start +[ INFO] [1732681976.254986822]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732681976.296706981]: wait-interpolation debug: start +[ INFO] [1732681977.303988783]: wait-interpolation debug: end +[ INFO] [1732681977.373752018]: wait-interpolation debug: start +[ERROR] [1732681982.221133212]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732681982.221179145]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732681982.223836109]: wait-interpolation debug: end +[ WARN] [1732681983.766890973]: continuous joint (r_wrist_roll_joint) moves 200.71 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681983.770662634]: continuous joint (r_wrist_roll_joint) moves 200.71 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732681983.770724462]: original trajectory command : +[ WARN] [1732681983.770750222]: : (#f(113.16 -1.97438 -17.8884 81.5614 -23.5899 90.3081 -109.718 243.159 23.8654 33.934 15.7586 -96.3087 163.002 -59.0575 265.473 0.0 0.0)) (1000) +[ WARN] [1732681983.770772021]: current angle vector : #f(113.16 -1.97438 -17.8884 81.5614 -23.5899 90.3081 -109.718 243.159 -4.73321 46.7747 17.3955 -96.74 201.366 -54.2977 64.7628 0.0 0.0) +[ WARN] [1732681983.770785814]: new trajectory command : dvi = 2 +[ WARN] [1732681983.770812117]: : #f(113.16 -1.97438 -17.8884 81.5614 -23.5899 90.3081 -109.718 243.159 9.56607 40.3543 16.577 -96.5244 182.184 -56.6776 165.118 0.0 0.0) 500 +[ WARN] [1732681983.770844384]: : #f(113.16 -1.97438 -17.8884 81.5614 -23.5899 90.3081 -109.718 243.159 23.8654 33.934 15.7586 -96.3087 163.002 -59.0575 265.473 0.0 0.0) 500 +[ WARN] [1732681983.770858605]: new trajectory command : +[ WARN] [1732681983.770885006]: : (#f(113.16 -1.97438 -17.8884 81.5614 -23.5899 90.3081 -109.718 243.159 9.56607 40.3543 16.577 -96.5244 182.184 -56.6776 165.118 0.0 0.0) #f(113.16 -1.97438 -17.8884 81.5614 -23.5899 90.3081 -109.718 243.159 23.8654 33.934 15.7586 -96.3087 163.002 -59.0575 265.473 0.0 0.0)) (500 500) +[ INFO] [1732681983.774794484]: wait-interpolation debug: start +[ INFO] [1732681985.085378533]: wait-interpolation debug: end +[ INFO] [1732681987.050661837]: wait-interpolation debug: start +[ INFO] [1732681987.063334964]: wait-interpolation debug: end +[ INFO] [1732681988.091782145]: wait-interpolation debug: start +[ INFO] [1732681988.102807136]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732681993.492358790]: wait-interpolation debug: start +[ INFO] [1732681994.496502138]: wait-interpolation debug: end +;; # :joint-angle(88.0537) violate max-angle(88.0) +;; # :joint-angle(88.0537) violate max-angle(88.0) +;; # :joint-angle(88.0537) violate max-angle(88.0) +;; # :joint-angle(88.0537) violate max-angle(88.0) +;; # :joint-angle(88.0537) violate max-angle(88.0) +;; # :joint-angle(88.0537) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0531) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +[ INFO] [1732681994.698035027]: wait-interpolation debug: start +[ INFO] [1732681995.725278998]: wait-interpolation debug: end +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +[ INFO] [1732681995.807935543]: wait-interpolation debug: start +[ INFO] [1732681996.805264288]: wait-interpolation debug: end +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +[ INFO] [1732681996.845372288]: wait-interpolation debug: start +[ INFO] [1732681997.869663218]: wait-interpolation debug: end +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +[ INFO] [1732681997.914157202]: wait-interpolation debug: start +[ INFO] [1732681998.921936312]: wait-interpolation debug: end +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +;; # :joint-angle(88.0528) violate max-angle(88.0) +[ INFO] [1732681998.962604325]: wait-interpolation debug: start + C-c C-cinterrupt10.B9-irteusgl$ load "main.l" +[ WARN] [1732682128.563757856]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732682128.563803535]: expected goal id 1732682128562782851_/pr2_eus_interface_1732680438716966801_7838_robotsound_jp_40 +[ WARN] [1732682128.563821616]: received goal id 1732682000537683643_/tweet_client_warning_473265_robotsound_jp_0 +[ WARN] [1732682128.564090388]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732682128.564113549]: expected goal id 1732682128562782851_/pr2_eus_interface_1732680438716966801_7838_robotsound_jp_40 +[ WARN] [1732682128.564128887]: received goal id 1732682001543684012_/tweet_client_warning_473265_robotsound_jp_1 +[ WARN] [1732682128.564334932]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732682128.564353734]: expected goal id 1732682128562782851_/pr2_eus_interface_1732680438716966801_7838_robotsound_jp_40 +[ WARN] [1732682128.564367316]: received goal id 1732682002590995463_/tweet_client_warning_473265_robotsound_jp_2 +[ INFO] [1732682134.765420961]: wait-interpolation debug: start +[ERROR] [1732682139.618359487]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682139.618412866]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682139.628261287]: wait-interpolation debug: end +[ INFO] [1732682141.467850130]: wait-interpolation debug: start +[ERROR] [1732682143.083623546]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682143.083664966]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682143.084543118]: wait-interpolation debug: end + C-c C-cinterrupt11.B10-irteusgl$ load "main.l" +[ WARN] [1732682186.143850925]: [/l_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732682186.143954849]: expected goal id 1732682186125180355_/pr2_eus_interface_1732680438716966801_7838_/l_gripper_controller/gripper_action_49 +[ WARN] [1732682186.144040832]: received goal id 1732682147624583482_/pr2_eus_interface_1732680438716966801_7838_/l_gripper_controller/gripper_action_48 +[ INFO] [1732682188.085762061]: wait-interpolation debug: start +[ERROR] [1732682189.682583502]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682189.682652635]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682189.689354350]: wait-interpolation debug: end +[ INFO] [1732682190.225854373]: wait-interpolation debug: start +[ERROR] [1732682191.822021695]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682191.822084361]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682191.825306425]: wait-interpolation debug: end +[ INFO] [1732682197.761946478]: wait-interpolation debug: start +[ INFO] [1732682197.762611797]: wait-interpolation debug: end +[ INFO] [1732682207.439094797]: wait-interpolation debug: start +[ INFO] [1732682207.444983080]: wait-interpolation debug: end +[ INFO] [1732682213.972698645]: wait-interpolation debug: start +[ INFO] [1732682214.976254652]: wait-interpolation debug: end +[ WARN] [1732682215.013564334]: continuous joint (l_forearm_roll_joint) moves 184.283 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682215.016111221]: continuous joint (l_forearm_roll_joint) moves 184.283 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682215.016184996]: original trajectory command : +[ WARN] [1732682215.016232052]: : (#f(50.0 -10.9476 30.1836 -3.92543 -96.108 189.839 -65.6517 172.84 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732682215.016271962]: current angle vector : #f(50.0 17.2139 13.681 45.7836 -77.9506 5.5551 -34.0295 172.84 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732682215.016286993]: new trajectory command : dvi = 2 +[ WARN] [1732682215.016331119]: : #f(50.0 3.13316 21.9323 20.9291 -87.0293 97.6968 -49.8406 172.84 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732682215.016381266]: : #f(50.0 -10.9476 30.1836 -3.92543 -96.108 189.839 -65.6517 172.84 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732682215.016400943]: new trajectory command : +[ WARN] [1732682215.016460723]: : (#f(50.0 3.13316 21.9323 20.9291 -87.0293 97.6968 -49.8406 172.84 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) #f(50.0 -10.9476 30.1836 -3.92543 -96.108 189.839 -65.6517 172.84 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732682215.019697650]: wait-interpolation debug: start +[ INFO] [1732682216.212736757]: wait-interpolation debug: end +[ WARN] [1732682216.293762272]: continuous joint (r_forearm_roll_joint) moves 186.826 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682216.297067425]: continuous joint (r_forearm_roll_joint) moves 186.826 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682216.297139051]: original trajectory command : +[ WARN] [1732682216.297185840]: : (#f(50.0 -10.9476 30.1836 -3.92543 -96.108 189.839 -65.6517 172.84 32.3303 42.1262 31.2872 -95.3464 166.826 -45.5421 76.333 0.0 0.0)) (500) +[ WARN] [1732682216.297271372]: current angle vector : #f(50.0 -10.9476 30.1836 -3.92543 -96.108 189.839 -65.6517 172.84 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732682216.297296250]: new trajectory command : dvi = 2 +[ WARN] [1732682216.297342610]: : #f(50.0 -10.9476 30.1836 -3.92543 -96.108 189.839 -65.6517 172.84 -13.8349 58.0631 -19.3564 -107.673 73.4128 -37.7711 128.166 0.0 0.0) 250 +[ WARN] [1732682216.297393847]: : #f(50.0 -10.9476 30.1836 -3.92543 -96.108 189.839 -65.6517 172.84 32.3303 42.1262 31.2872 -95.3464 166.826 -45.5421 76.333 0.0 0.0) 250 +[ WARN] [1732682216.297417839]: new trajectory command : +[ WARN] [1732682216.297469381]: : (#f(50.0 -10.9476 30.1836 -3.92543 -96.108 189.839 -65.6517 172.84 -13.8349 58.0631 -19.3564 -107.673 73.4128 -37.7711 128.166 0.0 0.0) #f(50.0 -10.9476 30.1836 -3.92543 -96.108 189.839 -65.6517 172.84 32.3303 42.1262 31.2872 -95.3464 166.826 -45.5421 76.333 0.0 0.0)) (250 250) +[ INFO] [1732682216.303949288]: wait-interpolation debug: start +[ERROR] [1732682217.911009097]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682217.911099417]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682217.924804686]: wait-interpolation debug: end +;; # :joint-angle(88.0333) violate max-angle(88.0) +;; # :joint-angle(88.0333) violate max-angle(88.0) +;; # :joint-angle(88.0333) violate max-angle(88.0) +;; # :joint-angle(88.0333) violate max-angle(88.0) +;; # :joint-angle(88.0333) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0991) violate max-angle(88.0) +;; # :joint-angle(88.0991) violate max-angle(88.0) +;; # :joint-angle(88.0991) violate max-angle(88.0) +;; # :joint-angle(88.0991) violate max-angle(88.0) +;; # :joint-angle(88.0991) violate max-angle(88.0) +;; # :joint-angle(88.0991) violate max-angle(88.0) +;; # :joint-angle(88.0991) violate max-angle(88.0) +;; # :joint-angle(88.0991) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1042) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.1015) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.098) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0938) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732682218.490744401]: wait-interpolation debug: start +[ INFO] [1732682219.625835885]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732682219.677627747]: wait-interpolation debug: start +[ INFO] [1732682220.676112679]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732682220.716171208]: wait-interpolation debug: start +[ INFO] [1732682221.747401857]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732682221.784299375]: wait-interpolation debug: start +[ INFO] [1732682222.801907471]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732682222.844144083]: wait-interpolation debug: start +[ INFO] [1732682223.853924053]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732682223.931625838]: wait-interpolation debug: start +[ INFO] [1732682224.945879551]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732682225.021421321]: wait-interpolation debug: start +[ INFO] [1732682226.030670796]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732682226.105281798]: wait-interpolation debug: start +[ INFO] [1732682227.115879122]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732682227.193630030]: wait-interpolation debug: start +[ INFO] [1732682228.194576028]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732682228.234774924]: wait-interpolation debug: start +[ INFO] [1732682229.243139281]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732682231.397679511]: wait-interpolation debug: start +[ INFO] [1732682231.403573146]: wait-interpolation debug: end +[ INFO] [1732682234.215282166]: wait-interpolation debug: start +[ INFO] [1732682234.225695531]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732682234.263954768]: wait-interpolation debug: start +[ INFO] [1732682235.268926439]: wait-interpolation debug: end +[ INFO] [1732682235.341905617]: wait-interpolation debug: start +[ERROR] [1732682240.510886898]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682240.510958970]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682240.515535820]: wait-interpolation debug: end +[ WARN] [1732682242.158344464]: continuous joint (r_wrist_roll_joint) moves 200.405 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682242.161751750]: continuous joint (r_wrist_roll_joint) moves 200.405 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682242.161821706]: original trajectory command : +[ WARN] [1732682242.161858038]: : (#f(117.387 -2.75869 -17.0885 73.9563 -22.2326 98.2593 -111.836 244.179 23.9424 33.1693 15.8981 -96.1634 162.914 -59.5683 265.138 0.0 0.0)) (1000) +[ WARN] [1732682242.161892028]: current angle vector : #f(117.387 -2.75869 -17.0885 73.9563 -22.2326 98.2593 -111.836 244.179 -4.34686 45.5357 18.128 -96.9383 200.808 -55.6967 64.7332 0.0 0.0) +[ WARN] [1732682242.161913597]: new trajectory command : dvi = 2 +[ WARN] [1732682242.161953463]: : #f(117.387 -2.75869 -17.0885 73.9563 -22.2326 98.2593 -111.836 244.179 9.79778 39.3525 17.0131 -96.5509 181.861 -57.6325 164.936 0.0 0.0) 500 +[ WARN] [1732682242.162003774]: : #f(117.387 -2.75869 -17.0885 73.9563 -22.2326 98.2593 -111.836 244.179 23.9424 33.1693 15.8981 -96.1634 162.914 -59.5683 265.138 0.0 0.0) 500 +[ WARN] [1732682242.162025321]: new trajectory command : +[ WARN] [1732682242.162070741]: : (#f(117.387 -2.75869 -17.0885 73.9563 -22.2326 98.2593 -111.836 244.179 9.79778 39.3525 17.0131 -96.5509 181.861 -57.6325 164.936 0.0 0.0) #f(117.387 -2.75869 -17.0885 73.9563 -22.2326 98.2593 -111.836 244.179 23.9424 33.1693 15.8981 -96.1634 162.914 -59.5683 265.138 0.0 0.0)) (500 500) +[ INFO] [1732682242.170759162]: wait-interpolation debug: start +[ INFO] [1732682243.440508604]: wait-interpolation debug: end +[ INFO] [1732682245.393693065]: wait-interpolation debug: start +[ INFO] [1732682245.393954260]: wait-interpolation debug: end +[ INFO] [1732682246.422696479]: wait-interpolation debug: start +[ INFO] [1732682246.434483542]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732682251.875588770]: wait-interpolation debug: start +[ INFO] [1732682252.894230667]: wait-interpolation debug: end +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0585) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +[ INFO] [1732682253.101812210]: wait-interpolation debug: start +[ INFO] [1732682254.223100441]: wait-interpolation debug: end +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +[ INFO] [1732682254.263263907]: wait-interpolation debug: start +[ INFO] [1732682255.373090041]: wait-interpolation debug: end +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +[ INFO] [1732682255.412554692]: wait-interpolation debug: start +[ INFO] [1732682256.523262510]: wait-interpolation debug: end +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +[ INFO] [1732682256.563777308]: wait-interpolation debug: start +[ INFO] [1732682257.604895270]: wait-interpolation debug: end +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +[ INFO] [1732682257.644350440]: wait-interpolation debug: start +[ INFO] [1732682258.668320737]: wait-interpolation debug: end +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +[ INFO] [1732682258.706157763]: wait-interpolation debug: start +[ INFO] [1732682259.709466600]: wait-interpolation debug: end +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +[ INFO] [1732682259.778450360]: wait-interpolation debug: start +[ INFO] [1732682260.778099453]: wait-interpolation debug: end +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +[ INFO] [1732682260.847032299]: wait-interpolation debug: start +[ INFO] [1732682261.851325426]: wait-interpolation debug: end +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +[ INFO] [1732682261.921189612]: wait-interpolation debug: start +[ INFO] [1732682262.926091222]: wait-interpolation debug: end +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +;; # :joint-angle(88.0582) violate max-angle(88.0) +[ INFO] [1732682263.001051372]: wait-interpolation debug: start +[ INFO] [1732682264.005840680]: wait-interpolation debug: end +;; # :joint-angle(88.0582) violate max-angle(88.0) +[ INFO] [1732682266.293584233]: wait-interpolation debug: start +[ INFO] [1732682266.294315709]: wait-interpolation debug: end +[ INFO] [1732682269.108904634]: wait-interpolation debug: start +[ INFO] [1732682269.148316308]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732682269.186240990]: wait-interpolation debug: start +[ INFO] [1732682270.188547477]: wait-interpolation debug: end +[ INFO] [1732682270.294189723]: wait-interpolation debug: start +[ERROR] [1732682273.097956020]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682273.098015577]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682273.099271430]: wait-interpolation debug: end +[ INFO] [1732682274.077419960]: wait-interpolation debug: start +[ INFO] [1732682275.332145066]: wait-interpolation debug: end +[ INFO] [1732682277.290666807]: wait-interpolation debug: start +[ INFO] [1732682277.296266889]: wait-interpolation debug: end +[ INFO] [1732682278.323663992]: wait-interpolation debug: start +[ INFO] [1732682278.338073854]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732682283.746116172]: wait-interpolation debug: start +[ERROR] [1732682285.344774987]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682285.344840991]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682285.354226052]: wait-interpolation debug: end +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +[ INFO] [1732682285.425771318]: wait-interpolation debug: start +[ INFO] [1732682286.426411751]: wait-interpolation debug: end +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +[ INFO] [1732682286.502298970]: wait-interpolation debug: start +[ INFO] [1732682287.533985112]: wait-interpolation debug: end +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +[ INFO] [1732682287.576809704]: wait-interpolation debug: start +[ INFO] [1732682288.585580328]: wait-interpolation debug: end +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +[ INFO] [1732682288.656433451]: wait-interpolation debug: start +[ INFO] [1732682289.656754623]: wait-interpolation debug: end +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +;; # :joint-angle(88.0724) violate max-angle(88.0) +[ INFO] [1732682289.734188666]: wait-interpolation debug: start +[ INFO] [1732682289.656754623]: wait-interpolation debug: end C-c C-cinterrupt12.B11-irteusgl$ +nil +12.B11-irteusgl$ (send *pass-rarm* :draw-on :flush t :size 100) +1 +13.B11-irteusgl$ (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) + :translate (float-vector 0 (- 0 (* *needle_len* 0.5)) 200)) + :translate #f(-10 0 0)) + :rotate -pi/2 :x)) + (send *pass-rarm* :draw-on :flush t :size 100) ;; for debug! +# +14.B11-irteusgl$ 1 +15.B11-irteusgl$ load "main.l" +nil +16.B11-irteusgl$ [ INFO] [1732682349.224947104]: wait-interpolation debug: start +[ERROR] [1732682357.181712739]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682357.181770375]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682357.185753610]: wait-interpolation debug: end +[ INFO] [1732682360.050067507]: wait-interpolation debug: start +[ERROR] [1732682361.649318259]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682361.649375294]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682361.650907709]: wait-interpolation debug: end +[ INFO] [1732682367.676368455]: wait-interpolation debug: start +[ INFO] [1732682367.676726719]: wait-interpolation debug: end +[ INFO] [1732682377.374837279]: wait-interpolation debug: start +[ INFO] [1732682377.375011532]: wait-interpolation debug: end +[ INFO] [1732682383.912822995]: wait-interpolation debug: start +[ INFO] [1732682384.915171006]: wait-interpolation debug: end +[ WARN] [1732682384.955202828]: continuous joint (l_forearm_roll_joint) moves 184.082 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682384.957554267]: continuous joint (l_forearm_roll_joint) moves 184.082 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682384.957628905]: original trajectory command : +[ WARN] [1732682384.957653726]: : (#f(50.0 -13.1664 30.5841 -7.95261 -96.25 190.006 -64.6717 173.016 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732682384.957675926]: current angle vector : #f(50.0 17.6247 14.4114 46.4772 -78.2949 5.92365 -34.4996 173.016 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732682384.957687096]: new trajectory command : dvi = 2 +[ WARN] [1732682384.957713284]: : #f(50.0 2.22913 22.4978 19.2623 -87.2724 97.9648 -49.5856 173.016 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732682384.957733973]: : #f(50.0 -13.1664 30.5841 -7.95261 -96.25 190.006 -64.6717 173.016 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732682384.957748873]: new trajectory command : +[ WARN] [1732682384.957775416]: : (#f(50.0 2.22913 22.4978 19.2623 -87.2724 97.9648 -49.5856 173.016 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) #f(50.0 -13.1664 30.5841 -7.95261 -96.25 190.006 -64.6717 173.016 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732682384.961525057]: wait-interpolation debug: start +[ INFO] [1732682386.145006085]: wait-interpolation debug: end +[ WARN] [1732682386.186694152]: continuous joint (r_forearm_roll_joint) moves 187.084 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682386.189458749]: continuous joint (r_forearm_roll_joint) moves 187.084 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682386.189503832]: original trajectory command : +[ WARN] [1732682386.189531728]: : (#f(50.0 -13.1664 30.5841 -7.95261 -96.25 190.006 -64.6717 173.016 32.3344 43.2804 31.283 -95.1188 167.084 -44.3717 76.806 0.0 0.0)) (500) +[ WARN] [1732682386.189555896]: current angle vector : #f(50.0 -13.1664 30.5841 -7.95261 -96.25 190.006 -64.6717 173.016 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732682386.189567022]: new trajectory command : dvi = 2 +[ WARN] [1732682386.189594083]: : #f(50.0 -13.1664 30.5841 -7.95261 -96.25 190.006 -64.6717 173.016 -13.8328 58.6402 -19.3585 -107.559 73.5422 -37.1859 128.403 0.0 0.0) 250 +[ WARN] [1732682386.189626404]: : #f(50.0 -13.1664 30.5841 -7.95261 -96.25 190.006 -64.6717 173.016 32.3344 43.2804 31.283 -95.1188 167.084 -44.3717 76.806 0.0 0.0) 250 +[ WARN] [1732682386.189640549]: new trajectory command : +[ WARN] [1732682386.189668534]: : (#f(50.0 -13.1664 30.5841 -7.95261 -96.25 190.006 -64.6717 173.016 -13.8328 58.6402 -19.3585 -107.559 73.5422 -37.1859 128.403 0.0 0.0) #f(50.0 -13.1664 30.5841 -7.95261 -96.25 190.006 -64.6717 173.016 32.3344 43.2804 31.283 -95.1188 167.084 -44.3717 76.806 0.0 0.0)) (250 250) +[ INFO] [1732682386.193891779]: wait-interpolation debug: start +[ERROR] [1732682387.805952457]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682387.806017127]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682387.815883999]: wait-interpolation debug: end +;; # :joint-angle(88.0321) violate max-angle(88.0) +;; # :joint-angle(88.0321) violate max-angle(88.0) +[ INFO] [1732682388.235482395]: wait-interpolation debug: start +[ INFO] [1732682389.526572412]: wait-interpolation debug: end +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +[ INFO] [1732682389.600943553]: wait-interpolation debug: start +[ INFO] [1732682390.607342556]: wait-interpolation debug: end +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +[ INFO] [1732682390.648868120]: wait-interpolation debug: start +[ INFO] [1732682391.658792429]: wait-interpolation debug: end +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +[ INFO] [1732682391.698045298]: wait-interpolation debug: start +[ INFO] [1732682392.711620269]: wait-interpolation debug: end +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +[ INFO] [1732682392.752844493]: wait-interpolation debug: start +[ INFO] [1732682393.753749929]: wait-interpolation debug: end +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +[ INFO] [1732682393.793787224]: wait-interpolation debug: start +[ INFO] [1732682394.801116413]: wait-interpolation debug: end +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +[ INFO] [1732682394.842618111]: wait-interpolation debug: start +[ INFO] [1732682395.853677562]: wait-interpolation debug: end +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +[ INFO] [1732682395.896036979]: wait-interpolation debug: start +[ INFO] [1732682396.906482833]: wait-interpolation debug: end +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +[ INFO] [1732682396.947883813]: wait-interpolation debug: start +[ INFO] [1732682397.974505677]: wait-interpolation debug: end +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +[ INFO] [1732682398.025623785]: wait-interpolation debug: start +[ INFO] [1732682399.026158742]: wait-interpolation debug: end +;; # :joint-angle(88.0751) violate max-angle(88.0) +[ INFO] [1732682401.166603361]: wait-interpolation debug: start +[ INFO] [1732682401.166875579]: wait-interpolation debug: end +[ INFO] [1732682403.975585404]: wait-interpolation debug: start +[ INFO] [1732682403.977124794]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732682404.048320236]: wait-interpolation debug: start +[ INFO] [1732682405.050792360]: wait-interpolation debug: end +[ INFO] [1732682405.149956028]: wait-interpolation debug: start +[ERROR] [1732682409.908056568]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682409.908099397]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682409.908614131]: wait-interpolation debug: end +[ INFO] [1732682411.455133757]: wait-interpolation debug: start +[ INFO] [1732682412.461762908]: wait-interpolation debug: end +[ INFO] [1732682414.428740670]: wait-interpolation debug: start +[ INFO] [1732682414.429053960]: wait-interpolation debug: end +[ INFO] [1732682415.457615976]: wait-interpolation debug: start +[ INFO] [1732682415.465414870]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732682420.827930865]: wait-interpolation debug: start +[ INFO] [1732682421.846097485]: wait-interpolation debug: end +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +[ INFO] [1732682421.888492919]: wait-interpolation debug: start +[ INFO] [1732682422.895103012]: wait-interpolation debug: end +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +[ INFO] [1732682422.936813797]: wait-interpolation debug: start +[ INFO] [1732682423.942585349]: wait-interpolation debug: end +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +[ INFO] [1732682423.985026994]: wait-interpolation debug: start +[ INFO] [1732682424.995663198]: wait-interpolation debug: end +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +[ INFO] [1732682425.047877858]: wait-interpolation debug: start +[ INFO] [1732682426.051725657]: wait-interpolation debug: end +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +[ INFO] [1732682426.089872029]: wait-interpolation debug: start +[ INFO] [1732682427.093807466]: wait-interpolation debug: end +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +[ INFO] [1732682427.130341645]: wait-interpolation debug: start +[ INFO] [1732682428.141494545]: wait-interpolation debug: end +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +[ INFO] [1732682428.195141362]: wait-interpolation debug: start +[ INFO] [1732682429.199156133]: wait-interpolation debug: end +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +[ INFO] [1732682429.238852621]: wait-interpolation debug: start +[ INFO] [1732682430.254915826]: wait-interpolation debug: end +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +[ INFO] [1732682430.297702727]: wait-interpolation debug: start + C-c C-cinterrupt17.B12-irteusgl$ load "main.l" +[ INFO] [1732682484.243199153]: wait-interpolation debug: start +[ERROR] [1732682489.008249815]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682489.008307549]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682489.011698668]: wait-interpolation debug: end +[ INFO] [1732682490.814452864]: wait-interpolation debug: start +[ERROR] [1732682492.433148618]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682492.433278378]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682492.455389675]: wait-interpolation debug: end +[ INFO] [1732682498.324733253]: wait-interpolation debug: start +[ INFO] [1732682498.326264383]: wait-interpolation debug: end +[ INFO] [1732682507.977739896]: wait-interpolation debug: start +[ INFO] [1732682507.978021952]: wait-interpolation debug: end +[ INFO] [1732682514.544610219]: wait-interpolation debug: start +[ INFO] [1732682515.546312437]: wait-interpolation debug: end +[ WARN] [1732682515.608701807]: continuous joint (l_forearm_roll_joint) moves 183.515 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682515.613899428]: continuous joint (l_forearm_roll_joint) moves 183.515 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682515.613985672]: original trajectory command : +[ WARN] [1732682515.614013164]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732682515.614037576]: current angle vector : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732682515.614052390]: new trajectory command : dvi = 2 +[ WARN] [1732682515.614082156]: : #f(50.0 1.586 23.3163 18.0552 -87.5893 98.265 -49.402 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732682515.614106694]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732682515.614121130]: new trajectory command : +[ WARN] [1732682515.614152125]: : (#f(50.0 1.586 23.3163 18.0552 -87.5893 98.265 -49.402 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732682515.616666302]: wait-interpolation debug: start +[ INFO] [1732682516.796662089]: wait-interpolation debug: end +[ WARN] [1732682516.837315626]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682516.839586282]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682516.839628740]: original trajectory command : +[ WARN] [1732682516.839653335]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (500) +[ WARN] [1732682516.839677027]: current angle vector : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732682516.839690559]: new trajectory command : dvi = 2 +[ WARN] [1732682516.839716774]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) 250 +[ WARN] [1732682516.839745011]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) 250 +[ WARN] [1732682516.839756948]: new trajectory command : +[ WARN] [1732682516.839784993]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (250 250) +[ INFO] [1732682516.843666575]: wait-interpolation debug: start +[ERROR] [1732682518.453878562]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682518.453946189]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682518.457206532]: wait-interpolation debug: end +[ INFO] [1732682518.806927589]: wait-interpolation debug: start +[ERROR] [1732682520.407137078]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682520.407186868]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682520.408034323]: wait-interpolation debug: end +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +[ INFO] [1732682520.452193313]: wait-interpolation debug: start +[ INFO] [1732682521.457799163]: wait-interpolation debug: end +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +[ INFO] [1732682521.498749820]: wait-interpolation debug: start +[ INFO] [1732682522.504586883]: wait-interpolation debug: end +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +[ INFO] [1732682522.546420549]: wait-interpolation debug: start +[ INFO] [1732682523.545821332]: wait-interpolation debug: end +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +[ INFO] [1732682523.588862766]: wait-interpolation debug: start +[ INFO] [1732682524.612406607]: wait-interpolation debug: end +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +[ INFO] [1732682524.698696216]: wait-interpolation debug: start +[ INFO] [1732682525.715428407]: wait-interpolation debug: end +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +[ INFO] [1732682525.796324434]: wait-interpolation debug: start +[ INFO] [1732682526.808640232]: wait-interpolation debug: end +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +[ INFO] [1732682526.863522439]: wait-interpolation debug: start +[ INFO] [1732682527.866654148]: wait-interpolation debug: end +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +[ INFO] [1732682527.920436930]: wait-interpolation debug: start +[ INFO] [1732682528.937991077]: wait-interpolation debug: end +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +;; # :joint-angle(88.0395) violate max-angle(88.0) +[ INFO] [1732682528.978509319]: wait-interpolation debug: start +[ INFO] [1732682529.976468908]: wait-interpolation debug: end +;; # :joint-angle(88.0395) violate max-angle(88.0) +[ INFO] [1732682532.103731411]: wait-interpolation debug: start +[ INFO] [1732682532.113393439]: wait-interpolation debug: end +[ INFO] [1732682534.936736939]: wait-interpolation debug: start +[ INFO] [1732682534.937392104]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732682535.016966422]: wait-interpolation debug: start +[ INFO] [1732682536.017744204]: wait-interpolation debug: end +[ INFO] [1732682536.117731117]: wait-interpolation debug: start +[ERROR] [1732682540.270892071]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682540.270943454]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682540.278637266]: wait-interpolation debug: end +[ INFO] [1732682541.590934744]: wait-interpolation debug: start +[ INFO] [1732682542.631283758]: wait-interpolation debug: end +[ INFO] [1732682544.601302553]: wait-interpolation debug: start +[ INFO] [1732682544.613692443]: wait-interpolation debug: end +[ INFO] [1732682545.625712559]: wait-interpolation debug: start +[ INFO] [1732682545.628720043]: wait-interpolation debug: end + C-c C-cinterrupt18.B13-irteusgl$ load "main.l" +[ WARN] [1732682555.001605644]: [/r_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732682555.001660053]: expected goal id 1732682554979098972_/pr2_eus_interface_1732680438716966801_7838_/r_gripper_controller/gripper_action_65 +[ WARN] [1732682555.001687169]: received goal id 1732682545614625400_/pr2_eus_interface_1732680438716966801_7838_/r_gripper_controller/gripper_action_64 +[ WARN] [1732682557.130260708]: continuous joint (r_forearm_roll_joint) moves -182.612 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682557.137648104]: continuous joint (r_forearm_roll_joint) moves -182.612 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682557.137721989]: original trajectory command : +[ WARN] [1732682557.137752558]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732682557.137783432]: current angle vector : #f(104.16 -1.71179 -15.913 74.1092 -25.0105 97.5568 -111.087 242.451 15.1148 35.9687 -0.302742 -96.7305 162.612 -61.955 98.6296 0.0 0.0) +[ WARN] [1732682557.137801387]: new trajectory command : dvi = 2 +[ WARN] [1732682557.137835981]: : #f(77.0801 29.1441 29.0435 72.0546 -72.5053 58.7784 -70.5437 211.226 -22.4426 54.9844 -35.1514 -108.365 71.3061 -45.9775 139.315 0.0 0.0) 500 +[ WARN] [1732682557.137871988]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732682557.137891343]: new trajectory command : +[ WARN] [1732682557.137930433]: : (#f(77.0801 29.1441 29.0435 72.0546 -72.5053 58.7784 -70.5437 211.226 -22.4426 54.9844 -35.1514 -108.365 71.3061 -45.9775 139.315 0.0 0.0) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732682557.141180857]: wait-interpolation debug: start +[ERROR] [1732682561.401438790]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682561.401510235]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682561.406539367]: wait-interpolation debug: end +[ INFO] [1732682562.794885118]: wait-interpolation debug: start +[ERROR] [1732682564.391920390]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682564.391989603]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682564.432292419]: wait-interpolation debug: end +[ INFO] [1732682570.418720687]: wait-interpolation debug: start +[ INFO] [1732682570.423798730]: wait-interpolation debug: end +[ INFO] [1732682580.135829690]: wait-interpolation debug: start +[ INFO] [1732682580.136985411]: wait-interpolation debug: end +[ INFO] [1732682586.716047668]: wait-interpolation debug: start +[ INFO] [1732682587.713589303]: wait-interpolation debug: end +[ WARN] [1732682587.747912388]: continuous joint (l_forearm_roll_joint) moves 183.515 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682587.752530405]: continuous joint (l_forearm_roll_joint) moves 183.515 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682587.752626398]: original trajectory command : +[ WARN] [1732682587.752662241]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732682587.752683880]: current angle vector : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732682587.752696224]: new trajectory command : dvi = 2 +[ WARN] [1732682587.752733318]: : #f(50.0 1.586 23.3163 18.0552 -87.5893 98.265 -49.402 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732682587.752779415]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732682587.752799520]: new trajectory command : +[ WARN] [1732682587.752842844]: : (#f(50.0 1.586 23.3163 18.0552 -87.5893 98.265 -49.402 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732682587.756587060]: wait-interpolation debug: start +[ INFO] [1732682588.933268190]: wait-interpolation debug: end +[ WARN] [1732682589.003404629]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682589.005790169]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682589.005851086]: original trajectory command : +[ WARN] [1732682589.005903590]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (500) +[ WARN] [1732682589.005948506]: current angle vector : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732682589.005972265]: new trajectory command : dvi = 2 +[ WARN] [1732682589.006020774]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) 250 +[ WARN] [1732682589.006071166]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) 250 +[ WARN] [1732682589.006096818]: new trajectory command : +[ WARN] [1732682589.006143771]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (250 250) +[ INFO] [1732682589.008785713]: wait-interpolation debug: start +[ERROR] [1732682590.620717926]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682590.620786758]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682590.627269405]: wait-interpolation debug: end +[ INFO] [1732682591.006120345]: wait-interpolation debug: start +[ INFO] [1732682592.456797667]: wait-interpolation debug: end +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +[ INFO] [1732682592.501493161]: wait-interpolation debug: start +[ INFO] [1732682593.515558963]: wait-interpolation debug: end +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +[ INFO] [1732682593.562788165]: wait-interpolation debug: start +[ INFO] [1732682594.565839761]: wait-interpolation debug: end +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +[ INFO] [1732682594.606050640]: wait-interpolation debug: start +[ INFO] [1732682595.617434639]: wait-interpolation debug: end +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +[ INFO] [1732682595.660625778]: wait-interpolation debug: start +[ INFO] [1732682596.674071295]: wait-interpolation debug: end +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +[ INFO] [1732682596.728459593]: wait-interpolation debug: start +[ INFO] [1732682597.738441594]: wait-interpolation debug: end +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +[ INFO] [1732682597.814330990]: wait-interpolation debug: start +[ INFO] [1732682598.828291990]: wait-interpolation debug: end +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +[ INFO] [1732682598.906485233]: wait-interpolation debug: start +[ INFO] [1732682599.924100219]: wait-interpolation debug: end +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +[ INFO] [1732682599.965960338]: wait-interpolation debug: start +[ INFO] [1732682600.976820392]: wait-interpolation debug: end +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +;; # :joint-angle(88.0392) violate max-angle(88.0) +[ INFO] [1732682601.016761553]: wait-interpolation debug: start +[ INFO] [1732682602.018082331]: wait-interpolation debug: end +;; # :joint-angle(88.0392) violate max-angle(88.0) +[ INFO] [1732682604.135800501]: wait-interpolation debug: start +[ INFO] [1732682604.136173537]: wait-interpolation debug: end +[ INFO] [1732682606.942419595]: wait-interpolation debug: start +[ INFO] [1732682606.945713245]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732682606.986950196]: wait-interpolation debug: start +[ INFO] [1732682608.006207999]: wait-interpolation debug: end +[ INFO] [1732682608.086212676]: wait-interpolation debug: start +[ INFO] [1732682604.136173537]: wait-interpolation debug: end C-c C-cinterrupt19.B14-irteusgl$ C-c C-cinterrupt19.B15-irteusgl$ C-c C-cinterrupt19.B16-irteusgl$ (send *ri* :stop-grasp) +[ERROR] [1732682632.370002218]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682632.370055383]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +(t t) +20.B16-irteusgl$ load "main.l" +[ WARN] [1732682887.620868324]: [/r_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732682887.620907091]: expected goal id 1732682887582689513_/pr2_eus_interface_1732680438716966801_7838_/r_gripper_controller/gripper_action_69 +[ WARN] [1732682887.620923598]: received goal id 1732682632320071307_/pr2_eus_interface_1732680438716966801_7838_/r_gripper_controller/gripper_action_68 +[ WARN] [1732682889.776853845]: continuous joint (r_forearm_roll_joint) moves -222.169 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682889.789175583]: continuous joint (r_forearm_roll_joint) moves -222.169 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682889.789307024]: original trajectory command : +[ WARN] [1732682889.789384662]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732682889.789459256]: current angle vector : #f(104.16 -1.71179 -15.913 74.1092 -25.0105 97.5568 -111.087 242.451 -5.42897 48.6048 16.083 -96.3645 202.169 -52.1115 64.8881 0.0 0.0) +[ WARN] [1732682889.789505302]: new trajectory command : dvi = 2 +[ WARN] [1732682889.789596290]: : #f(77.0801 29.1441 29.0435 72.0546 -72.5053 58.7784 -70.5437 211.226 -32.7145 61.3024 -26.9585 -108.182 91.0844 -41.0558 122.444 0.0 0.0) 500 +[ WARN] [1732682889.789684883]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732682889.789749338]: new trajectory command : +[ WARN] [1732682889.789847853]: : (#f(77.0801 29.1441 29.0435 72.0546 -72.5053 58.7784 -70.5437 211.226 -32.7145 61.3024 -26.9585 -108.182 91.0844 -41.0558 122.444 0.0 0.0) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732682889.796952192]: wait-interpolation debug: start +[ERROR] [1732682894.077026770]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682894.077143824]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682894.093195575]: wait-interpolation debug: end +[ INFO] [1732682895.472454936]: wait-interpolation debug: start +[ERROR] [1732682897.087957645]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682897.088000008]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682897.092203860]: wait-interpolation debug: end +[ INFO] [1732682903.008036219]: wait-interpolation debug: start +[ INFO] [1732682903.009502257]: wait-interpolation debug: end +[ INFO] [1732682912.803861078]: wait-interpolation debug: start +[ INFO] [1732682912.804005582]: wait-interpolation debug: end +[ INFO] [1732682919.391901569]: wait-interpolation debug: start +[ INFO] [1732682920.394718366]: wait-interpolation debug: end +[ WARN] [1732682920.429005485]: continuous joint (l_forearm_roll_joint) moves 183.515 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682920.433456031]: continuous joint (l_forearm_roll_joint) moves 183.515 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682920.433546209]: original trajectory command : +[ WARN] [1732682920.433581926]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732682920.433616416]: current angle vector : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732682920.433637764]: new trajectory command : dvi = 2 +[ WARN] [1732682920.433678475]: : #f(50.0 1.586 23.3163 18.0552 -87.5893 98.265 -49.402 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732682920.433711863]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732682920.433737516]: new trajectory command : +[ WARN] [1732682920.433795677]: : (#f(50.0 1.586 23.3163 18.0552 -87.5893 98.265 -49.402 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732682920.438380169]: wait-interpolation debug: start +[ INFO] [1732682921.633102552]: wait-interpolation debug: end +[ WARN] [1732682921.713356349]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682921.715863733]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732682921.715948962]: original trajectory command : +[ WARN] [1732682921.716005542]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (500) +[ WARN] [1732682921.716053502]: current angle vector : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732682921.716081556]: new trajectory command : dvi = 2 +[ WARN] [1732682921.716140330]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) 250 +[ WARN] [1732682921.716206758]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) 250 +[ WARN] [1732682921.716244068]: new trajectory command : +[ WARN] [1732682921.716305475]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (250 250) +[ INFO] [1732682921.726930213]: wait-interpolation debug: start +[ERROR] [1732682923.331341866]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682923.331403758]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682923.339650636]: wait-interpolation debug: end +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0264) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0431) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0454) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +[ INFO] [1732682924.054526682]: wait-interpolation debug: start +[ INFO] [1732682925.446230176]: wait-interpolation debug: end +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +[ INFO] [1732682925.509824533]: wait-interpolation debug: start +[ INFO] [1732682926.512632066]: wait-interpolation debug: end +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +[ INFO] [1732682926.558113858]: wait-interpolation debug: start +[ INFO] [1732682927.563128244]: wait-interpolation debug: end +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +[ INFO] [1732682927.604144101]: wait-interpolation debug: start +[ INFO] [1732682928.603655214]: wait-interpolation debug: end +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +[ INFO] [1732682928.644745743]: wait-interpolation debug: start +[ INFO] [1732682929.652984421]: wait-interpolation debug: end +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +[ INFO] [1732682929.693267523]: wait-interpolation debug: start +[ INFO] [1732682930.694671776]: wait-interpolation debug: end +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +[ INFO] [1732682930.734779952]: wait-interpolation debug: start +[ INFO] [1732682931.772065198]: wait-interpolation debug: end +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +[ INFO] [1732682931.811506092]: wait-interpolation debug: start +[ INFO] [1732682932.814897702]: wait-interpolation debug: end +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +[ INFO] [1732682932.886222692]: wait-interpolation debug: start +[ INFO] [1732682933.886716212]: wait-interpolation debug: end +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +;; # :joint-angle(88.0448) violate max-angle(88.0) +[ INFO] [1732682933.927182934]: wait-interpolation debug: start +[ INFO] [1732682934.925430491]: wait-interpolation debug: end +;; # :joint-angle(88.0448) violate max-angle(88.0) +[ INFO] [1732682937.112562159]: wait-interpolation debug: start +[ INFO] [1732682937.124580178]: wait-interpolation debug: end +[ INFO] [1732682939.939143349]: wait-interpolation debug: start +[ INFO] [1732682939.951836069]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732682939.991565923]: wait-interpolation debug: start +[ INFO] [1732682940.993489325]: wait-interpolation debug: end +[ INFO] [1732682941.061606626]: wait-interpolation debug: start +[ERROR] [1732682945.209140180]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732682945.209183256]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732682945.219871749]: wait-interpolation debug: end +[ INFO] [1732682946.526551251]: wait-interpolation debug: start +[ INFO] [1732682947.527496709]: wait-interpolation debug: end +[ INFO] [1732682949.498733385]: wait-interpolation debug: start +[ INFO] [1732682949.498994801]: wait-interpolation debug: end +[ INFO] [1732682950.528727632]: wait-interpolation debug: start +[ INFO] [1732682950.543672271]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732682956.031965136]: wait-interpolation debug: start +[ INFO] [1732682957.098588772]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732682957.136106881]: wait-interpolation debug: start +[ INFO] [1732682958.144997507]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732682958.186109018]: wait-interpolation debug: start +[ INFO] [1732682959.195712115]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732682959.236025201]: wait-interpolation debug: start +[ INFO] [1732682960.235426106]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732682960.289321553]: wait-interpolation debug: start +[ INFO] [1732682961.288999485]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732682961.333357527]: wait-interpolation debug: start +[ INFO] [1732682962.339784769]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732682962.383568590]: wait-interpolation debug: start +[ INFO] [1732682963.386068722]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732682963.426447638]: wait-interpolation debug: start +[ INFO] [1732682964.424282140]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732682964.466875502]: wait-interpolation debug: start +[ INFO] [1732682965.475901455]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732682965.547188327]: wait-interpolation debug: start +[ INFO] [1732682966.553669370]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732682966.628022718]: wait-interpolation debug: start +[ INFO] [1732682967.633728386]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) C-c C-cinterrupt21.B17-irteusgl$ (send *ri* :stop-grasp) +[ WARN] [1732682988.133385278]: [/r_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732682988.133450734]: expected goal id 1732682988099450041_/pr2_eus_interface_1732680438716966801_7838_/r_gripper_controller/gripper_action_76 +[ WARN] [1732682988.133482894]: received goal id 1732682967636128704_/pr2_eus_interface_1732680438716966801_7838_/r_gripper_controller/gripper_action_75 +(t t) +22.B17-irteusgl$ (exit) +[ INFO] [1732683221.785149941]: cell* ROSEUS_EXIT(context*, int, cell**) +[ INFO] [1732683221.785255141]: exiting roseus 0 +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rossetmaste +rossetmaste: command not found +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rossetmaster +set ROS_MASTER_URI to http://localhost:11311 +mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ roseus +configuring by "/opt/ros/noetic/share/euslisp/jskeus/eus//lib/eusrt.l" +;; readmacro ;; object ;; packsym ;; common ;; constants ;; stream ;; string ;; loader ;; pprint ;; process ;; hashtab ;; array ;; mathtran ;; eusdebug ;; eusforeign ;; extnum ;; coordinates ;; tty ;; history ;; toplevel ;; trans ;; comp ;; builtins ;; par ;; intersection ;; geoclasses ;; geopack ;; geobody ;; primt ;; compose ;; polygon ;; viewing ;; viewport ;; viewsurface ;; hid ;; shadow ;; bodyrel ;; dda ;; helpsub ;; eushelp ;; xforeign ;; Xdecl ;; Xgraphics ;; Xcolor ;; Xeus ;; Xevent ;; Xpanel ;; Xitem ;; Xtext ;; Xmenu ;; Xscroll ;; Xcanvas ;; Xtop ;; Xapplwin +connected to Xserver DISPLAY=:0 +X events are being asynchronously monitored. +;; pixword ;; RGBHLS ;; convolve ;; piximage ;; pbmfile ;; image_correlation ;; oglforeign ;; gldecl ;; glconst ;; glforeign ;; gluconst ;; gluforeign ;; glxconst ;; glxforeign ;; eglforeign ;; eglfunc ;; glutil ;; gltexture ;; glprim ;; gleus ;; glview ;; toiv-undefined ;; fstringdouble irtmath irtutil irtc irtgeoc irtgraph gnuplotlib ___time ___pgsql irtgeo euspqp pqp irtscene irtmodel irtdyna irtrobot irtsensor irtbvh irtcollada irtstl irtwrl irtpointcloud eusbullet bullet irtcollision irtx eusjpeg euspng png irtimage irtglrgb +;; extending gcstack 0x55bf7e1f7680[16374] --> 0x55bf7e687c90[32748] top=3d4b +irtgl irtglc irtviewer +EusLisp 9.29( 1.2.5) for Linux64 created on ip-10-0-1-5(Tue Jun 20 10:34:21 PST 2023) +roseus ;; loading roseus("1.7.5") on euslisp((9.29 ip-10-0-1-5 Tue Jun 20 10:34:21 PST 2023 1.2.5)) +eustf roseus_c_util 1.irteusgl$ load "main.l" +;; roseus_resume is disabled. + +;; extending gcstack 0x55bf7e687c90[32738] --> 0x55bf801a56e0[65476] top=7ed2 +[ WARN] [1732683242.441508369]: [l_arm_controller/follow_joint_trajectory] action server is not found +[ WARN] [1732683242.444810842]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732683242.444956156]: # is not respond, pr2-interface is disabled +[ WARN] [1732683242.445013090]: Starting 'Kinematics Simulator' +[ WARN] [1732683242.445097171]: (If you do not intend to start Kinematics Simulator, make sure that you can run 'rostopic info /l_arm_controller/follow_joint_trajectory/goal' and 'rostopic info /l_arm_controller/follow_joint_trajectory/cancel' and check whether Subscribers exists. If there is no Subscribers, please check joint_trajectory_action node.) +[ WARN] [1732683242.445170183]: (Please also check 'rostopic info /l_arm_controller/follow_joint_trajectory/feedback' and 'rostopic info /l_arm_controller/follow_joint_trajectory/result' and check whether Publishers exists. If there is no Publishers, please check joint_trajectory_action node.) +[ WARN] [1732683242.445256983]: (If joint_trajectory_action node already exists, you might have a network problem. Please make sure that you can run 'rosnode ping JOINT_TRAJECTORY_ACTION_SERVER_NODE_NAME' and 'rosnode ping /pr2_eus_interface_1732683238730027337') +current *timer-job* is ((lambda nil (send # :robot-interface-simulation-callback)) lisp::count-up-timer) +[ WARN] [1732683245.721084598]: [/base_controller/follow_joint_trajectory] action server is not found +[ WARN] [1732683245.721244301]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732683245.721297423]: move-base-trajectory-action is not found +[ WARN] [1732683245.758770777]: # is not respond, pr2-interface is disabled +;; (make-irtviewer) executed +[ WARN] [1732683246.939918729]: [robotsound_jp] action server is not found +[ WARN] [1732683246.940116471]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732683246.940216639]: action server /robotsound_jp not found. +[ WARN] [1732683248.674105352]: topic /robotsound_jp/goal already advertised +[ WARN] [1732683248.674166557]: topic /robotsound_jp/cancel already advertised +[ WARN] [1732683249.783267676]: [robotsound_jp] action server is not found +[ WARN] [1732683249.783494384]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732683249.783599906]: action server /robotsound_jp not found. +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +[ WARN] [1732683252.798038587]: topic /robotsound_jp/goal already advertised +[ WARN] [1732683252.798188758]: topic /robotsound_jp/cancel already advertised +[ WARN] [1732683253.916832631]: [robotsound_jp] action server is not found +[ WARN] [1732683253.917045314]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732683253.917132392]: action server /robotsound_jp not found. +[ WARN] [1732683253.942031605]: topic /robotsound_jp/goal already advertised +[ WARN] [1732683253.942214863]: topic /robotsound_jp/cancel already advertised +[ WARN] [1732683255.063582499]: [robotsound_jp] action server is not found +[ WARN] [1732683255.063899357]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732683255.064024975]: action server /robotsound_jp not found. +[ WARN] [1732683257.427602180]: continuous joint (l_forearm_roll_joint) moves 183.515 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683257.807539939]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683257.807613594]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +[ WARN] [1732683258.424121279]: continuous joint (l_forearm_roll_joint) moves 280.678 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683258.424197589]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683259.027142181]: continuous joint (l_forearm_roll_joint) moves 358.123 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683259.027216125]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683259.614272537]: continuous joint (l_forearm_roll_joint) moves 358.303 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683259.614342229]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683260.226144024]: continuous joint (l_forearm_roll_joint) moves 358.467 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683260.226219425]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683260.826284658]: continuous joint (l_forearm_roll_joint) moves 358.618 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683260.826374788]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683261.425857072]: continuous joint (l_forearm_roll_joint) moves 358.755 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683261.425932002]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683262.054589523]: continuous joint (l_forearm_roll_joint) moves 358.879 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683262.054674470]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683262.633691358]: continuous joint (l_forearm_roll_joint) moves 358.992 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683262.633782577]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683263.240960364]: continuous joint (l_forearm_roll_joint) moves 359.095 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683263.241032850]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683263.833010083]: continuous joint (l_forearm_roll_joint) moves 359.188 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683263.833096151]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +remaining 100 +[ WARN] [1732683265.516026261]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683265.516106560]: continuous joint (r_forearm_roll_joint) moves 370.456 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683266.102949490]: continuous joint (l_forearm_roll_joint) moves 358.438 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683266.103036302]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683267.527632419]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683267.527717276]: continuous joint (r_forearm_roll_joint) moves 345.043 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +[ WARN] [1732683269.097942506]: topic /robotsound_jp/goal already advertised +[ WARN] [1732683269.097998290]: topic /robotsound_jp/cancel already advertised +[ WARN] [1732683270.205563124]: [robotsound_jp] action server is not found +[ WARN] [1732683270.205754347]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732683270.205849701]: action server /robotsound_jp not found. +[ WARN] [1732683271.269889439]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683271.269964416]: continuous joint (r_forearm_roll_joint) moves 351.994 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +[ WARN] [1732683271.894044543]: continuous joint (l_forearm_roll_joint) moves 361.753 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683271.894120614]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683272.518118342]: continuous joint (l_forearm_roll_joint) moves 359.192 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683272.518200362]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683273.108385331]: continuous joint (l_forearm_roll_joint) moves 359.258 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683273.108460059]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683273.708654524]: continuous joint (l_forearm_roll_joint) moves 359.32 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683273.708723444]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683274.302318008]: continuous joint (l_forearm_roll_joint) moves 359.376 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683274.302393523]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683274.916957102]: continuous joint (l_forearm_roll_joint) moves 359.428 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683274.917030265]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683275.503042247]: continuous joint (l_forearm_roll_joint) moves 359.476 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683275.503137354]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683276.109258782]: continuous joint (l_forearm_roll_joint) moves 359.521 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683276.109329646]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683276.701386758]: continuous joint (l_forearm_roll_joint) moves 359.562 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683276.701462342]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683277.305497151]: continuous joint (l_forearm_roll_joint) moves 359.601 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683277.305570114]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +remaining 100 +[ WARN] [1732683278.948081062]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683278.948193706]: continuous joint (r_forearm_roll_joint) moves 371.707 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683279.575866622]: continuous joint (l_forearm_roll_joint) moves 356.912 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683279.575960816]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683280.381971041]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683280.382063873]: continuous joint (r_forearm_roll_joint) moves 354.869 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +[ WARN] [1732683281.996899839]: topic /robotsound_jp/goal already advertised +[ WARN] [1732683281.996960881]: topic /robotsound_jp/cancel already advertised +[ WARN] [1732683283.103681727]: [robotsound_jp] action server is not found +[ WARN] [1732683283.103956936]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732683283.104087013]: action server /robotsound_jp not found. +[ WARN] [1732683284.191648875]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683284.191736117]: continuous joint (r_forearm_roll_joint) moves 345.098 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +[ WARN] [1732683284.812312353]: continuous joint (l_forearm_roll_joint) moves 363.684 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683284.812382501]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683285.417954587]: continuous joint (l_forearm_roll_joint) moves 359.6 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683285.418035597]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683286.013428621]: continuous joint (l_forearm_roll_joint) moves 359.627 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683286.013506443]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683286.622166776]: continuous joint (l_forearm_roll_joint) moves 359.653 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683286.622247527]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683287.253089654]: continuous joint (l_forearm_roll_joint) moves 359.677 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683287.253165956]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683287.841452112]: continuous joint (l_forearm_roll_joint) moves 359.7 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683287.841526381]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683288.439727292]: continuous joint (l_forearm_roll_joint) moves 359.721 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683288.439797685]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683289.041086765]: continuous joint (l_forearm_roll_joint) moves 359.742 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683289.041160822]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683289.641552856]: continuous joint (l_forearm_roll_joint) moves 359.76 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683289.641643640]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683290.264140380]: continuous joint (l_forearm_roll_joint) moves 359.778 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683290.264234778]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +remaining 100 +[ WARN] [1732683291.898753169]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683291.898865917]: continuous joint (r_forearm_roll_joint) moves 370.41 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683292.515501113]: continuous joint (l_forearm_roll_joint) moves 356.487 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683292.515594508]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683293.140585403]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683293.140661015]: continuous joint (r_forearm_roll_joint) moves 363.726 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +[ WARN] [1732683294.719117400]: topic /robotsound_jp/goal already advertised +[ WARN] [1732683294.719179177]: topic /robotsound_jp/cancel already advertised +[ WARN] [1732683295.825335539]: [robotsound_jp] action server is not found +[ WARN] [1732683295.825535681]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732683295.825620145]: action server /robotsound_jp not found. +[ WARN] [1732683296.888634123]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683296.888708868]: continuous joint (r_forearm_roll_joint) moves 341.749 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +[ WARN] [1732683297.518258784]: continuous joint (l_forearm_roll_joint) moves 364.519 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683297.518327489]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683298.149406714]: continuous joint (l_forearm_roll_joint) moves 359.755 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683298.149480667]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683298.725800935]: continuous joint (l_forearm_roll_joint) moves 359.769 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683298.725878003]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683299.339013214]: continuous joint (l_forearm_roll_joint) moves 359.783 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683299.339094229]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683299.939392090]: continuous joint (l_forearm_roll_joint) moves 359.795 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683299.939467899]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683300.539336552]: continuous joint (l_forearm_roll_joint) moves 359.807 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683300.539410105]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683301.125789630]: continuous joint (l_forearm_roll_joint) moves 359.818 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683301.125858665]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683301.739740340]: continuous joint (l_forearm_roll_joint) moves 359.829 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683301.739811643]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683302.339547801]: continuous joint (l_forearm_roll_joint) moves 359.839 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683302.339626119]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683302.949147208]: continuous joint (l_forearm_roll_joint) moves 359.848 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683302.949220843]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +remaining 100 +[ WARN] [1732683304.593323237]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683304.593410988]: continuous joint (r_forearm_roll_joint) moves 368.075 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683305.203464340]: continuous joint (l_forearm_roll_joint) moves 356.063 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683305.203538509]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683305.803051563]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683305.803143622]: continuous joint (r_forearm_roll_joint) moves 370.128 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +[ WARN] [1732683307.419968419]: topic /robotsound_jp/goal already advertised +[ WARN] [1732683307.420112712]: topic /robotsound_jp/cancel already advertised +[ WARN] [1732683308.540735925]: [robotsound_jp] action server is not found +[ WARN] [1732683308.540932829]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732683308.541018519]: action server /robotsound_jp not found. +[ WARN] [1732683309.628970400]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683309.629038842]: continuous joint (r_forearm_roll_joint) moves 340.207 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +[ WARN] [1732683310.266535636]: continuous joint (l_forearm_roll_joint) moves 364.983 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683310.266612635]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683310.851576066]: continuous joint (l_forearm_roll_joint) moves 359.825 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683310.851671085]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683311.471487367]: continuous joint (l_forearm_roll_joint) moves 359.834 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683311.471560663]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683312.059705870]: continuous joint (l_forearm_roll_joint) moves 359.841 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683312.059785436]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683312.667071522]: continuous joint (l_forearm_roll_joint) moves 359.849 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683312.667152385]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683313.262150066]: continuous joint (l_forearm_roll_joint) moves 359.856 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683313.262228719]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683313.894408907]: continuous joint (l_forearm_roll_joint) moves 359.862 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683313.894480383]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683314.487606547]: continuous joint (l_forearm_roll_joint) moves 359.869 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683314.487680198]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683315.074692505]: continuous joint (l_forearm_roll_joint) moves 359.874 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683315.074782388]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683315.689511294]: continuous joint (l_forearm_roll_joint) moves 359.88 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683315.689585065]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +remaining 100 +[ WARN] [1732683317.348539758]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683317.348623193]: continuous joint (r_forearm_roll_joint) moves 365.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683317.989074261]: continuous joint (l_forearm_roll_joint) moves 355.622 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683317.989149139]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683318.550399973]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683318.550483159]: continuous joint (r_forearm_roll_joint) moves 374.539 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +[ WARN] [1732683320.194452472]: topic /robotsound_jp/goal already advertised +[ WARN] [1732683320.194541892]: topic /robotsound_jp/cancel already advertised +[ WARN] [1732683321.308327223]: [robotsound_jp] action server is not found +[ WARN] [1732683321.308620683]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732683321.308747361]: action server /robotsound_jp not found. +t +2.irteusgl$(exit) +[ INFO] [1732683330.177736343]: cell* ROSEUS_EXIT(context*, int, cell**) +[ INFO] [1732683330.177874426]: exiting roseus 0 +mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rossetmaster pr1040 +set ROS_MASTER_URI to http://pr1040:11311 +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ load "main.l" + +Command 'load' not found, did you mean: + + command 'nload' from deb nload (0.7.4-2build3) + command 'xload' from deb x11-apps (7.7+8) + command 'tload' from deb procps (2:3.3.16-1ubuntu2.4) + +Try: sudo apt install + +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ roseus +configuring by "/opt/ros/noetic/share/euslisp/jskeus/eus//lib/eusrt.l" +;; readmacro ;; object ;; packsym ;; common ;; constants ;; stream ;; string ;; loader ;; pprint ;; process ;; hashtab ;; array ;; mathtran ;; eusdebug ;; eusforeign ;; extnum ;; coordinates ;; tty ;; history ;; toplevel ;; trans ;; comp ;; builtins ;; par ;; intersection ;; geoclasses ;; geopack ;; geobody ;; primt ;; compose ;; polygon ;; viewing ;; viewport ;; viewsurface ;; hid ;; shadow ;; bodyrel ;; dda ;; helpsub ;; eushelp ;; xforeign ;; Xdecl ;; Xgraphics ;; Xcolor ;; Xeus ;; Xevent ;; Xpanel ;; Xitem ;; Xtext ;; Xmenu ;; Xscroll ;; Xcanvas ;; Xtop ;; Xapplwin +connected to Xserver DISPLAY=:0 +X events are being asynchronously monitored. +;; pixword ;; RGBHLS ;; convolve ;; piximage ;; pbmfile ;; image_correlation ;; oglforeign ;; gldecl ;; glconst ;; glforeign ;; gluconst ;; gluforeign ;; glxconst ;; glxforeign ;; eglforeign ;; eglfunc ;; glutil ;; gltexture ;; glprim ;; gleus ;; glview ;; toiv-undefined ;; fstringdouble irtmath irtutil irtc irtgeoc irtgraph gnuplotlib ___time ___pgsql irtgeo euspqp pqp irtscene irtmodel irtdyna irtrobot irtsensor irtbvh irtcollada irtstl irtwrl irtpointcloud eusbullet bullet irtcollision irtx eusjpeg euspng png irtimage irtglrgb +;; extending gcstack 0x5594c9d58680[16374] --> 0x5594ca1e8c90[32748] top=3d4b +irtgl irtglc irtviewer +EusLisp 9.29( 1.2.5) for Linux64 created on ip-10-0-1-5(Tue Jun 20 10:34:21 PST 2023) +roseus ;; loading roseus("1.7.5") on euslisp((9.29 ip-10-0-1-5 Tue Jun 20 10:34:21 PST 2023 1.2.5)) +eustf roseus_c_util 1.irteusgl$ load "main.l" +;; roseus_resume is disabled. + +;; extending gcstack 0x5594ca1e8c90[32738] --> 0x5594cbd066e0[65476] top=7ed2 +;; # :joint-angle(88.0674) violate max-angle(88.0) +;; (make-irtviewer) executed +[ INFO] [1732683394.445457096]: wait-interpolation debug: start +[ERROR] [1732683398.619994636]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732683398.620115710]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732683398.628196304]: wait-interpolation debug: end +[ INFO] [1732683400.224272943]: wait-interpolation debug: start +[ERROR] [1732683401.827084870]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732683401.827207384]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732683401.828992403]: wait-interpolation debug: end +[ INFO] [1732683407.712384230]: wait-interpolation debug: start +[ INFO] [1732683407.728688117]: wait-interpolation debug: end +[ INFO] [1732683417.599693821]: wait-interpolation debug: start +[ INFO] [1732683417.599913032]: wait-interpolation debug: end +[ INFO] [1732683424.144198107]: wait-interpolation debug: start +[ INFO] [1732683425.176446479]: wait-interpolation debug: end +[ WARN] [1732683425.213047435]: continuous joint (l_forearm_roll_joint) moves 183.515 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683425.215677529]: continuous joint (l_forearm_roll_joint) moves 183.515 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683425.215750125]: original trajectory command : +[ WARN] [1732683425.215775616]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732683425.215799076]: current angle vector : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732683425.215811005]: new trajectory command : dvi = 2 +[ WARN] [1732683425.215839264]: : #f(50.0 1.586 23.3163 18.0552 -87.5893 98.265 -49.402 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732683425.215861730]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732683425.215880728]: new trajectory command : +[ WARN] [1732683425.215912543]: : (#f(50.0 1.586 23.3163 18.0552 -87.5893 98.265 -49.402 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732683425.218105946]: wait-interpolation debug: start +[ INFO] [1732683426.400399509]: wait-interpolation debug: end +[ WARN] [1732683426.446348971]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683426.449372011]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683426.449418879]: original trajectory command : +[ WARN] [1732683426.449455274]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (500) +[ WARN] [1732683426.449505538]: current angle vector : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732683426.449526522]: new trajectory command : dvi = 2 +[ WARN] [1732683426.449577862]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) 250 +[ WARN] [1732683426.449638250]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) 250 +[ WARN] [1732683426.449666936]: new trajectory command : +[ WARN] [1732683426.449734133]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (250 250) +[ INFO] [1732683426.455662242]: wait-interpolation debug: start +[ERROR] [1732683428.065006373]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732683428.065082097]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732683428.075594937]: wait-interpolation debug: end +;; # :joint-angle(88.038) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0644) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732683428.522944828]: wait-interpolation debug: start +[ INFO] [1732683429.809135248]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683429.855679704]: wait-interpolation debug: start +[ INFO] [1732683430.862352666]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683430.899614988]: wait-interpolation debug: start +[ INFO] [1732683431.902725344]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683431.938752799]: wait-interpolation debug: start +[ INFO] [1732683432.942656107]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683432.988956761]: wait-interpolation debug: start +[ INFO] [1732683433.987084449]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683434.025519197]: wait-interpolation debug: start +[ INFO] [1732683435.029123067]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683435.067990638]: wait-interpolation debug: start +[ INFO] [1732683436.073951660]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683436.112329665]: wait-interpolation debug: start +[ INFO] [1732683437.115676749]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683437.152067822]: wait-interpolation debug: start +[ INFO] [1732683438.157909342]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683438.205352578]: wait-interpolation debug: start +[ INFO] [1732683439.210170716]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683441.365787565]: wait-interpolation debug: start +[ INFO] [1732683441.366088964]: wait-interpolation debug: end +[ INFO] [1732683444.177499816]: wait-interpolation debug: start +[ INFO] [1732683444.182553288]: wait-interpolation debug: end +remaining 100 +[ INFO] [1732683444.221587211]: wait-interpolation debug: start +[ INFO] [1732683445.225291205]: wait-interpolation debug: end +[ INFO] [1732683445.289888537]: wait-interpolation debug: start +[ERROR] [1732683449.467218168]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732683449.467271963]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732683449.472842822]: wait-interpolation debug: end +[ INFO] [1732683450.767046442]: wait-interpolation debug: start +[ INFO] [1732683451.788457431]: wait-interpolation debug: end +[ INFO] [1732683453.769999844]: wait-interpolation debug: start +[ INFO] [1732683453.774153367]: wait-interpolation debug: end +[ INFO] [1732683454.802334214]: wait-interpolation debug: start +[ INFO] [1732683454.813488322]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732683460.271611063]: wait-interpolation debug: start +[ INFO] [1732683461.276578809]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732683461.353541524]: wait-interpolation debug: start +[ INFO] [1732683462.357924864]: wait-interpolation debug: end +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +[ INFO] [1732683462.430333948]: wait-interpolation debug: start +[ INFO] [1732683463.442725067]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732683463.511310365]: wait-interpolation debug: start +[ INFO] [1732683464.514600525]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732683464.556049204]: wait-interpolation debug: start +[ INFO] [1732683465.561842992]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732683465.597205809]: wait-interpolation debug: start +[ INFO] [1732683466.602758113]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732683466.637817466]: wait-interpolation debug: start +[ INFO] [1732683467.646321397]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732683467.686371949]: wait-interpolation debug: start +[ INFO] [1732683468.695793886]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732683468.734967472]: wait-interpolation debug: start +[ INFO] [1732683469.752060943]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732683469.789883063]: wait-interpolation debug: start +[ INFO] [1732683470.797522837]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732683470.837383208]: wait-interpolation debug: start +[ INFO] [1732683471.843459406]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732683471.882557539]: wait-interpolation debug: start +[ INFO] [1732683472.926285656]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732683475.085014779]: wait-interpolation debug: start +[ INFO] [1732683475.085433185]: wait-interpolation debug: end +[ INFO] [1732683477.910002520]: wait-interpolation debug: start +[ INFO] [1732683477.914581058]: wait-interpolation debug: end +remaining 100 +[ INFO] [1732683477.956482026]: wait-interpolation debug: start +[ INFO] [1732683478.962340753]: wait-interpolation debug: end +[ INFO] [1732683479.026766240]: wait-interpolation debug: start +[ERROR] [1732683481.510408107]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732683481.510464397]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732683481.515191300]: wait-interpolation debug: end +[ INFO] [1732683482.389763080]: wait-interpolation debug: start +[ INFO] [1732683483.399022976]: wait-interpolation debug: end +[ INFO] [1732683485.371504302]: wait-interpolation debug: start +[ INFO] [1732683485.377694952]: wait-interpolation debug: end +[ INFO] [1732683486.406852544]: wait-interpolation debug: start +[ INFO] [1732683486.423259765]: wait-interpolation debug: end +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +[ INFO] [1732683491.817228898]: wait-interpolation debug: start +[ INFO] [1732683492.826801720]: wait-interpolation debug: end +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +[ INFO] [1732683492.872763065]: wait-interpolation debug: start +[ INFO] [1732683493.885300191]: wait-interpolation debug: end +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +[ INFO] [1732683493.930400673]: wait-interpolation debug: start +[ INFO] [1732683494.967687027]: wait-interpolation debug: end +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +[ INFO] [1732683495.008419868]: wait-interpolation debug: start +[ INFO] [1732683496.013505544]: wait-interpolation debug: end +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +[ INFO] [1732683496.049746248]: wait-interpolation debug: start +[ INFO] [1732683497.058851807]: wait-interpolation debug: end +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +[ INFO] [1732683497.096128428]: wait-interpolation debug: start +[ INFO] [1732683498.109043157]: wait-interpolation debug: end +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +[ INFO] [1732683498.146364336]: wait-interpolation debug: start +[ INFO] [1732683499.154562171]: wait-interpolation debug: end +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +[ INFO] [1732683499.191820999]: wait-interpolation debug: start +[ WARN] [1732683499.204766688]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ INFO] [1732683500.202507480]: wait-interpolation debug: end +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +[ INFO] [1732683500.238461715]: wait-interpolation debug: start +[ INFO] [1732683501.250135233]: wait-interpolation debug: end +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +[ INFO] [1732683501.319649477]: wait-interpolation debug: start +[ INFO] [1732683502.329677332]: wait-interpolation debug: end +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +[ INFO] [1732683502.365170354]: wait-interpolation debug: start +[ INFO] [1732683503.371635956]: wait-interpolation debug: end +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +[ INFO] [1732683503.408737670]: wait-interpolation debug: start +[ INFO] [1732683504.435982657]: wait-interpolation debug: end +;; # :joint-angle(88.0653) violate max-angle(88.0) +[ INFO] [1732683506.563667209]: wait-interpolation debug: start +[ INFO] [1732683506.569123149]: wait-interpolation debug: end +[ INFO] [1732683509.409343279]: wait-interpolation debug: start +[ INFO] [1732683509.414322576]: wait-interpolation debug: end +remaining 100 +[ INFO] [1732683509.455396607]: wait-interpolation debug: start +[ INFO] [1732683510.492988918]: wait-interpolation debug: end +[ INFO] [1732683510.559921602]: wait-interpolation debug: start +[ERROR] [1732683512.350255769]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732683512.350304426]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732683512.353466203]: wait-interpolation debug: end +[ INFO] [1732683513.013748995]: wait-interpolation debug: start +[ INFO] [1732683514.018039980]: wait-interpolation debug: end +[ INFO] [1732683515.977755073]: wait-interpolation debug: start +[ INFO] [1732683515.993783341]: wait-interpolation debug: end +[ INFO] [1732683517.006714170]: wait-interpolation debug: start +[ INFO] [1732683517.013439327]: wait-interpolation debug: end +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +[ INFO] [1732683522.415239880]: wait-interpolation debug: start +[ INFO] [1732683523.428676719]: wait-interpolation debug: end +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +[ INFO] [1732683523.480867410]: wait-interpolation debug: start +[ INFO] [1732683524.485061635]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732683524.524186257]: wait-interpolation debug: start +[ INFO] [1732683525.529156141]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732683525.572997939]: wait-interpolation debug: start +[ INFO] [1732683526.574245109]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732683526.613905430]: wait-interpolation debug: start + C-c C-cinterrupt2.B1-irteusgl$ load "main.l" +[ INFO] [1732683632.669719793]: wait-interpolation debug: start +[ERROR] [1732683641.074973109]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732683641.075031672]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732683641.079795293]: wait-interpolation debug: end +[ INFO] [1732683644.139157797]: wait-interpolation debug: start +[ERROR] [1732683645.735576768]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732683645.735636701]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732683645.738578879]: wait-interpolation debug: end +[ INFO] [1732683651.651766295]: wait-interpolation debug: start +[ INFO] [1732683651.652070510]: wait-interpolation debug: end +[ INFO] [1732683661.415947210]: wait-interpolation debug: start +[ INFO] [1732683661.417841518]: wait-interpolation debug: end +[ INFO] [1732683668.026701505]: wait-interpolation debug: start +[ INFO] [1732683669.033851322]: wait-interpolation debug: end +[ WARN] [1732683669.072404088]: continuous joint (l_forearm_roll_joint) moves 183.515 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683669.074690593]: continuous joint (l_forearm_roll_joint) moves 183.515 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683669.074764430]: original trajectory command : +[ WARN] [1732683669.074811266]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732683669.074854310]: current angle vector : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732683669.074867877]: new trajectory command : dvi = 2 +[ WARN] [1732683669.074903129]: : #f(50.0 1.586 23.3163 18.0552 -87.5893 98.265 -49.402 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732683669.074947882]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732683669.074967225]: new trajectory command : +[ WARN] [1732683669.075013747]: : (#f(50.0 1.586 23.3163 18.0552 -87.5893 98.265 -49.402 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732683669.078708032]: wait-interpolation debug: start +[ INFO] [1732683670.257269986]: wait-interpolation debug: end +[ WARN] [1732683670.298733841]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683670.303415686]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732683670.303458015]: original trajectory command : +[ WARN] [1732683670.303483339]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (500) +[ WARN] [1732683670.303505426]: current angle vector : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732683670.303520260]: new trajectory command : dvi = 2 +[ WARN] [1732683670.303545097]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) 250 +[ WARN] [1732683670.303575482]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) 250 +[ WARN] [1732683670.303587451]: new trajectory command : +[ WARN] [1732683670.303614025]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (250 250) +[ INFO] [1732683670.306074878]: wait-interpolation debug: start +[ERROR] [1732683671.918945536]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732683671.918997806]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732683671.920300248]: wait-interpolation debug: end +[ INFO] [1732683672.338848134]: wait-interpolation debug: start +[ INFO] [1732683673.627923852]: wait-interpolation debug: end +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +[ INFO] [1732683673.667717843]: wait-interpolation debug: start +[ INFO] [1732683674.691990083]: wait-interpolation debug: end +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +[ INFO] [1732683674.732590408]: wait-interpolation debug: start +[ INFO] [1732683675.736247750]: wait-interpolation debug: end +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +[ INFO] [1732683675.769191781]: wait-interpolation debug: start +[ INFO] [1732683676.767120258]: wait-interpolation debug: end +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +[ INFO] [1732683676.806795740]: wait-interpolation debug: start +[ INFO] [1732683677.812197083]: wait-interpolation debug: end +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +[ INFO] [1732683677.853305054]: wait-interpolation debug: start +[ INFO] [1732683678.857470587]: wait-interpolation debug: end +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +[ INFO] [1732683678.896610841]: wait-interpolation debug: start +[ INFO] [1732683679.911079236]: wait-interpolation debug: end +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +[ INFO] [1732683679.949447853]: wait-interpolation debug: start +[ INFO] [1732683680.954917003]: wait-interpolation debug: end +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +[ INFO] [1732683680.996091645]: wait-interpolation debug: start +[ INFO] [1732683681.996293179]: wait-interpolation debug: end +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +;; # :joint-angle(88.0677) violate max-angle(88.0) +[ INFO] [1732683682.034834635]: wait-interpolation debug: start +[ INFO] [1732683683.042974239]: wait-interpolation debug: end +;; # :joint-angle(88.0677) violate max-angle(88.0) +[ INFO] [1732683685.205976429]: wait-interpolation debug: start +[ INFO] [1732683685.206336601]: wait-interpolation debug: end +[ INFO] [1732683688.012789496]: wait-interpolation debug: start +[ INFO] [1732683688.012950273]: wait-interpolation debug: end +remaining 250 +[ INFO] [1732683688.052994470]: wait-interpolation debug: start +[ INFO] [1732683689.089476428]: wait-interpolation debug: end +[ INFO] [1732683689.153021394]: wait-interpolation debug: start +[ERROR] [1732683693.303224301]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732683693.303303892]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732683693.315248192]: wait-interpolation debug: end +[ INFO] [1732683694.637284089]: wait-interpolation debug: start +[ INFO] [1732683695.653297309]: wait-interpolation debug: end +[ INFO] [1732683697.616913467]: wait-interpolation debug: start +[ INFO] [1732683697.617452509]: wait-interpolation debug: end +[ INFO] [1732683698.646640382]: wait-interpolation debug: start +[ INFO] [1732683698.662659289]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732683704.085497543]: wait-interpolation debug: start +[ INFO] [1732683705.093823571]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732683705.135784904]: wait-interpolation debug: start +[ INFO] [1732683706.137258377]: wait-interpolation debug: end +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +[ INFO] [1732683706.172813322]: wait-interpolation debug: start +[ INFO] [1732683707.175918181]: wait-interpolation debug: end +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +[ INFO] [1732683707.215907652]: wait-interpolation debug: start +[ INFO] [1732683708.223968613]: wait-interpolation debug: end +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +[ INFO] [1732683708.261343970]: wait-interpolation debug: start +[ INFO] [1732683709.270647338]: wait-interpolation debug: end +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +[ INFO] [1732683709.308310383]: wait-interpolation debug: start +[ INFO] [1732683710.316228992]: wait-interpolation debug: end +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +[ INFO] [1732683710.359200301]: wait-interpolation debug: start +[ INFO] [1732683711.388407179]: wait-interpolation debug: end +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +[ INFO] [1732683711.434011991]: wait-interpolation debug: start +[ INFO] [1732683712.438286453]: wait-interpolation debug: end +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +[ INFO] [1732683712.473727538]: wait-interpolation debug: start +[ INFO] [1732683713.476196748]: wait-interpolation debug: end +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +[ INFO] [1732683713.514975520]: wait-interpolation debug: start +[ INFO] [1732683714.515658332]: wait-interpolation debug: end +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +[ INFO] [1732683714.555830193]: wait-interpolation debug: start +[ INFO] [1732683715.555160081]: wait-interpolation debug: end +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +[ INFO] [1732683715.593352110]: wait-interpolation debug: start +[ INFO] [1732683716.608347073]: wait-interpolation debug: end +;; # :joint-angle(88.0733) violate max-angle(88.0) +[ INFO] [1732683718.752247895]: wait-interpolation debug: start +[ INFO] [1732683718.752386266]: wait-interpolation debug: end +[ INFO] [1732683721.569567862]: wait-interpolation debug: start +[ INFO] [1732683721.575014475]: wait-interpolation debug: end +remaining 250 +[ INFO] [1732683721.614954049]: wait-interpolation debug: start +[ INFO] [1732683722.617684236]: wait-interpolation debug: end +[ INFO] [1732683722.696512027]: wait-interpolation debug: start +[ERROR] [1732683725.217449921]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732683725.217497268]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732683725.222563044]: wait-interpolation debug: end +[ INFO] [1732683726.046910794]: wait-interpolation debug: start +[ INFO] [1732683727.046540162]: wait-interpolation debug: end +[ INFO] [1732683728.974777870]: wait-interpolation debug: start +[ INFO] [1732683728.975054817]: wait-interpolation debug: end +[ INFO] [1732683729.985354986]: wait-interpolation debug: start +[ INFO] [1732683729.988515741]: wait-interpolation debug: end +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +[ INFO] [1732683735.442145710]: wait-interpolation debug: start +[ INFO] [1732683736.445998229]: wait-interpolation debug: end +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +;; # :joint-angle(88.0733) violate max-angle(88.0) +[ INFO] [1732683736.486786017]: wait-interpolation debug: start +[ INFO] [1732683737.485600986]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683737.524797935]: wait-interpolation debug: start +[ INFO] [1732683738.528134401]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683738.567571760]: wait-interpolation debug: start +[ INFO] [1732683739.576653172]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683739.615988756]: wait-interpolation debug: start +[ INFO] [1732683740.627377922]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683740.666109231]: wait-interpolation debug: start +[ INFO] [1732683741.666215544]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683741.703720986]: wait-interpolation debug: start +[ INFO] [1732683742.703917072]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683742.739266109]: wait-interpolation debug: start +[ INFO] [1732683743.746864731]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683743.785104655]: wait-interpolation debug: start +[ INFO] [1732683744.786100118]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683744.826957878]: wait-interpolation debug: start +[ INFO] [1732683745.832315459]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683745.875007765]: wait-interpolation debug: start +[ INFO] [1732683746.898346810]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683746.943841548]: wait-interpolation debug: start +[ INFO] [1732683747.963058654]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732683750.085962740]: wait-interpolation debug: start +[ INFO] [1732683750.086111498]: wait-interpolation debug: end +[ INFO] [1732683752.900791694]: wait-interpolation debug: start +[ INFO] [1732683752.907162625]: wait-interpolation debug: end +remaining 250 +[ INFO] [1732683752.945217054]: wait-interpolation debug: start +[ INFO] [1732683753.952743165]: wait-interpolation debug: end +[ INFO] [1732683754.017801078]: wait-interpolation debug: start +[ERROR] [1732683755.810761871]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732683755.810812074]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732683755.814915027]: wait-interpolation debug: end +[ INFO] [1732683756.497526831]: wait-interpolation debug: start +[ INFO] [1732683757.503508058]: wait-interpolation debug: end +[ INFO] [1732683759.457554132]: wait-interpolation debug: start +[ INFO] [1732683759.465807857]: wait-interpolation debug: end +[ INFO] [1732683760.478552411]: wait-interpolation debug: start +[ INFO] [1732683760.482356684]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732683765.878704001]: wait-interpolation debug: start +[ INFO] [1732683766.875969173]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732683766.916906133]: wait-interpolation debug: start +[ INFO] [1732683767.924660946]: wait-interpolation debug: end +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +[ INFO] [1732683767.966064091]: wait-interpolation debug: start +[ INFO] [1732683768.965993071]: wait-interpolation debug: end +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +[ INFO] [1732683769.004717357]: wait-interpolation debug: start +[ INFO] [1732683770.008030775]: wait-interpolation debug: end +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +[ INFO] [1732683770.049683806]: wait-interpolation debug: start +[ INFO] [1732683771.048377494]: wait-interpolation debug: end +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +[ INFO] [1732683771.086422600]: wait-interpolation debug: start +[ INFO] [1732683772.093624951]: wait-interpolation debug: end +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +[ INFO] [1732683772.132388270]: wait-interpolation debug: start +[ INFO] [1732683773.133327640]: wait-interpolation debug: end +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +[ INFO] [1732683773.170149626]: wait-interpolation debug: start +[ INFO] [1732683774.184117695]: wait-interpolation debug: end +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +[ INFO] [1732683774.253863977]: wait-interpolation debug: start +[ INFO] [1732683775.266194483]: wait-interpolation debug: end +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +[ INFO] [1732683775.305276442]: wait-interpolation debug: start +[ INFO] [1732683776.318044795]: wait-interpolation debug: end +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +[ INFO] [1732683776.355398211]: wait-interpolation debug: start +[ INFO] [1732683777.366737961]: wait-interpolation debug: end +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +;; # :joint-angle(88.0612) violate max-angle(88.0) +[ INFO] [1732683777.402913051]: wait-interpolation debug: start +[ INFO] [1732683778.404778492]: wait-interpolation debug: end +;; # :joint-angle(88.0612) violate max-angle(88.0) +[ INFO] [1732683780.507734646]: wait-interpolation debug: start +[ INFO] [1732683780.508177753]: wait-interpolation debug: end +[ INFO] [1732683783.316061857]: wait-interpolation debug: start +[ INFO] [1732683783.316673866]: wait-interpolation debug: end +remaining 250 +[ INFO] [1732683783.357033507]: wait-interpolation debug: start +[ INFO] [1732683784.358319699]: wait-interpolation debug: end +[ INFO] [1732683784.433269285]: wait-interpolation debug: start +[ERROR] [1732683785.760073203]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732683785.760133289]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732683785.763325585]: wait-interpolation debug: end +[ INFO] [1732683786.358243257]: wait-interpolation debug: start +[ INFO] [1732683787.364431536]: wait-interpolation debug: end +[ INFO] [1732683789.303578782]: wait-interpolation debug: start +[ INFO] [1732683789.303758626]: wait-interpolation debug: end +[ INFO] [1732683790.328707992]: wait-interpolation debug: start +[ INFO] [1732683790.346696770]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732683795.795205968]: wait-interpolation debug: start +[ INFO] [1732683796.793006693]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732683796.834593532]: wait-interpolation debug: start +[ INFO] [1732683797.834460760]: wait-interpolation debug: end +;; # :joint-angle(88.0579) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +[ INFO] [1732683797.873713489]: wait-interpolation debug: start +[ INFO] [1732683798.877901551]: wait-interpolation debug: end +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +[ INFO] [1732683798.918325072]: wait-interpolation debug: start +[ INFO] [1732683799.923152414]: wait-interpolation debug: end +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +;; # :joint-angle(88.0576) violate max-angle(88.0) +[ INFO] [1732683799.958925172]: wait-interpolation debug: start + C-c C-cinterrupt3.B2-irteusgl$ (send *ri* :speak-jp "初期姿勢に戻ります.注意してください." :wait t) + (send *pr2* :reset-pose) ;;Set Initial Pose + (send *ri* :start-grasp :arms) + (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +t +4.B2-irteusgl$ #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +5.B2-irteusgl$ nil +6.B2-irteusgl$ (9.78407 1.13119) +7.B2-irteusgl$ #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +8.B2-irteusgl$ load "main.l" +[ WARN] [1732685105.070490187]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732685105.070547658]: expected goal id 1732685105069275378_/pr2_eus_interface_1732683385784217302_14981_robotsound_jp_16 +[ WARN] [1732685105.070587999]: received goal id 1732684001423499255_/tweet_client_warning_473265_robotsound_jp_7 +[ WARN] [1732685105.070877159]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732685105.070912539]: expected goal id 1732685105069275378_/pr2_eus_interface_1732683385784217302_14981_robotsound_jp_16 +[ WARN] [1732685105.070943014]: received goal id 1732684002440128701_/tweet_client_warning_473265_robotsound_jp_8 +[ WARN] [1732685105.071205969]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732685105.071241570]: expected goal id 1732685105069275378_/pr2_eus_interface_1732683385784217302_14981_robotsound_jp_16 +[ WARN] [1732685105.071272068]: received goal id 1732684013383369784_/tweet_client_uptime_473244_robotsound_jp_0 +[ WARN] [1732685105.071706692]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732685105.071752740]: expected goal id 1732685105069275378_/pr2_eus_interface_1732683385784217302_14981_robotsound_jp_16 +[ WARN] [1732685105.071784281]: received goal id 1732684014387191203_/tweet_client_uptime_473244_robotsound_jp_1 +[ WARN] [1732685105.072271726]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732685105.072324376]: expected goal id 1732685105069275378_/pr2_eus_interface_1732683385784217302_14981_robotsound_jp_16 +[ WARN] [1732685105.072356399]: received goal id 1732684015343296365_/tweet_client_uptime_473244_robotsound_jp_2 +[ WARN] [1732685105.072694786]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732685105.072727770]: expected goal id 1732685105069275378_/pr2_eus_interface_1732683385784217302_14981_robotsound_jp_16 +[ WARN] [1732685105.072757289]: received goal id 1732685000428954184_/tweet_client_warning_473265_robotsound_jp_9 +[ WARN] [1732685105.073003259]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732685105.073035665]: expected goal id 1732685105069275378_/pr2_eus_interface_1732683385784217302_14981_robotsound_jp_16 +[ WARN] [1732685105.073066448]: received goal id 1732685001433128441_/tweet_client_warning_473265_robotsound_jp_10 +[ WARN] [1732685105.073304504]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732685105.073338358]: expected goal id 1732685105069275378_/pr2_eus_interface_1732683385784217302_14981_robotsound_jp_16 +[ WARN] [1732685105.073373485]: received goal id 1732685002459097233_/tweet_client_warning_473265_robotsound_jp_11 +[ERROR] [1732685108.980192346]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685108.980233982]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685108.991268464]: wait-interpolation debug: start +[ INFO] [1732685109.989633926]: wait-interpolation debug: end +[ INFO] [1732685110.032299753]: wait-interpolation debug: start +[ERROR] [1732685111.628099224]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685111.628164884]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685111.634710864]: wait-interpolation debug: end +[ INFO] [1732685117.653332841]: wait-interpolation debug: start +[ INFO] [1732685117.655181895]: wait-interpolation debug: end +[ INFO] [1732685127.331830477]: wait-interpolation debug: start +[ INFO] [1732685127.332454421]: wait-interpolation debug: end +[ INFO] [1732685133.927916953]: wait-interpolation debug: start +[ INFO] [1732685134.927674922]: wait-interpolation debug: end +[ WARN] [1732685134.972743136]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685134.975589015]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685134.975632417]: original trajectory command : +[ WARN] [1732685134.975659290]: : (#f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (500) +[ WARN] [1732685134.975682395]: current angle vector : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732685134.975695685]: new trajectory command : dvi = 2 +[ WARN] [1732685134.975721146]: : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) 250 +[ WARN] [1732685134.975751555]: : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) 250 +[ WARN] [1732685134.975764196]: new trajectory command : +[ WARN] [1732685134.975795929]: : (#f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (250 250) +[ INFO] [1732685134.978889072]: wait-interpolation debug: start +[ERROR] [1732685136.590519059]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685136.590561511]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685136.594042245]: wait-interpolation debug: end +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.033) violate max-angle(88.0) +;; # :joint-angle(88.0709) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0873) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0846) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.081) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0801) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.0793) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-81.8238 8.82445 -0.607339)/(82.3005/10) +;; dif-rot : #f(-0.003527 -0.024101 0.124964)/(0.127316/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 128.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -2.220446e-16 -2.220446e-16 180.0) (2.220446e-16 1.0 -2.220446e-16 0.0) (2.220446e-16 2.220446e-16 1.0 5.684342e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -2.220446e-16 -2.220446e-16 180.0) (2.220446e-16 1.0 -2.220446e-16 0.0) (2.220446e-16 2.220446e-16 1.0 5.684342e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-38-13-84-49-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-38-13-84-49-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +[ INFO] [1732685138.156582703]: wait-interpolation debug: start +[ INFO] [1732685139.203162610]: wait-interpolation debug: end +;; # :joint-angle(88.079) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-80.0328 8.63085 -0.470722)/(80.4982/10) +;; dif-rot : #f(-0.003416 -0.025036 0.12171)/(0.124305/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 118.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 -2.842171e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 -2.842171e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-39-51-24-43-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-39-51-24-43-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +[ INFO] [1732685139.532126224]: wait-interpolation debug: start +[ INFO] [1732685140.550004643]: wait-interpolation debug: end +;; # :joint-angle(88.079) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-77.9534 8.40314 -0.337409)/(78.4057/10) +;; dif-rot : #f(-0.003289 -0.025773 0.117998)/(0.120825/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 108.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 0.0 180.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 5.684342e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 0.0 180.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 5.684342e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-40-84-74-53-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-40-84-74-53-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +[ INFO] [1732685140.865916686]: wait-interpolation debug: start +[ INFO] [1732685141.923650133]: wait-interpolation debug: end +;; # :joint-angle(88.079) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-75.5799 8.14089 -0.208907)/(76.0173/10) +;; dif-rot : #f(-0.003147 -0.026297 0.113834)/(0.116874/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 98.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 0.0 180.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 1.421085e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 0.0 180.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 1.421085e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-42-21-78-96-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-42-21-78-96-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +[ INFO] [1732685142.233002295]: wait-interpolation debug: start +[ INFO] [1732685143.235648837]: wait-interpolation debug: end +;; # :joint-angle(88.079) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-72.9058 7.84367 -0.086767)/(73.3266/10) +;; dif-rot : #f(-0.002991 -0.026592 0.109219)/(0.112449/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 88.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -1.110223e-16 -5.551115e-17 180.0) (1.110223e-16 1.0 1.110223e-16 -1.136868e-13) (5.551115e-17 -1.110223e-16 1.0 -1.421085e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -1.110223e-16 -5.551115e-17 180.0) (1.110223e-16 1.0 1.110223e-16 -1.136868e-13) (5.551115e-17 -1.110223e-16 1.0 -1.421085e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-43-53-12-73-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-43-53-12-73-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +[ INFO] [1732685143.552124122]: wait-interpolation debug: start +[ INFO] [1732685144.574618326]: wait-interpolation debug: end +;; # :joint-angle(88.079) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-69.9238 7.51103 0.027418)/(70.326/10) +;; dif-rot : #f(-0.002821 -0.026642 0.104156)/(0.107547/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 78.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 -2.842171e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 -2.842171e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-44-87-08-15-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-44-87-08-15-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +[ INFO] [1732685144.888935504]: wait-interpolation debug: start +[ INFO] [1732685145.893353340]: wait-interpolation debug: end +;; # :joint-angle(88.079) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-66.6256 7.14253 0.132008)/(67.0074/10) +;; dif-rot : #f(-0.002638 -0.026434 0.098647)/(0.102162/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 68.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 5.551115e-17 -5.551115e-17 180.0) (-5.551115e-17 1.0 1.540744e-33 0.0) (5.551115e-17 1.540744e-33 1.0 4.263256e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 5.551115e-17 -5.551115e-17 180.0) (-5.551115e-17 1.0 1.540744e-33 0.0) (5.551115e-17 1.540744e-33 1.0 4.263256e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-46-15-32-97-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-46-15-32-97-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +[ INFO] [1732685146.170968909]: wait-interpolation debug: start +[ INFO] [1732685147.172675218]: wait-interpolation debug: end +;; # :joint-angle(88.079) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-62.9906 6.73154 0.224477)/(63.3497/10) +;; dif-rot : #f(-0.002443 -0.025946 0.092675)/(0.09627/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 58.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 2.220446e-16 0.0 180.0) (-2.220446e-16 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 2.220446e-16 0.0 180.0) (-2.220446e-16 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-47-46-67-92-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-47-46-67-92-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +[ INFO] [1732685147.486967090]: wait-interpolation debug: start +[ INFO] [1732685148.493939334]: wait-interpolation debug: end +;; # :joint-angle(88.079) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-58.7581 6.13998 0.282334)/(59.0787/10) +;; dif-rot : #f(-0.002223 -0.02503 0.085822)/(0.089425/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 48.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 -1.136868e-13) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 -1.136868e-13) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-48-77-86-69-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-48-77-86-69-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +[ INFO] [1732685148.799063450]: wait-interpolation debug: start +[ INFO] [1732685149.815774436]: wait-interpolation debug: end +;; # :joint-angle(88.079) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-53.6735 5.24152 0.277104)/(53.9295/10) +;; dif-rot : #f(-0.001967 -0.023533 0.077712)/(0.081221/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 38.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 2.131628e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 2.131628e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-50-08-35-12-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-25-50-08-35-12-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +;; # :joint-angle(88.079) violate max-angle(88.0) +[ INFO] [1732685150.102494198]: wait-interpolation debug: start +[ INFO] [1732685151.104292673]: wait-interpolation debug: end +;; # :joint-angle(88.079) violate max-angle(88.0) +[ INFO] [1732685153.293515488]: wait-interpolation debug: start +[ INFO] [1732685153.293734785]: wait-interpolation debug: end +[ INFO] [1732685156.103643303]: wait-interpolation debug: start +[ INFO] [1732685156.106117643]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732685156.182061326]: wait-interpolation debug: start +[ INFO] [1732685158.181518967]: wait-interpolation debug: end +[ INFO] [1732685158.306113080]: wait-interpolation debug: start +[ERROR] [1732685160.265286248]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685160.265345586]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685160.270766694]: wait-interpolation debug: end +[ INFO] [1732685160.964249363]: wait-interpolation debug: start +[ INFO] [1732685161.971722606]: wait-interpolation debug: end +[ INFO] [1732685163.913172217]: wait-interpolation debug: start +[ INFO] [1732685163.913354073]: wait-interpolation debug: end +[ INFO] [1732685164.941329267]: wait-interpolation debug: start +[ INFO] [1732685164.952246117]: wait-interpolation debug: end +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +[ INFO] [1732685170.320863456]: wait-interpolation debug: start +[ INFO] [1732685171.324578979]: wait-interpolation debug: end +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +[ INFO] [1732685171.372150239]: wait-interpolation debug: start +[ INFO] [1732685172.370993322]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732685172.411859391]: wait-interpolation debug: start +[ INFO] [1732685173.411386083]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732685173.460521103]: wait-interpolation debug: start +[ INFO] [1732685174.460777947]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732685174.511815253]: wait-interpolation debug: start +[ INFO] [1732685175.509692901]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732685175.547633013]: wait-interpolation debug: start +[ INFO] [1732685176.553800960]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732685176.591606700]: wait-interpolation debug: start +[ INFO] [1732685177.593689331]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732685177.631177503]: wait-interpolation debug: start +[ INFO] [1732685178.646998169]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732685178.688928835]: wait-interpolation debug: start +[ INFO] [1732685179.702088937]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732685179.739175482]: wait-interpolation debug: start +[ INFO] [1732685180.753292952]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732685180.803576303]: wait-interpolation debug: start +[ INFO] [1732685181.807769283]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732685181.875723851]: wait-interpolation debug: start +[ INFO] [1732685182.881924904]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732685185.032061899]: wait-interpolation debug: start +[ INFO] [1732685185.032407633]: wait-interpolation debug: end +[ INFO] [1732685187.840868096]: wait-interpolation debug: start +[ INFO] [1732685187.844410264]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732685187.920440326]: wait-interpolation debug: start +[ INFO] [1732685189.925269110]: wait-interpolation debug: end +[ INFO] [1732685189.990906590]: wait-interpolation debug: start +[ERROR] [1732685193.322277594]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685193.322335250]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685193.325916058]: wait-interpolation debug: end +[ INFO] [1732685194.433708660]: wait-interpolation debug: start +[ INFO] [1732685195.444045248]: wait-interpolation debug: end +[ INFO] [1732685197.373342491]: wait-interpolation debug: start +[ INFO] [1732685197.373995780]: wait-interpolation debug: end +[ INFO] [1732685198.435642850]: wait-interpolation debug: start +[ INFO] [1732685198.443008446]: wait-interpolation debug: end + C-c C-cinterrupt9.B3-irteusgl$ load "main.l" +[ WARN] [1732685214.122574917]: [/r_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732685214.122629016]: expected goal id 1732685214098997552_/pr2_eus_interface_1732683385784217302_14981_/r_gripper_controller/gripper_action_34 +[ WARN] [1732685214.122656960]: received goal id 1732685198374893923_/pr2_eus_interface_1732683385784217302_14981_/r_gripper_controller/gripper_action_33 +[ WARN] [1732685216.251061595]: continuous joint (r_forearm_roll_joint) moves -182.994 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685216.254058477]: continuous joint (r_forearm_roll_joint) moves -182.994 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685216.254199127]: original trajectory command : +[ WARN] [1732685216.254259021]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732685216.254312609]: current angle vector : #f(118.83 -0.405289 -15.6375 79.5614 -27.8941 91.6994 -108.654 240.542 0.995373 34.1932 -26.6706 -96.1736 162.994 -66.2648 119.683 0.0 0.0) +[ WARN] [1732685216.254354273]: new trajectory command : dvi = 2 +[ WARN] [1732685216.254433462]: : #f(84.4151 29.7974 29.1812 74.7807 -73.9471 55.8497 -69.3272 210.271 -29.5023 54.0966 -48.3353 -108.087 71.4968 -48.1324 149.842 0.0 0.0) 500 +[ WARN] [1732685216.254516638]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732685216.254541006]: new trajectory command : +[ WARN] [1732685216.254583550]: : (#f(84.4151 29.7974 29.1812 74.7807 -73.9471 55.8497 -69.3272 210.271 -29.5023 54.0966 -48.3353 -108.087 71.4968 -48.1324 149.842 0.0 0.0) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732685216.263700189]: wait-interpolation debug: start +[ERROR] [1732685221.640688327]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685221.640774889]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685221.644399242]: wait-interpolation debug: end +[ INFO] [1732685223.442830594]: wait-interpolation debug: start +[ERROR] [1732685225.038751650]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685225.038831933]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685225.043620109]: wait-interpolation debug: end +[ INFO] [1732685230.867008574]: wait-interpolation debug: start +[ INFO] [1732685230.880430001]: wait-interpolation debug: end +[ INFO] [1732685240.530130043]: wait-interpolation debug: start +[ INFO] [1732685240.530284363]: wait-interpolation debug: end +[ INFO] [1732685247.059482372]: wait-interpolation debug: start +[ INFO] [1732685248.079719502]: wait-interpolation debug: end +[ WARN] [1732685248.123036904]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685248.125443349]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685248.125487286]: original trajectory command : +[ WARN] [1732685248.125512383]: : (#f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (500) +[ WARN] [1732685248.125535419]: current angle vector : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732685248.125548878]: new trajectory command : dvi = 2 +[ WARN] [1732685248.125574096]: : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) 250 +[ WARN] [1732685248.125604533]: : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) 250 +[ WARN] [1732685248.125617564]: new trajectory command : +[ WARN] [1732685248.125646265]: : (#f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (250 250) +[ INFO] [1732685248.128059820]: wait-interpolation debug: start +[ERROR] [1732685249.738568739]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685249.738707670]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685249.753800627]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0908) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0929) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0905) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0849) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0763) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-81.8238 8.82445 -0.607339)/(82.3005/10) +;; dif-rot : #f(-0.003527 -0.024101 0.124964)/(0.127316/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 128.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -2.220446e-16 -2.220446e-16 180.0) (2.220446e-16 1.0 -2.220446e-16 0.0) (2.220446e-16 2.220446e-16 1.0 5.684342e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -2.220446e-16 -2.220446e-16 180.0) (2.220446e-16 1.0 -2.220446e-16 0.0) (2.220446e-16 2.220446e-16 1.0 5.684342e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-30-98-70-41-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-30-98-70-41-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732685251.004933583]: wait-interpolation debug: start +[ INFO] [1732685252.011326850]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-80.0328 8.63085 -0.470722)/(80.4982/10) +;; dif-rot : #f(-0.003416 -0.025036 0.12171)/(0.124305/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 118.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 -2.842171e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 -2.842171e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-32-27-49-90-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-32-27-49-90-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732685252.302488718]: wait-interpolation debug: start +[ INFO] [1732685253.309855024]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-77.9534 8.40314 -0.337409)/(78.4057/10) +;; dif-rot : #f(-0.003289 -0.025773 0.117998)/(0.120825/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 108.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 0.0 180.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 5.684342e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 0.0 180.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 5.684342e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-33-57-50-01-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-33-57-50-01-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732685253.595187503]: wait-interpolation debug: start +[ INFO] [1732685254.601215778]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-75.5799 8.14089 -0.208907)/(76.0173/10) +;; dif-rot : #f(-0.003147 -0.026297 0.113834)/(0.116874/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 98.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 0.0 180.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 1.421085e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 0.0 180.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 1.421085e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-34-86-65-02-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-34-86-65-02-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732685254.883633471]: wait-interpolation debug: start +[ INFO] [1732685255.891342238]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-72.9058 7.84367 -0.086767)/(73.3266/10) +;; dif-rot : #f(-0.002991 -0.026592 0.109219)/(0.112449/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 88.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -1.110223e-16 -5.551115e-17 180.0) (1.110223e-16 1.0 1.110223e-16 -1.136868e-13) (5.551115e-17 -1.110223e-16 1.0 -1.421085e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -1.110223e-16 -5.551115e-17 180.0) (1.110223e-16 1.0 1.110223e-16 -1.136868e-13) (5.551115e-17 -1.110223e-16 1.0 -1.421085e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-36-15-83-40-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-36-15-83-40-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732685256.174936297]: wait-interpolation debug: start +[ INFO] [1732685257.190545085]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-69.9238 7.51103 0.027418)/(70.326/10) +;; dif-rot : #f(-0.002821 -0.026642 0.104156)/(0.107547/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 78.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 -2.842171e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 -2.842171e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-37-44-95-51-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-37-44-95-51-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732685257.465881531]: wait-interpolation debug: start +[ INFO] [1732685258.483657384]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-66.6256 7.14253 0.132008)/(67.0074/10) +;; dif-rot : #f(-0.002638 -0.026434 0.098647)/(0.102162/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 68.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 5.551115e-17 -5.551115e-17 180.0) (-5.551115e-17 1.0 1.540744e-33 0.0) (5.551115e-17 1.540744e-33 1.0 4.263256e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 5.551115e-17 -5.551115e-17 180.0) (-5.551115e-17 1.0 1.540744e-33 0.0) (5.551115e-17 1.540744e-33 1.0 4.263256e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-38-74-25-06-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-38-74-25-06-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732685258.756362450]: wait-interpolation debug: start +[ INFO] [1732685259.768659244]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-62.9906 6.73154 0.224477)/(63.3497/10) +;; dif-rot : #f(-0.002443 -0.025946 0.092675)/(0.09627/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 58.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 2.220446e-16 0.0 180.0) (-2.220446e-16 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 2.220446e-16 0.0 180.0) (-2.220446e-16 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-40-02-93-24-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-40-02-93-24-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732685260.049494429]: wait-interpolation debug: start +[ INFO] [1732685261.053535899]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-58.7581 6.13998 0.282334)/(59.0787/10) +;; dif-rot : #f(-0.002223 -0.02503 0.085822)/(0.089425/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 48.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 -1.136868e-13) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 -1.136868e-13) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-41-31-18-83-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-41-31-18-83-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732685261.359778541]: wait-interpolation debug: start +[ INFO] [1732685262.363470219]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-53.6735 5.24152 0.277104)/(53.9295/10) +;; dif-rot : #f(-0.001967 -0.023533 0.077712)/(0.081221/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 38.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 2.131628e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 2.131628e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-42-65-28-83-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-27-42-65-28-83-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732685262.672836081]: wait-interpolation debug: start +[ INFO] [1732685263.673950738]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732685265.832351494]: wait-interpolation debug: start +[ INFO] [1732685265.832771061]: wait-interpolation debug: end +[ INFO] [1732685268.648972844]: wait-interpolation debug: start +[ INFO] [1732685268.655720078]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732685268.727426693]: wait-interpolation debug: start +[ INFO] [1732685270.732023364]: wait-interpolation debug: end +[ INFO] [1732685270.859798137]: wait-interpolation debug: start +[ERROR] [1732685272.819029795]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685272.819071022]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685272.822320583]: wait-interpolation debug: end +[ INFO] [1732685273.505488344]: wait-interpolation debug: start +[ INFO] [1732685274.502717594]: wait-interpolation debug: end +[ INFO] [1732685276.412018083]: wait-interpolation debug: start +[ INFO] [1732685276.412573255]: wait-interpolation debug: end +[ INFO] [1732685277.425766411]: wait-interpolation debug: start +[ INFO] [1732685277.430072335]: wait-interpolation debug: end +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +[ INFO] [1732685282.801692460]: wait-interpolation debug: start +[ INFO] [1732685283.804152881]: wait-interpolation debug: end +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +[ INFO] [1732685283.860804753]: wait-interpolation debug: start +[ INFO] [1732685284.883574611]: wait-interpolation debug: end +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +[ INFO] [1732685284.922631916]: wait-interpolation debug: start +[ INFO] [1732685285.951655999]: wait-interpolation debug: end +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +[ INFO] [1732685286.000128860]: wait-interpolation debug: start +[ INFO] [1732685287.005222490]: wait-interpolation debug: end +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +[ INFO] [1732685287.051575733]: wait-interpolation debug: start +[ INFO] [1732685288.059182942]: wait-interpolation debug: end +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +[ INFO] [1732685288.101685613]: wait-interpolation debug: start +[ INFO] [1732685289.106780151]: wait-interpolation debug: end +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +[ INFO] [1732685289.153805254]: wait-interpolation debug: start +[ INFO] [1732685290.163843082]: wait-interpolation debug: end +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +[ INFO] [1732685290.203907857]: wait-interpolation debug: start +;; # :joint-angle(88.0799) violate max-angle(88.0) C-c C-cinterrupt10.B4-irteusgl$ ;; # :joint-angle(88.0799) violate max-angle(88.0) +nil +11.B4-irteusgl$ load "main.l" +[ INFO] [1732685304.178767496]: wait-interpolation debug: start +[ERROR] [1732685306.139425946]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685306.139468658]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732685306.734358895]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685306.734424096]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685306.738916312]: wait-interpolation debug: end +[ INFO] [1732685307.024024686]: wait-interpolation debug: start +[ERROR] [1732685308.625176275]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685308.625253668]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685308.632669747]: wait-interpolation debug: end +[ INFO] [1732685314.577520907]: wait-interpolation debug: start +[ INFO] [1732685314.581154046]: wait-interpolation debug: end +[ INFO] [1732685324.257332020]: wait-interpolation debug: start +[ INFO] [1732685324.285420520]: wait-interpolation debug: end +[ INFO] [1732685330.841429108]: wait-interpolation debug: start +[ INFO] [1732685331.841893398]: wait-interpolation debug: end +;; inverse-kinematics failed. +;; dif-pos : #f(-259.302 254.022 610.06)/(709.885/10) +;; dif-rot : #f(6.938894e-18 -0.307196 -0.091946)/(0.320661/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis :x) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 100.0 1870.0) :rot #2f((1.0 0.0 0.0) (0.0 1.0 0.0) (0.0 0.0 1.0)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 6.938894e-18 180.0) (0.0 1.0 0.0 0.0) (-6.938894e-18 0.0 1.0 2.273737e-13) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 6.938894e-18 180.0) (0.0 1.0 0.0 0.0) (-6.938894e-18 0.0 1.0 2.273737e-13) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis :x))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-28-52-09-46-51-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-28-52-09-46-51-failure.l")(ik-setup)(ik-check)) +[ INFO] [1732685332.111466087]: wait-interpolation debug: start +[ INFO] [1732685333.112910459]: wait-interpolation debug: end +[ WARN] [1732685333.161116399]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685333.163398625]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685333.163437801]: original trajectory command : +[ WARN] [1732685333.163461970]: : (#f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (500) +[ WARN] [1732685333.163486080]: current angle vector : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732685333.163499577]: new trajectory command : dvi = 2 +[ WARN] [1732685333.163524789]: : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) 250 +[ WARN] [1732685333.163556759]: : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) 250 +[ WARN] [1732685333.163568198]: new trajectory command : +[ WARN] [1732685333.163595438]: : (#f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (250 250) +[ INFO] [1732685333.166025168]: wait-interpolation debug: start +[ERROR] [1732685334.780155829]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685334.780279267]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685334.796018691]: wait-interpolation debug: end +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0499) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0926) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.087) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0843) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0816) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-81.8238 8.82445 -0.607339)/(82.3005/10) +;; dif-rot : #f(-0.003527 -0.024101 0.124964)/(0.127316/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 128.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -2.220446e-16 -2.220446e-16 180.0) (2.220446e-16 1.0 -2.220446e-16 0.0) (2.220446e-16 2.220446e-16 1.0 5.684342e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -2.220446e-16 -2.220446e-16 180.0) (2.220446e-16 1.0 -2.220446e-16 0.0) (2.220446e-16 2.220446e-16 1.0 5.684342e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-28-56-06-65-42-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-28-56-06-65-42-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +[ INFO] [1732685336.081483345]: wait-interpolation debug: start +[ INFO] [1732685337.101316098]: wait-interpolation debug: end +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-80.0328 8.63085 -0.470722)/(80.4982/10) +;; dif-rot : #f(-0.003416 -0.025036 0.12171)/(0.124305/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 118.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 -2.842171e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 -2.842171e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-28-57-36-15-16-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-28-57-36-15-16-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +[ INFO] [1732685337.375254624]: wait-interpolation debug: start +[ INFO] [1732685338.373194047]: wait-interpolation debug: end +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-77.9534 8.40314 -0.337409)/(78.4057/10) +;; dif-rot : #f(-0.003289 -0.025773 0.117998)/(0.120825/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 108.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 0.0 180.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 5.684342e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 0.0 180.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 5.684342e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-28-58-63-28-36-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-28-58-63-28-36-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +[ INFO] [1732685338.646485235]: wait-interpolation debug: start +[ INFO] [1732685339.651446131]: wait-interpolation debug: end +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-75.5799 8.14089 -0.208907)/(76.0173/10) +;; dif-rot : #f(-0.003147 -0.026297 0.113834)/(0.116874/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 98.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 0.0 180.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 1.421085e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 0.0 180.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 1.421085e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-28-59-91-37-11-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-28-59-91-37-11-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +[ INFO] [1732685339.933499219]: wait-interpolation debug: start +[ INFO] [1732685340.941683307]: wait-interpolation debug: end +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-72.9058 7.84367 -0.086767)/(73.3266/10) +;; dif-rot : #f(-0.002991 -0.026592 0.109219)/(0.112449/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 88.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -1.110223e-16 -5.551115e-17 180.0) (1.110223e-16 1.0 1.110223e-16 -1.136868e-13) (5.551115e-17 -1.110223e-16 1.0 -1.421085e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -1.110223e-16 -5.551115e-17 180.0) (1.110223e-16 1.0 1.110223e-16 -1.136868e-13) (5.551115e-17 -1.110223e-16 1.0 -1.421085e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-29-01-21-41-68-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-29-01-21-41-68-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +[ INFO] [1732685341.230653577]: wait-interpolation debug: start +[ INFO] [1732685342.239166000]: wait-interpolation debug: end +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-69.9238 7.51103 0.027418)/(70.326/10) +;; dif-rot : #f(-0.002821 -0.026642 0.104156)/(0.107547/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 78.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 -2.842171e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 -2.842171e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-29-02-52-05-47-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-29-02-52-05-47-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +[ INFO] [1732685342.542249162]: wait-interpolation debug: start +[ INFO] [1732685343.551198800]: wait-interpolation debug: end +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-66.6256 7.14253 0.132008)/(67.0074/10) +;; dif-rot : #f(-0.002638 -0.026434 0.098647)/(0.102162/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 68.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 5.551115e-17 -5.551115e-17 180.0) (-5.551115e-17 1.0 1.540744e-33 0.0) (5.551115e-17 1.540744e-33 1.0 4.263256e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 5.551115e-17 -5.551115e-17 180.0) (-5.551115e-17 1.0 1.540744e-33 0.0) (5.551115e-17 1.540744e-33 1.0 4.263256e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-29-03-82-85-79-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-29-03-82-85-79-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +[ INFO] [1732685343.843354815]: wait-interpolation debug: start +[ INFO] [1732685344.853484348]: wait-interpolation debug: end +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-62.9906 6.73154 0.224477)/(63.3497/10) +;; dif-rot : #f(-0.002443 -0.025946 0.092675)/(0.09627/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 58.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 2.220446e-16 0.0 180.0) (-2.220446e-16 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 2.220446e-16 0.0 180.0) (-2.220446e-16 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-29-05-12-40-79-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-29-05-12-40-79-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +[ INFO] [1732685345.144665078]: wait-interpolation debug: start +[ INFO] [1732685346.147048069]: wait-interpolation debug: end +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-58.7581 6.13998 0.282334)/(59.0787/10) +;; dif-rot : #f(-0.002223 -0.02503 0.085822)/(0.089425/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 48.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 -1.136868e-13) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 -1.136868e-13) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-29-06-41-03-61-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-29-06-41-03-61-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +[ INFO] [1732685346.429031505]: wait-interpolation debug: start +[ INFO] [1732685347.429077760]: wait-interpolation debug: end +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-53.6735 5.24152 0.277104)/(53.9295/10) +;; dif-rot : #f(-0.001967 -0.023533 0.077712)/(0.081221/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 38.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 2.131628e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 2.131628e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-29-07-69-16-71-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-29-07-69-16-71-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +[ INFO] [1732685347.712508052]: wait-interpolation debug: start +[ INFO] [1732685348.711136004]: wait-interpolation debug: end +;; # :joint-angle(88.0754) violate max-angle(88.0) +[ INFO] [1732685350.882346419]: wait-interpolation debug: start +[ INFO] [1732685350.882889271]: wait-interpolation debug: end +[ INFO] [1732685353.689011051]: wait-interpolation debug: start +[ INFO] [1732685353.690565045]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732685353.729256867]: wait-interpolation debug: start +[ INFO] [1732685355.732642959]: wait-interpolation debug: end +[ INFO] [1732685355.875121470]: wait-interpolation debug: start +[ERROR] [1732685357.834966795]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685357.835015059]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685357.835974078]: wait-interpolation debug: end +[ INFO] [1732685358.505832233]: wait-interpolation debug: start +[ INFO] [1732685359.527747576]: wait-interpolation debug: end +[ INFO] [1732685361.454624129]: wait-interpolation debug: start +[ INFO] [1732685361.460966286]: wait-interpolation debug: end +[ INFO] [1732685362.490400934]: wait-interpolation debug: start +[ INFO] [1732685362.507772861]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732685367.893878070]: wait-interpolation debug: start +[ INFO] [1732685368.898421450]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732685368.978950475]: wait-interpolation debug: start +[ INFO] [1732685370.024526771]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732685370.069676886]: wait-interpolation debug: start +[ INFO] [1732685371.096875827]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732685371.136246350]: wait-interpolation debug: start +[ INFO] [1732685372.141383204]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732685372.211109627]: wait-interpolation debug: start +[ INFO] [1732685373.241920973]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732685373.280073930]: wait-interpolation debug: start +[ INFO] [1732685374.280533533]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732685374.354228513]: wait-interpolation debug: start +[ INFO] [1732685375.359126208]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732685375.394897753]: wait-interpolation debug: start +[ INFO] [1732685376.403705185]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732685376.444132741]: wait-interpolation debug: start +[ INFO] [1732685377.455897203]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732685377.501693875]: wait-interpolation debug: start +[ INFO] [1732685378.505028266]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732685378.541462709]: wait-interpolation debug: start +[ INFO] [1732685379.544501409]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732685379.582964505]: wait-interpolation debug: start +[ INFO] [1732685380.613839591]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732685382.789543524]: wait-interpolation debug: start +[ INFO] [1732685382.807693686]: wait-interpolation debug: end +[ INFO] [1732685385.618901659]: wait-interpolation debug: start +[ INFO] [1732685385.622439716]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732685385.668831473]: wait-interpolation debug: start +[ INFO] [1732685385.622439716]: wait-interpolation debug: end C-c C-cinterrupt12.B5-irteusgl$ +nil +12.B5-irteusgl$ (setq current-coords (send (send *desk* :get :left-coords) :copy-worldcoords)) +(setq new-coords (send current-coords :translate (float-vector 0 100 1000))) +# +13.B5-irteusgl$ # +14.B5-irteusgl$ (setq current-coords (send (send *desk* :get :left-coords) :copy-worldcoords)) +(setq new-coords (send current-coords :translate (float-vector 0 100 1000))) +(send *pr2* :larm :inverse-kinematics new-coords :rotation-axis :x) +(send *pr2* :larm :end-coords :assoc *needle*) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +nil +14.B5-irteusgl$ # +15.B5-irteusgl$ # +16.B5-irteusgl$ nil +16.B5-irteusgl$ ;; inverse-kinematics failed. +;; dif-pos : #f(-73.3973 513.956 369.019)/(636.956/10) +;; dif-rot : #f(1.084202e-19 -0.025332 0.039818)/(0.047193/0.087266) +;; coords : # +;; angles : (75.6193 4.29549 -4.83872 81.8626 -40.4063 93.0595 -98.9548 233.784 -27.3434 49.5094 -24.4487 -94.3993 192.274 -40.6719 96.3754 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis :x) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(75.6193 4.29549 -4.83872 81.8626 -40.4063 93.0595 -98.9548 233.784 -27.3434 49.5094 -24.4487 -94.3993 192.274 -40.6719 96.3754 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 100.0 1870.0) :rot #2f((1.0 0.0 0.0) (0.0 1.0 0.0) (0.0 0.0 1.0)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 3.469447e-18 0.0 180.0) (-3.469447e-18 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 3.469447e-18 0.0 180.0) (-3.469447e-18 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis :x))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-29-58-93-97-10-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-29-58-93-97-10-failure.l")(ik-setup)(ik-check)) +nil +17.B5-irteusgl$ # +18.B5-irteusgl$ #f(75.6193 4.29549 -4.83872 81.8626 -40.4063 93.0595 -98.9548 233.784 -27.3434 49.5094 -24.4487 -94.3993 192.274 -40.6719 96.3754 0.0 0.0) +19.B5-irteusgl$ [ INFO] [1732685399.011740342]: wait-interpolation debug: start +[ INFO] [1732685400.023391816]: wait-interpolation debug: end +(nil nil nil nil) +20.B5-irteusgl$ 1 +21.B5-irteusgl$ new-coords +# +22.B5-irteusgl$ (send *pr2* :larm :inverse-kinematics new-coords :rotation-axis t +) +;; inverse-kinematics failed. +;; dif-pos : #f(-248.024 113.151 625.869)/(682.664/10) +;; dif-rot : #f(-0.037452 -0.263117 -0.131965)/(0.296729/0.087266) +;; coords : # +;; angles : (75.6193 4.29549 -4.83872 81.8626 -40.4063 93.0595 -98.9548 233.784 -27.3434 49.5094 -24.4487 -94.3993 192.274 -40.6719 96.3754 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(75.6193 4.29549 -4.83872 81.8626 -40.4063 93.0595 -98.9548 233.784 -27.3434 49.5094 -24.4487 -94.3993 192.274 -40.6719 96.3754 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 100.0 1870.0) :rot #2f((1.0 0.0 0.0) (0.0 1.0 0.0) (0.0 0.0 1.0)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 1.257675e-17 180.0) (0.0 1.0 0.0 -1.421085e-14) (-1.257675e-17 0.0 1.0 -2.273737e-13) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 1.257675e-17 180.0) (0.0 1.0 0.0 -1.421085e-14) (-1.257675e-17 0.0 1.0 -2.273737e-13) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-30-32-57-87-02-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-30-32-57-87-02-failure.l")(ik-setup)(ik-check)) +nil +23.B5-irteusgl$ load "main.l" +[ WARN] [1732685473.454905198]: continuous joint (r_forearm_roll_joint) moves -212.274 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685473.459199112]: continuous joint (r_forearm_roll_joint) moves -212.274 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685473.459303008]: original trajectory command : +[ WARN] [1732685473.459361484]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732685473.459425111]: current angle vector : #f(75.6193 4.29549 -4.83872 81.8626 -40.4063 93.0595 -98.9548 233.784 -27.3434 49.5094 -24.4487 -94.3993 192.274 -40.6719 96.3754 0.0 0.0) +[ WARN] [1732685473.459475618]: new trajectory command : dvi = 2 +[ WARN] [1732685473.459560681]: : #f(62.8097 32.1477 34.5806 75.9313 -80.2032 56.5297 -64.4774 206.892 -43.6717 61.7547 -47.2244 -107.2 86.1368 -35.336 138.188 0.0 0.0) 500 +[ WARN] [1732685473.459641960]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732685473.459687798]: new trajectory command : +[ WARN] [1732685473.459782656]: : (#f(62.8097 32.1477 34.5806 75.9313 -80.2032 56.5297 -64.4774 206.892 -43.6717 61.7547 -47.2244 -107.2 86.1368 -35.336 138.188 0.0 0.0) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732685473.465951571]: wait-interpolation debug: start +[ERROR] [1732685475.527447250]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685475.527493990]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732685476.118115868]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685476.118188752]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685476.131196556]: wait-interpolation debug: end +[ INFO] [1732685476.292234462]: wait-interpolation debug: start +[ERROR] [1732685477.887864087]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685477.887952858]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685477.892554967]: wait-interpolation debug: end +[ INFO] [1732685492.479232519]: wait-interpolation debug: start +[ INFO] [1732685492.504903175]: wait-interpolation debug: end +[ INFO] [1732685502.191949129]: wait-interpolation debug: start +[ INFO] [1732685502.192279008]: wait-interpolation debug: end +[ INFO] [1732685508.746683972]: wait-interpolation debug: start +[ INFO] [1732685509.754011573]: wait-interpolation debug: end +;; inverse-kinematics failed. +;; dif-pos : #f(-259.302 254.022 610.06)/(709.885/10) +;; dif-rot : #f(6.938894e-18 -0.307196 -0.091946)/(0.320661/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis :x) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 100.0 1870.0) :rot #2f((1.0 0.0 0.0) (0.0 1.0 0.0) (0.0 0.0 1.0)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 6.938894e-18 180.0) (0.0 1.0 0.0 0.0) (-6.938894e-18 0.0 1.0 2.273737e-13) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 6.938894e-18 180.0) (0.0 1.0 0.0 0.0) (-6.938894e-18 0.0 1.0 2.273737e-13) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis :x))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-31-50-00-87-80-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-31-50-00-87-80-failure.l")(ik-setup)(ik-check)) +[ INFO] [1732685510.028947362]: wait-interpolation debug: start +[ INFO] [1732685511.032910237]: wait-interpolation debug: end +[ WARN] [1732685511.077030252]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685511.080832525]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685511.080875723]: original trajectory command : +[ WARN] [1732685511.080910079]: : (#f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (500) +[ WARN] [1732685511.080937141]: current angle vector : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732685511.080950069]: new trajectory command : dvi = 2 +[ WARN] [1732685511.080979125]: : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) 250 +[ WARN] [1732685511.081010245]: : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) 250 +[ WARN] [1732685511.081022290]: new trajectory command : +[ WARN] [1732685511.081050381]: : (#f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (250 250) +[ INFO] [1732685511.083597451]: wait-interpolation debug: start +[ERROR] [1732685512.690523187]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685512.690561890]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685512.692429140]: wait-interpolation debug: end +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.057) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0914) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0902) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0879) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0799) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-81.8238 8.82445 -0.607339)/(82.3005/10) +;; dif-rot : #f(-0.003527 -0.024101 0.124964)/(0.127316/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 128.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -2.220446e-16 -2.220446e-16 180.0) (2.220446e-16 1.0 -2.220446e-16 0.0) (2.220446e-16 2.220446e-16 1.0 5.684342e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -2.220446e-16 -2.220446e-16 180.0) (2.220446e-16 1.0 -2.220446e-16 0.0) (2.220446e-16 2.220446e-16 1.0 5.684342e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-31-53-91-77-25-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-31-53-91-77-25-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732685513.935704607]: wait-interpolation debug: start +[ INFO] [1732685514.935940738]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-80.0328 8.63085 -0.470722)/(80.4982/10) +;; dif-rot : #f(-0.003416 -0.025036 0.12171)/(0.124305/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 118.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 -2.842171e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 -2.842171e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-31-55-19-82-08-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-31-55-19-82-08-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732685515.261774573]: wait-interpolation debug: start +[ INFO] [1732685516.262820651]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-77.9534 8.40314 -0.337409)/(78.4057/10) +;; dif-rot : #f(-0.003289 -0.025773 0.117998)/(0.120825/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 108.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 0.0 180.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 5.684342e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 0.0 180.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 5.684342e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-31-56-55-03-20-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-31-56-55-03-20-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732685516.570467667]: wait-interpolation debug: start +[ INFO] [1732685517.573252054]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-75.5799 8.14089 -0.208907)/(76.0173/10) +;; dif-rot : #f(-0.003147 -0.026297 0.113834)/(0.116874/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 98.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 0.0 180.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 1.421085e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 0.0 0.0 180.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 1.421085e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-31-57-85-81-21-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-31-57-85-81-21-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732685517.878386859]: wait-interpolation debug: start +[ INFO] [1732685518.893090328]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-72.9058 7.84367 -0.086767)/(73.3266/10) +;; dif-rot : #f(-0.002991 -0.026592 0.109219)/(0.112449/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 88.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -1.110223e-16 -5.551115e-17 180.0) (1.110223e-16 1.0 1.110223e-16 -1.136868e-13) (5.551115e-17 -1.110223e-16 1.0 -1.421085e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -1.110223e-16 -5.551115e-17 180.0) (1.110223e-16 1.0 1.110223e-16 -1.136868e-13) (5.551115e-17 -1.110223e-16 1.0 -1.421085e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-31-59-18-27-39-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-31-59-18-27-39-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732685519.205423950]: wait-interpolation debug: start +[ INFO] [1732685520.211860347]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; inverse-kinematics failed. +;; dif-pos : #f(-69.9238 7.51103 0.027418)/(70.326/10) +;; dif-rot : #f(-0.002821 -0.026642 0.104156)/(0.107547/0.087266) +;; coords : # +;; angles : (50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +;; args : ((#) :move-target # :link-list (# # # # # # #) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list ((# 0.005)) :link-list (# # # # # # #) :move-target # :move-arm :larm :use-torso nil :rotation-axis t) +;; command : (let ((r (instance pr2-sensor-robot :init))) (progn (send r :newcoords (make-coords :4x4 #2f((1.0 0.0 0.0 0.0) (0.0 1.0 0.0 0.0) (0.0 0.0 1.0 0.0) (0.0 0.0 0.0 1.0)))) (mapc #'(lambda (j a) (send* j :joint-angle a nil)) (list (send r :torso_lift_joint) (send r :l_shoulder_pan_joint) (send r :l_shoulder_lift_joint) (send r :l_upper_arm_roll_joint) (send r :l_elbow_flex_joint) (send r :l_forearm_roll_joint) (send r :l_wrist_flex_joint) (send r :l_wrist_roll_joint) (send r :r_shoulder_pan_joint) (send r :r_shoulder_lift_joint) (send r :r_upper_arm_roll_joint) (send r :r_elbow_flex_joint) (send r :r_forearm_roll_joint) (send r :r_wrist_flex_joint) (send r :r_wrist_roll_joint) (send r :head_pan_joint) (send r :head_tilt_joint)) '(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (objects (list r))) (send* r :inverse-kinematics (list (list (make-coords :pos #f(700.0 78.0 770.0) :rot #2f((-2.109511e-32 1.0 -3.445093e-16) (-6.123234e-17 -3.445093e-16 -1.0) (-1.0 0.0 6.123234e-17)))) :dump-command nil :debug-view t :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 -2.842171e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :rthre 0.087266 :thre 10 :stop 300 :additional-weight-list (list (list (send r :link "torso_lift_link") 0.005)) :link-list (list (send r :link "l_shoulder_pan_link") (send r :link "l_shoulder_lift_link") (send r :link "l_upper_arm_roll_link") (send r :link "l_elbow_flex_link") (send r :link "l_forearm_roll_link") (send r :link "l_wrist_flex_link") (send r :link "l_wrist_roll_link")) :move-target (let* ((p (send r :link "l_wrist_roll_link")) (mt (make-cascoords :coords (send (send p :copy-worldcoords) :transform (make-coords :4x4 #2f((1.0 -5.551115e-17 0.0 180.0) (5.551115e-17 1.0 0.0 0.0) (0.0 0.0 1.0 -2.842171e-14) (0.0 0.0 0.0 1.0))))))) (send p :assoc mt) mt) :move-arm :larm :use-torso nil :rotation-axis t))) +;; dump debug command to /tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-32-00-49-70-45-failure.l +;; (progn (load "/tmp/irtmodel-ik-14981/pr2-sensor-robot-2024-11-27-14-32-00-49-70-45-failure.l")(ik-setup)(ik-check)) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732685520.516101502]: wait-interpolation debug: start + C-c C-cinterrupt24.B6-irteusgl$ load "main.l" +[ WARN] [1732685597.194330428]: continuous joint (r_forearm_roll_joint) moves -187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685597.201203277]: continuous joint (r_forearm_roll_joint) moves -187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685597.201283139]: original trajectory command : +[ WARN] [1732685597.201317634]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732685597.201353296]: current angle vector : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +[ WARN] [1732685597.201375448]: new trajectory command : dvi = 2 +[ WARN] [1732685597.201422081]: : #f(50.0 39.114 44.7435 58.7586 -99.3739 13.2537 -32.6131 176.643 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) 500 +[ WARN] [1732685597.201464138]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732685597.201511730]: new trajectory command : +[ WARN] [1732685597.201580576]: : (#f(50.0 39.114 44.7435 58.7586 -99.3739 13.2537 -32.6131 176.643 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732685597.210905269]: wait-interpolation debug: start +[ERROR] [1732685598.905486081]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685598.905561766]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732685598.906634224]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685598.906686734]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685598.913313279]: wait-interpolation debug: end +[ INFO] [1732685599.793551031]: wait-interpolation debug: start +[ERROR] [1732685601.387401490]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685601.387469711]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685601.392560313]: wait-interpolation debug: end +[ INFO] [1732685607.277448091]: wait-interpolation debug: start +[ INFO] [1732685607.286955223]: wait-interpolation debug: end +[ INFO] [1732685616.973524751]: wait-interpolation debug: start +[ INFO] [1732685616.973886659]: wait-interpolation debug: end +[ INFO] [1732685623.509540711]: wait-interpolation debug: start +[ INFO] [1732685624.542077825]: wait-interpolation debug: end +[ WARN] [1732685624.581474118]: continuous joint (l_forearm_roll_joint) moves 183.515 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685624.583758169]: continuous joint (l_forearm_roll_joint) moves 183.515 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685624.583828145]: original trajectory command : +[ WARN] [1732685624.583853310]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732685624.583876338]: current angle vector : #f(50.0 18.2281 15.487 47.5172 -78.7478 6.50744 -35.2263 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732685624.583887838]: new trajectory command : dvi = 2 +[ WARN] [1732685624.583914796]: : #f(50.0 1.586 23.3163 18.0552 -87.5893 98.265 -49.402 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732685624.583936677]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732685624.583949153]: new trajectory command : +[ WARN] [1732685624.583980841]: : (#f(50.0 1.586 23.3163 18.0552 -87.5893 98.265 -49.402 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732685624.587107753]: wait-interpolation debug: start +[ INFO] [1732685625.771871750]: wait-interpolation debug: end +[ WARN] [1732685625.817381769]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685625.821033463]: continuous joint (r_forearm_roll_joint) moves 187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732685625.821093168]: original trajectory command : +[ WARN] [1732685625.821131536]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (500) +[ WARN] [1732685625.821164647]: current angle vector : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732685625.821186266]: new trajectory command : dvi = 2 +[ WARN] [1732685625.821228789]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) 250 +[ WARN] [1732685625.821268287]: : #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) 250 +[ WARN] [1732685625.821291449]: new trajectory command : +[ WARN] [1732685625.821353314]: : (#f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) #f(50.0 -15.0561 31.1456 -11.4068 -96.4309 190.023 -63.5777 173.286 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0)) (250 250) +[ INFO] [1732685625.827748986]: wait-interpolation debug: start +[ERROR] [1732685627.433583856]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732685627.433629080]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732685627.434613881]: wait-interpolation debug: end +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +[ INFO] [1732685627.913605046]: wait-interpolation debug: start +[ INFO] [1732685629.152090499]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732685629.251741024]: wait-interpolation debug: start +[ INFO] [1732685630.256603108]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732685630.295578430]: wait-interpolation debug: start +[ INFO] [1732685631.300660280]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732685631.339449630]: wait-interpolation debug: start +[ INFO] [1732685632.342594344]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732685632.381334795]: wait-interpolation debug: start +[ INFO] [1732685633.385263485]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732685633.423631966]: wait-interpolation debug: start +[ INFO] [1732685634.422087409]: wait-interpolation debug: end +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +;; # :joint-angle(88.0668) violate max-angle(88.0) +[ INFO] [1732685634.458106506]: wait-interpolation debug: start +[ INFO] [1732685633.423631966]: wait-interpolation debug: start C-c C-cinterrupt25.B7-irteusgl$ +nil +25.B7-irteusgl$ load "main.l" +[ WARN] [1732687691.373319126]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732687691.373360898]: expected goal id 1732687691372294499_/pr2_eus_interface_1732683385784217302_14981_robotsound_jp_40 +[ WARN] [1732687691.373403351]: received goal id 1732686001435843751_/tweet_client_warning_473265_robotsound_jp_13 +[ WARN] [1732687691.373706739]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732687691.373739425]: expected goal id 1732687691372294499_/pr2_eus_interface_1732683385784217302_14981_robotsound_jp_40 +[ WARN] [1732687691.373774807]: received goal id 1732686002467392909_/tweet_client_warning_473265_robotsound_jp_14 +[ WARN] [1732687691.374161625]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732687691.374198737]: expected goal id 1732687691372294499_/pr2_eus_interface_1732683385784217302_14981_robotsound_jp_40 +[ WARN] [1732687691.374233565]: received goal id 1732687000447928185_/tweet_client_warning_473265_robotsound_jp_15 +[ WARN] [1732687691.374595442]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732687691.374631652]: expected goal id 1732687691372294499_/pr2_eus_interface_1732683385784217302_14981_robotsound_jp_40 +[ WARN] [1732687691.374666937]: received goal id 1732687001452152078_/tweet_client_warning_473265_robotsound_jp_16 +[ WARN] [1732687691.375040371]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732687691.375074659]: expected goal id 1732687691372294499_/pr2_eus_interface_1732683385784217302_14981_robotsound_jp_40 +[ WARN] [1732687691.375099255]: received goal id 1732687002448194325_/tweet_client_warning_473265_robotsound_jp_17 +[ WARN] [1732687691.375466492]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732687691.375503055]: expected goal id 1732687691372294499_/pr2_eus_interface_1732683385784217302_14981_robotsound_jp_40 +[ WARN] [1732687691.375538345]: received goal id 1732687613057398799_/tweet_client_uptime_473244_robotsound_jp_3 +[ WARN] [1732687691.375913678]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732687691.375947918]: expected goal id 1732687691372294499_/pr2_eus_interface_1732683385784217302_14981_robotsound_jp_40 +[ WARN] [1732687691.375976933]: received goal id 1732687614061248797_/tweet_client_uptime_473244_robotsound_jp_4 +[ WARN] [1732687691.376341030]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732687691.376375260]: expected goal id 1732687691372294499_/pr2_eus_interface_1732683385784217302_14981_robotsound_jp_40 +[ WARN] [1732687691.376403855]: received goal id 1732687615009757155_/tweet_client_uptime_473244_robotsound_jp_5 +[ WARN] [1732687697.414054830]: continuous joint (r_forearm_roll_joint) moves -187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732687697.417520050]: continuous joint (r_forearm_roll_joint) moves -187.371 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732687697.417600546]: original trajectory command : +[ WARN] [1732687697.417640334]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732687697.417679765]: current angle vector : #f(50.0 6.55551 -3.51767 71.0383 -42.4343 101.845 -105.315 235.132 32.2597 45.0163 31.1091 -94.7041 167.371 -42.5909 77.6941 0.0 0.0) +[ WARN] [1732687697.417701297]: new trajectory command : dvi = 2 +[ WARN] [1732687697.417750704]: : #f(50.0 33.2778 35.2412 70.5191 -81.2171 60.9223 -67.6573 207.566 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) 500 +[ WARN] [1732687697.417805575]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732687697.417828475]: new trajectory command : +[ WARN] [1732687697.417876446]: : (#f(50.0 33.2778 35.2412 70.5191 -81.2171 60.9223 -67.6573 207.566 -13.8701 59.5081 -19.4454 -107.352 73.6856 -36.2955 128.847 0.0 0.0) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732687697.426108249]: wait-interpolation debug: start +[ERROR] [1732687699.120117593]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732687699.120210562]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732687699.121307048]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732687699.121346617]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732687699.125843254]: wait-interpolation debug: end +[ INFO] [1732687699.932691668]: wait-interpolation debug: start +[ERROR] [1732687701.528847340]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732687701.528918602]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732687701.529768080]: wait-interpolation debug: end + C-c C-cinterrupt26.B8-irteusgl$ load "main.l" +[ INFO] [1732687725.159078218]: wait-interpolation debug: start +[ERROR] [1732687726.777549014]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732687726.777674588]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732687726.796323450]: wait-interpolation debug: end +[ INFO] [1732687727.053757125]: wait-interpolation debug: start +[ERROR] [1732687728.651008975]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732687728.651098103]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732687728.656338523]: wait-interpolation debug: end +[ INFO] [1732687734.517436661]: wait-interpolation debug: start +[ INFO] [1732687734.521863565]: wait-interpolation debug: end +[ INFO] [1732687745.056254669]: wait-interpolation debug: start +[ INFO] [1732687745.056650453]: wait-interpolation debug: end +[ INFO] [1732687751.619446590]: wait-interpolation debug: start +[ INFO] [1732687752.623460570]: wait-interpolation debug: end +[ WARN] [1732687752.656163010]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732687752.661010016]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732687752.661193525]: original trajectory command : +[ WARN] [1732687752.661251105]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732687752.661295891]: current angle vector : #f(50.0 17.8275 14.7726 46.824 -78.4543 6.11414 -34.739 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732687752.661319703]: new trajectory command : dvi = 2 +[ WARN] [1732687752.661372383]: : #f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732687752.661420773]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732687752.661443533]: new trajectory command : +[ WARN] [1732687752.661503701]: : (#f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732687752.667872431]: wait-interpolation debug: start +[ INFO] [1732687753.852851567]: wait-interpolation debug: end +[ WARN] [1732687753.896392855]: continuous joint (r_forearm_roll_joint) moves 187.158 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732687753.900775270]: continuous joint (r_forearm_roll_joint) moves 187.158 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732687753.900868234]: original trajectory command : +[ WARN] [1732687753.900921541]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2632 43.8923 31.1313 -94.9978 167.158 -43.7994 77.1917 0.0 0.0)) (500) +[ WARN] [1732687753.900969540]: current angle vector : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) +[ WARN] [1732687753.900997323]: new trajectory command : dvi = 2 +[ WARN] [1732687753.901051338]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8684 58.9462 -19.4343 -107.499 73.5791 -36.8997 128.596 0.0 0.0) 250 +[ WARN] [1732687753.901113897]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2632 43.8923 31.1313 -94.9978 167.158 -43.7994 77.1917 0.0 0.0) 250 +[ WARN] [1732687753.901146920]: new trajectory command : +[ WARN] [1732687753.901209317]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8684 58.9462 -19.4343 -107.499 73.5791 -36.8997 128.596 0.0 0.0) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2632 43.8923 31.1313 -94.9978 167.158 -43.7994 77.1917 0.0 0.0)) (250 250) +[ INFO] [1732687753.911051887]: wait-interpolation debug: start +[ERROR] [1732687755.519615080]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732687755.519674396]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732687755.526223224]: wait-interpolation debug: end +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.0534) violate max-angle(88.0) +;; # :joint-angle(88.084) violate max-angle(88.0) +;; # :joint-angle(88.0953) violate max-angle(88.0) +;; # :joint-angle(88.0953) violate max-angle(88.0) +;; # :joint-angle(88.0953) violate max-angle(88.0) +;; # :joint-angle(88.0953) violate max-angle(88.0) +;; # :joint-angle(88.0953) violate max-angle(88.0) +;; # :joint-angle(88.0953) violate max-angle(88.0) +[ INFO] [1732687756.008103684]: wait-interpolation debug: start +[ INFO] [1732687757.235911015]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732687757.274779383]: wait-interpolation debug: start +[ INFO] [1732687758.301039880]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732687758.346319168]: wait-interpolation debug: start +[ INFO] [1732687759.359677282]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732687759.432823083]: wait-interpolation debug: start +[ INFO] [1732687760.485258946]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732687760.529738844]: wait-interpolation debug: start +[ INFO] [1732687761.580454749]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732687761.640619231]: wait-interpolation debug: start +[ INFO] [1732687762.647784558]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732687762.693142315]: wait-interpolation debug: start +[ INFO] [1732687763.719504805]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732687763.760449448]: wait-interpolation debug: start +[ INFO] [1732687764.776883017]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732687764.816045003]: wait-interpolation debug: start +[ INFO] [1732687765.822467531]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732687765.888196813]: wait-interpolation debug: start +[ INFO] [1732687766.902289963]: wait-interpolation debug: end +;; # :joint-angle(88.0736) violate max-angle(88.0) +[ INFO] [1732687769.135880932]: wait-interpolation debug: start +[ INFO] [1732687769.139558006]: wait-interpolation debug: end +[ INFO] [1732687772.216275220]: wait-interpolation debug: start +[ INFO] [1732687772.233842333]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732687772.274511605]: wait-interpolation debug: start +[ INFO] [1732687773.497715263]: wait-interpolation debug: end +[ INFO] [1732687773.586989912]: wait-interpolation debug: start +[ERROR] [1732687778.148450923]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732687778.148513299]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732687778.153994447]: wait-interpolation debug: end +[ INFO] [1732687779.597853940]: wait-interpolation debug: start +[ INFO] [1732687780.595652875]: wait-interpolation debug: end +[ INFO] [1732687782.533108555]: wait-interpolation debug: start +[ INFO] [1732687782.536464534]: wait-interpolation debug: end +[ INFO] [1732687783.602515654]: wait-interpolation debug: start +[ INFO] [1732687783.609749610]: wait-interpolation debug: end +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +[ INFO] [1732687789.046179675]: wait-interpolation debug: start +[ INFO] [1732687790.063692466]: wait-interpolation debug: end +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +[ INFO] [1732687790.107555083]: wait-interpolation debug: start +[ INFO] [1732687791.142213659]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687791.180161472]: wait-interpolation debug: start +[ INFO] [1732687792.208244452]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687792.253392931]: wait-interpolation debug: start +[ INFO] [1732687793.284642800]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687793.320672938]: wait-interpolation debug: start +[ INFO] [1732687794.352097838]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687794.396929796]: wait-interpolation debug: start +[ INFO] [1732687795.399831021]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687795.434606568]: wait-interpolation debug: start +[ INFO] [1732687796.489144046]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687796.556640344]: wait-interpolation debug: start +[ INFO] [1732687797.626799082]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687797.671859364]: wait-interpolation debug: start +[ INFO] [1732687798.700599064]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687798.743755129]: wait-interpolation debug: start +[ INFO] [1732687799.781347600]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687799.847311769]: wait-interpolation debug: start +[ INFO] [1732687800.864556595]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687800.903747747]: wait-interpolation debug: start +[ INFO] [1732687801.941546517]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687804.123951783]: wait-interpolation debug: start +[ INFO] [1732687804.127436044]: wait-interpolation debug: end +[ INFO] [1732687806.984855743]: wait-interpolation debug: start +[ INFO] [1732687806.994804009]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732687807.039006200]: wait-interpolation debug: start +[ INFO] [1732687808.093117725]: wait-interpolation debug: end +[ INFO] [1732687808.153156557]: wait-interpolation debug: start +[ERROR] [1732687810.769401709]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732687810.769472509]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732687810.773578021]: wait-interpolation debug: end +[ INFO] [1732687811.684174758]: wait-interpolation debug: start +[ INFO] [1732687812.684624098]: wait-interpolation debug: end +[ INFO] [1732687814.628104971]: wait-interpolation debug: start +[ INFO] [1732687814.631418165]: wait-interpolation debug: end +[ INFO] [1732687815.664957086]: wait-interpolation debug: start +[ INFO] [1732687815.675175834]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732687821.080196281]: wait-interpolation debug: start +[ INFO] [1732687822.109808685]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732687822.151585477]: wait-interpolation debug: start +[ INFO] [1732687823.194599140]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687823.232188072]: wait-interpolation debug: start +[ INFO] [1732687824.276411588]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687824.314510456]: wait-interpolation debug: start +[ INFO] [1732687825.318664004]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687825.355209294]: wait-interpolation debug: start +[ INFO] [1732687826.424013269]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687826.469336898]: wait-interpolation debug: start +[ INFO] [1732687827.475250574]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687827.515621909]: wait-interpolation debug: start +[ INFO] [1732687828.527380238]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687828.600408169]: wait-interpolation debug: start +[ INFO] [1732687829.603251546]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687829.675461908]: wait-interpolation debug: start +[ INFO] [1732687830.695967686]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687830.737066219]: wait-interpolation debug: start +[ INFO] [1732687831.736491102]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687831.773312950]: wait-interpolation debug: start +[ INFO] [1732687832.783161605]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732687832.822252148]: wait-interpolation debug: start +[ INFO] [1732687833.823733806]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) + C-c C-cinterrupt27.B9-irteusgl$ (send *ri* :stop-grasp) +[ WARN] [1732687847.741212466]: [/r_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732687847.741274273]: expected goal id 1732687847727878893_/pr2_eus_interface_1732683385784217302_14981_/r_gripper_controller/gripper_action_59 +[ WARN] [1732687847.741309576]: received goal id 1732687833826108526_/pr2_eus_interface_1732683385784217302_14981_/r_gripper_controller/gripper_action_58 +(t t) +28.B9-irteusgl$ (reset-pose) +Call Stack (max depth: 20): + 0: at sigint-handler + 1: at sigint-handler + 2: at (setelt stamp-list joint-idx (send msg :header :stamp)) + 3: at (setf (elt stamp-list joint-idx) (send msg :header :stamp)) + 4: at (progn (setf (elt stamp-list joint-idx) (send msg :header :stamp))) + 5: at (if (eq key :position) (progn (setf (elt stamp-list joint-idx) (send msg :header :stamp)))) + 6: at (when (eq key :position) (setf (elt stamp-list joint-idx) (send msg :header :stamp))) + 7: at (while #:dolist13911755 (setq jn (pop #:dolist13911755)) (setq joint-idx (position jn robot-state-names :test #'string=)) (setf (elt data-vec joint-idx) (elt joint-data idx)) (incf idx) (when (eq key :position) (setf (elt stamp-list joint-idx) (send msg :header :stamp)))) + 8: at (let ((jn nil) (#:dolist13911755 joint-names)) nil (while #:dolist13911755 (setq jn (pop #:dolist13911755)) (setq joint-idx (position jn robot-state-names :test #'string=)) (setf (elt data-vec joint-idx) (elt joint-data idx)) (incf idx) (when (eq key :position) (setf (elt stamp-list joint-idx) (send msg :header :stamp)))) nil) + 9: at (dolist (jn joint-names) (setq joint-idx (position jn robot-state-names :test #'string=)) (setf (elt data-vec joint-idx) (elt joint-data idx)) (incf idx) (when (eq key :position) (setf (elt stamp-list joint-idx) (send msg :header :stamp)))) + 10: at (progn (setq data-vec (cdr (assoc key robot-state))) (dolist (jn joint-names) (setq joint-idx (position jn robot-state-names :test #'string=)) (setf (elt data-vec joint-idx) (elt joint-data idx)) (incf idx) (when (eq key :position) (setf (elt stamp-list joint-idx) (send msg :header :stamp))))) + 11: at (if (= (length joint-names) (length joint-data)) (progn (setq data-vec (cdr (assoc key robot-state))) (dolist (jn joint-names) (setq joint-idx (position jn robot-state-names :test #'string=)) (setf (elt data-vec joint-idx) (elt joint-data idx)) (incf idx) (when (eq key :position) (setf (elt stamp-list joint-idx) (send msg :header :stamp)))))) + 12: at (when (= (length joint-names) (length joint-data)) (setq data-vec (cdr (assoc key robot-state))) (dolist (jn joint-names) (setq joint-idx (position jn robot-state-names :test #'string=)) (setf (elt data-vec joint-idx) (elt joint-data idx)) (incf idx) (when (eq key :position) (setf (elt stamp-list joint-idx) (send msg :header :stamp))))) + 13: at (while #:dolist13911753 (setq key (pop #:dolist13911753)) (setq joint-data (send msg key) idx 0) (when (= (length joint-names) (length joint-data)) (setq data-vec (cdr (assoc key robot-state))) (dolist (jn joint-names) (setq joint-idx (position jn robot-state-names :test #'string=)) (setf (elt data-vec joint-idx) (elt joint-data idx)) (incf idx) (when (eq key :position) (setf (elt stamp-list joint-idx) (send msg :header :stamp)))))) + 14: at (let ((key nil) (#:dolist13911753 '(:position :velocity :effort))) nil (while #:dolist13911753 (setq key (pop #:dolist13911753)) (setq joint-data (send msg key) idx 0) (when (= (length joint-names) (length joint-data)) (setq data-vec (cdr (assoc key robot-state))) (dolist (jn joint-names) (setq joint-idx (position jn robot-state-names :test #'string=)) (setf (elt data-vec joint-idx) (elt joint-data idx)) (incf idx) (when (eq key :position) (setf (elt stamp-list joint-idx) (send msg :header :stamp)))))) nil) + 15: at (dolist (key '(:position :velocity :effort)) (setq joint-data (send msg key) idx 0) (when (= (length joint-names) (length joint-data)) (setq data-vec (cdr (assoc key robot-state))) (dolist (jn joint-names) (setq joint-idx (position jn robot-state-names :test #'string=)) (setf (elt data-vec joint-idx) (elt joint-data idx)) (incf idx) (when (eq key :position) (setf (elt stamp-list joint-idx) (send msg :header :stamp)))))) + 16: at (let ((joint-names (send msg :name)) (stamp-list (cdr (assoc :stamp-list robot-state))) (idx 0) joint-idx joint-data data-vec) (dolist (key '(:position :velocity :effort)) (setq joint-data (send msg key) idx 0) (when (= (length joint-names) (length joint-data)) (setq data-vec (cdr (assoc key robot-state))) (dolist (jn joint-names) (setq joint-idx (position jn robot-state-names :test #'string=)) (setf (elt data-vec joint-idx) (elt joint-data idx)) (incf idx) (when (eq key :position) (setf (elt stamp-list joint-idx) (send msg :header :stamp))))))) + 17: at (let ((robot-state-names (cdr (assoc :name robot-state)))) (cond (robot-state-names (let ((diff (set-difference (send msg :name) robot-state-names :test #'string=))) (when diff (setq robot-state-names (append robot-state-names diff)) (dolist (key '(:position :velocity :effort)) (setf (cdr (assoc key robot-state)) (concatenate float-vector (cdr (assoc key robot-state)) (instantiate float-vector (- (length robot-state-names) (length (cdr (assoc key robot-state)))))))) (setf (cdr (assoc :stamp-list robot-state)) (concatenate cons (cdr (assoc :stamp-list robot-state)) (make-list (- (length robot-state-names) (length (cdr (assoc :stamp-list robot-state)))))))))) (t (push (cons :name (send msg :name)) robot-state) (setq robot-state-names (send msg :name)) (dolist (key '(:position :velocity :effort)) (push (cons key (instantiate float-vector (length robot-state-names))) robot-state)) (push (cons :stamp-list (make-list (length robot-state-names))) robot-state))) (let ((joint-names (send msg :name)) (stamp-list (cdr (assoc :stamp-list robot-state))) (idx 0) joint-idx joint-data data-vec) (dolist (key '(:position :velocity :effort)) (setq joint-data (send msg key) idx 0) (when (= (length joint-names) (length joint-data)) (setq data-vec (cdr (assoc key robot-state))) (dolist (jn joint-names) (setq joint-idx (position jn robot-state-names :test #'string=)) (setf (elt data-vec joint-idx) (elt joint-data idx)) (incf idx) (when (eq key :position) (setf (elt stamp-list joint-idx) (send msg :header :stamp))))))) (setf (cdr (assoc :name robot-state)) robot-state-names) (send self :set-robot-state1 :stamp (send msg :header :stamp))) + 18: at (ros::spin-once ros::groupname) + 19: at (ros::spin-once ros::groupname) + And more... +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: undefined function reset-pose in sigint-handler +29.E10-irteusgl$ (exit) +[ INFO] [1732689271.415925068]: cell* ROSEUS_EXIT(context*, int, cell**) +[ INFO] [1732689271.416089281]: exiting roseus 0 +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ ls +main.l removable +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ (exit) +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rossetmaster +set ROS_MASTER_URI to http://localhost:11311 +mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rosesu +rosesu: command not found +mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ roseus +configuring by "/opt/ros/noetic/share/euslisp/jskeus/eus//lib/eusrt.l" +;; readmacro ;; object ;; packsym ;; common ;; constants ;; stream ;; string ;; loader ;; pprint ;; process ;; hashtab ;; array ;; mathtran ;; eusdebug ;; eusforeign ;; extnum ;; coordinates ;; tty ;; history ;; toplevel ;; trans ;; comp ;; builtins ;; par ;; intersection ;; geoclasses ;; geopack ;; geobody ;; primt ;; compose ;; polygon ;; viewing ;; viewport ;; viewsurface ;; hid ;; shadow ;; bodyrel ;; dda ;; helpsub ;; eushelp ;; xforeign ;; Xdecl ;; Xgraphics ;; Xcolor ;; Xeus ;; Xevent ;; Xpanel ;; Xitem ;; Xtext ;; Xmenu ;; Xscroll ;; Xcanvas ;; Xtop ;; Xapplwin +connected to Xserver DISPLAY=:0 +X events are being asynchronously monitored. +;; pixword ;; RGBHLS ;; convolve ;; piximage ;; pbmfile ;; image_correlation ;; oglforeign ;; gldecl ;; glconst ;; glforeign ;; gluconst ;; gluforeign ;; glxconst ;; glxforeign ;; eglforeign ;; eglfunc ;; glutil ;; gltexture ;; glprim ;; gleus ;; glview ;; toiv-undefined ;; fstringdouble irtmath irtutil irtc irtgeoc irtgraph gnuplotlib ___time ___pgsql irtgeo euspqp pqp irtscene irtmodel irtdyna irtrobot irtsensor irtbvh irtcollada irtstl irtwrl irtpointcloud eusbullet bullet irtcollision irtx eusjpeg euspng png irtimage irtglrgb +;; extending gcstack 0x55c10f1fd680[16374] --> 0x55c10f68dc90[32748] top=3d4b +irtgl irtglc irtviewer +EusLisp 9.29( 1.2.5) for Linux64 created on ip-10-0-1-5(Tue Jun 20 10:34:21 PST 2023) +roseus ;; loading roseus("1.7.5") on euslisp((9.29 ip-10-0-1-5 Tue Jun 20 10:34:21 PST 2023 1.2.5)) +eustf roseus_c_util 1.irteusgl$ load "main.l" +;; roseus_resume is disabled. + +;; extending gcstack 0x55c10f68dc90[32738] --> 0x55c1111ab6e0[65476] top=7ed2 +[ERROR] [1732702414.823765009]: [registerPublisher] Failed to contact master at [localhost:11311]. Retrying... +[ERROR] [1732702414.823765009]: [registerPublisher] Failed to contact master at [localhost:11311]. Retrying... + + +[ INFO] [1732702433.829253402]: Connected to master at [localhost:11311] +[ WARN] [1732702438.322862954]: [l_arm_controller/follow_joint_trajectory] action server is not found +[ WARN] [1732702438.326225802]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732702438.326363994]: # is not respond, pr2-interface is disabled +[ WARN] [1732702438.326433312]: Starting 'Kinematics Simulator' +[ WARN] [1732702438.326501512]: (If you do not intend to start Kinematics Simulator, make sure that you can run 'rostopic info /l_arm_controller/follow_joint_trajectory/goal' and 'rostopic info /l_arm_controller/follow_joint_trajectory/cancel' and check whether Subscribers exists. If there is no Subscribers, please check joint_trajectory_action node.) +[ WARN] [1732702438.326564424]: (Please also check 'rostopic info /l_arm_controller/follow_joint_trajectory/feedback' and 'rostopic info /l_arm_controller/follow_joint_trajectory/result' and check whether Publishers exists. If there is no Publishers, please check joint_trajectory_action node.) +[ WARN] [1732702438.326644191]: (If joint_trajectory_action node already exists, you might have a network problem. Please make sure that you can run 'rosnode ping JOINT_TRAJECTORY_ACTION_SERVER_NODE_NAME' and 'rosnode ping /pr2_eus_interface_1732702414817440445') +current *timer-job* is ((lambda nil (send # :robot-interface-simulation-callback)) lisp::count-up-timer) +[ WARN] [1732702441.616531347]: [/base_controller/follow_joint_trajectory] action server is not found +[ WARN] [1732702441.616765819]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732702441.616875116]: move-base-trajectory-action is not found +[ WARN] [1732702441.666682325]: # is not respond, pr2-interface is disabled +;; (make-irtviewer) executed +[ WARN] [1732702442.882723153]: [robotsound_jp] action server is not found +[ WARN] [1732702442.882813954]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732702442.882843284]: action server /robotsound_jp not found. +[ WARN] [1732702444.581892209]: topic /robotsound_jp/goal already advertised +[ WARN] [1732702444.581956396]: topic /robotsound_jp/cancel already advertised +[ WARN] [1732702445.689110643]: [robotsound_jp] action server is not found +[ WARN] [1732702445.689302474]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732702445.689463099]: action server /robotsound_jp not found. +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +[ WARN] [1732702448.713415025]: topic /robotsound_jp/goal already advertised +[ WARN] [1732702448.713493165]: topic /robotsound_jp/cancel already advertised +[ WARN] [1732702449.821404361]: [robotsound_jp] action server is not found +[ WARN] [1732702449.821668856]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732702449.821788271]: action server /robotsound_jp not found. +[ WARN] [1732702449.851940736]: topic /robotsound_jp/goal already advertised +[ WARN] [1732702449.852029209]: topic /robotsound_jp/cancel already advertised +[ WARN] [1732702450.964396875]: [robotsound_jp] action server is not found +[ WARN] [1732702450.964468160]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732702450.964486371]: action server /robotsound_jp not found. +Call Stack (max depth: 20): + 0: at #'cb-recog + 1: at (ros::subscribe "/recognize_wound/cluster_decomposer/boxes" jsk_recognition_msgs::boundingboxarray #'cb-recog) + 2: at (apply #'ros::load-org-for-ros ros::fullname args) + 3: at (apply #'ros::load-org-for-ros ros::fullname args) + 4: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 5: at (load "main.l") + 6: at # +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: undefined function cb-recog in #'cb-recog +2.E1-irteusgl$ Call Stack (max depth: 20): + 0: at (aref error) + 1: at euserror + 2: at euserror + 3: at #'cb-recog + 4: at (ros::subscribe "/recognize_wound/cluster_decomposer/boxes" jsk_recognition_msgs::boundingboxarray #'cb-recog) + 5: at (apply #'ros::load-org-for-ros ros::fullname args) + 6: at (apply #'ros::load-org-for-ros ros::fullname args) + 7: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 8: at (load "main.l") + 9: at # +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: unbound variable error in (aref error) +3.E2-irteusgl$ nil +3.E2-irteusgl$ nil +3.E2-irteusgl$ (send (send *center* :copy-worldcoords) :draw-on :flush t :size 100) +1 +4.E2-irteusgl$ (exit) +nil +4.E2-irteusgl$ [ INFO] [1732703349.099123255]: cell* ROSEUS_EXIT(context*, int, cell**) +[ INFO] [1732703349.099301404]: exiting roseus 0 +mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rossetmaster pr1040 +set ROS_MASTER_URI to http://pr1040:11311 +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ load "main.l" + +Command 'load' not found, did you mean: + + command 'xload' from deb x11-apps (7.7+8) + command 'nload' from deb nload (0.7.4-2build3) + command 'tload' from deb procps (2:3.3.16-1ubuntu2.4) + +Try: sudo apt install + +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ roseus +configuring by "/opt/ros/noetic/share/euslisp/jskeus/eus//lib/eusrt.l" +;; readmacro ;; object ;; packsym ;; common ;; constants ;; stream ;; string ;; loader ;; pprint ;; process ;; hashtab ;; array ;; mathtran ;; eusdebug ;; eusforeign ;; extnum ;; coordinates ;; tty ;; history ;; toplevel ;; trans ;; comp ;; builtins ;; par ;; intersection ;; geoclasses ;; geopack ;; geobody ;; primt ;; compose ;; polygon ;; viewing ;; viewport ;; viewsurface ;; hid ;; shadow ;; bodyrel ;; dda ;; helpsub ;; eushelp ;; xforeign ;; Xdecl ;; Xgraphics ;; Xcolor ;; Xeus ;; Xevent ;; Xpanel ;; Xitem ;; Xtext ;; Xmenu ;; Xscroll ;; Xcanvas ;; Xtop ;; Xapplwin +connected to Xserver DISPLAY=:0 +X events are being asynchronously monitored. +;; pixword ;; RGBHLS ;; convolve ;; piximage ;; pbmfile ;; image_correlation ;; oglforeign ;; gldecl ;; glconst ;; glforeign ;; gluconst ;; gluforeign ;; glxconst ;; glxforeign ;; eglforeign ;; eglfunc ;; glutil ;; gltexture ;; glprim ;; gleus ;; glview ;; toiv-undefined ;; fstringdouble irtmath irtutil irtc irtgeoc irtgraph gnuplotlib ___time ___pgsql irtgeo euspqp pqp irtscene irtmodel irtdyna irtrobot irtsensor irtbvh irtcollada irtstl irtwrl irtpointcloud eusbullet bullet irtcollision irtx eusjpeg euspng png irtimage irtglrgb +;; extending gcstack 0x564dba63f680[16374] --> 0x564dbaacfc90[32748] top=3d4b +irtgl irtglc irtviewer +EusLisp 9.29( 1.2.5) for Linux64 created on ip-10-0-1-5(Tue Jun 20 10:34:21 PST 2023) +roseus ;; loading roseus("1.7.5") on euslisp((9.29 ip-10-0-1-5 Tue Jun 20 10:34:21 PST 2023 1.2.5)) +eustf roseus_c_util 1.irteusgl$ load "main.l" +;; roseus_resume is disabled. + +;; extending gcstack 0x564dbaacfc90[32738] --> 0x564dbc5ed6e0[65476] top=7ed2 +;; # :joint-angle(75.492) violate max-angle(74.2702) +;; (make-irtviewer) executed +[ WARN] [1732703534.233342583]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732703534.251764987]: expected goal id 1732703534202858890_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_0 +[ WARN] [1732703534.251810414]: received goal id /battery_warning-77-1732703528.966 +;; # :joint-angle(75.492) violate max-angle(74.2702) +;; # :joint-angle(75.492) violate max-angle(74.2702) +;; # :joint-angle(75.492) violate max-angle(74.2702) +;; # :joint-angle(75.492) violate max-angle(74.2702) +;; # :joint-angle(75.492) violate max-angle(74.2702) +;; # :joint-angle(75.492) violate max-angle(74.2702) +[ WARN] [1732703540.304097150]: continuous joint (l_wrist_roll_joint) moves 199.998 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732703540.304226332]: continuous joint (r_forearm_roll_joint) moves -308.861 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(75.492) violate max-angle(74.2702) +;; # :joint-angle(75.492) violate max-angle(74.2702) +;; # :joint-angle(75.492) violate max-angle(74.2702) +;; # :joint-angle(75.492) violate max-angle(74.2702) +;; # :joint-angle(75.492) violate max-angle(74.2702) +[ WARN] [1732703540.313528651]: continuous joint (l_wrist_roll_joint) moves 199.998 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732703540.313597376]: continuous joint (r_forearm_roll_joint) moves -308.861 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732703540.313638016]: original trajectory command : +[ WARN] [1732703540.313660573]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732703540.313686188]: current angle vector : #f(50.1614 44.0644 58.6145 95.963 -72.4112 41.6565 -50.9052 -19.9975 -40.3785 74.26 -66.7036 -73.293 288.861 -67.454 20.001 -3.40664 72.2681) +[ WARN] [1732703540.313700009]: new trajectory command : dvi = 3 +[ WARN] [1732703540.313735687]: : #f(50.1076 49.3763 63.743 87.3087 -88.2742 34.4377 -43.9368 46.6683 -46.919 74.1733 -67.8024 -88.862 185.907 -54.9694 73.334 -2.27109 48.1788) 333 +[ WARN] [1732703540.313781115]: : #f(50.0538 54.6881 68.8715 78.6543 -104.137 27.2188 -36.9684 113.334 -53.4595 74.0867 -68.9012 -104.431 82.9537 -42.4847 126.667 -1.13555 24.0894) 333 +[ WARN] [1732703540.313806627]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 333 +[ WARN] [1732703540.313820898]: new trajectory command : +[ WARN] [1732703540.313871658]: : (#f(50.1076 49.3763 63.743 87.3087 -88.2742 34.4377 -43.9368 46.6683 -46.919 74.1733 -67.8024 -88.862 185.907 -54.9694 73.334 -2.27109 48.1788) #f(50.0538 54.6881 68.8715 78.6543 -104.137 27.2188 -36.9684 113.334 -53.4595 74.0867 -68.9012 -104.431 82.9537 -42.4847 126.667 -1.13555 24.0894) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (333 333 333) +;; # :joint-angle(75.492) violate max-angle(74.2702) +[ INFO] [1732703540.318813755]: wait-interpolation debug: start +[ INFO] [1732703542.214279890]: wait-interpolation debug: end +[ INFO] [1732703542.329723096]: wait-interpolation debug: start +[ERROR] [1732703543.942014306]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732703543.942243103]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732703543.956372839]: wait-interpolation debug: end +[ INFO] [1732703549.899107202]: wait-interpolation debug: start +[ INFO] [1732703549.899447750]: wait-interpolation debug: end +[ INFO] [1732703559.608990380]: wait-interpolation debug: start +[ INFO] [1732703559.609446484]: wait-interpolation debug: end +[ INFO] [1732703566.165938402]: wait-interpolation debug: start +[ INFO] [1732703567.182781873]: wait-interpolation debug: end +[ WARN] [1732703567.239398034]: continuous joint (l_forearm_roll_joint) moves 184.273 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732703567.242103206]: continuous joint (l_forearm_roll_joint) moves 184.273 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732703567.242187559]: original trajectory command : +[ WARN] [1732703567.242214579]: : (#f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914)) (1000) +[ WARN] [1732703567.242239554]: current angle vector : #f(50.0 17.4201 14.0475 46.1304 -78.127 5.7373 -34.263 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) +[ WARN] [1732703567.242253581]: new trajectory command : dvi = 2 +[ WARN] [1732703567.242284008]: : #f(50.0 2.27643 22.141 19.3617 -87.1344 97.8737 -49.6376 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) 500 +[ WARN] [1732703567.242308323]: : #f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) 500 +[ WARN] [1732703567.242322564]: new trajectory command : +[ WARN] [1732703567.242354065]: : (#f(50.0 2.27643 22.141 19.3617 -87.1344 97.8737 -49.6376 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) #f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914)) (500 500) +[ INFO] [1732703567.245481934]: wait-interpolation debug: start +[ INFO] [1732703568.430791150]: wait-interpolation debug: end +Call Stack (max depth: 20): + 0: at (while (null *target-ypos-tmp*) (ros::dulation-sleep 0.1) (ros::spin-once)) + 1: at (apply #'ros::load-org-for-ros ros::fullname args) + 2: at (apply #'ros::load-org-for-ros ros::fullname args) + 3: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 4: at (load "main.l") + 5: at # +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: undefined function ros::dulation-sleep in (while (null *target-ypos-tmp*) (ros::dulation-sleep 0.1) (ros::spin-once)) +2.E1-irteusgl$ ros::duration-sleep 0.1 +t +3.E1-irteusgl$ reset +4.irteusgl$ load "main.l" +[ INFO] [1732703633.200146785]: wait-interpolation debug: start +[ERROR] [1732703634.793244701]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732703634.793285922]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732703634.798872681]: wait-interpolation debug: end +[ INFO] [1732703635.267045102]: wait-interpolation debug: start +[ERROR] [1732703636.869009858]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732703636.869066872]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732703636.876170198]: wait-interpolation debug: end +[ INFO] [1732703642.967441401]: wait-interpolation debug: start +[ INFO] [1732703642.969479536]: wait-interpolation debug: end +[ INFO] [1732703652.663041416]: wait-interpolation debug: start +[ INFO] [1732703652.663186694]: wait-interpolation debug: end +[ INFO] [1732703659.243492471]: wait-interpolation debug: start +[ INFO] [1732703660.256767792]: wait-interpolation debug: end +[ WARN] [1732703660.314275847]: continuous joint (l_forearm_roll_joint) moves 184.273 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732703660.319502784]: continuous joint (l_forearm_roll_joint) moves 184.273 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732703660.319673971]: original trajectory command : +[ WARN] [1732703660.319708766]: : (#f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914)) (1000) +[ WARN] [1732703660.319734266]: current angle vector : #f(50.0 17.4201 14.0475 46.1304 -78.127 5.7373 -34.263 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) +[ WARN] [1732703660.319749680]: new trajectory command : dvi = 2 +[ WARN] [1732703660.319785328]: : #f(50.0 2.27643 22.141 19.3617 -87.1344 97.8737 -49.6376 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) 500 +[ WARN] [1732703660.319811793]: : #f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) 500 +[ WARN] [1732703660.319826668]: new trajectory command : +[ WARN] [1732703660.319859357]: : (#f(50.0 2.27643 22.141 19.3617 -87.1344 97.8737 -49.6376 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) #f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914)) (500 500) +[ INFO] [1732703660.323271756]: wait-interpolation debug: start +[ INFO] [1732703661.516906048]: wait-interpolation debug: end +Call Stack (max depth: 20): + 0: at (while (null *target-ypos-tmp*) (ros::dulation-sleep 0.1) (ros::spin-once)) + 1: at (apply #'ros::load-org-for-ros ros::fullname args) + 2: at (apply #'ros::load-org-for-ros ros::fullname args) + 3: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 4: at (load "main.l") + 5: at # +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: undefined function ros::dulation-sleep in (while (null *target-ypos-tmp*) (ros::dulation-sleep 0.1) (ros::spin-once)) +5.E1-irteusgl$ reset +6.irteusgl$ load "main.l" +[ INFO] [1732703682.971356279]: wait-interpolation debug: start +[ERROR] [1732703684.587531314]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732703684.587713805]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732703684.609246577]: wait-interpolation debug: end +[ INFO] [1732703685.115400554]: wait-interpolation debug: start +[ERROR] [1732703686.715547654]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732703686.715600209]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732703686.725866217]: wait-interpolation debug: end +[ INFO] [1732703692.626213506]: wait-interpolation debug: start +[ INFO] [1732703692.628856220]: wait-interpolation debug: end +[ INFO] [1732703702.341820152]: wait-interpolation debug: start +[ INFO] [1732703702.342693569]: wait-interpolation debug: end +[ INFO] [1732703708.876926467]: wait-interpolation debug: start +[ INFO] [1732703709.910111609]: wait-interpolation debug: end +[ WARN] [1732703709.962227474]: continuous joint (l_forearm_roll_joint) moves 184.273 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732703709.964847646]: continuous joint (l_forearm_roll_joint) moves 184.273 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732703709.964931599]: original trajectory command : +[ WARN] [1732703709.964959066]: : (#f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914)) (1000) +[ WARN] [1732703709.964982736]: current angle vector : #f(50.0 17.4201 14.0475 46.1304 -78.127 5.7373 -34.263 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) +[ WARN] [1732703709.964997105]: new trajectory command : dvi = 2 +[ WARN] [1732703709.965027371]: : #f(50.0 2.27643 22.141 19.3617 -87.1344 97.8737 -49.6376 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) 500 +[ WARN] [1732703709.965050860]: : #f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) 500 +[ WARN] [1732703709.965065416]: new trajectory command : +[ WARN] [1732703709.965096496]: : (#f(50.0 2.27643 22.141 19.3617 -87.1344 97.8737 -49.6376 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) #f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914)) (500 500) +[ INFO] [1732703709.970730164]: wait-interpolation debug: start +[ INFO] [1732703711.147222468]: wait-interpolation debug: end +Call Stack (max depth: 20): + 0: at (while (< i #:dotimes871122) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (+ *target-ypos* (* *traj_len* 0.2)) *target-zpos*))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) x (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -pi/2 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (* *needle_len* 0.5) 200)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (- 0 (* *needle_len* 0.5)) 200)) :translate #f(-10.0 0.0 0.0)) :rotate -pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1) (send *pr2* :rarm :move-end-pos (float-vector 0 0 -50) :local) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq i (1+ i))) + 1: at (let ((i 0) (#:dotimes871122 5)) (declare (integer i #:dotimes871122)) (while (< i #:dotimes871122) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (+ *target-ypos* (* *traj_len* 0.2)) *target-zpos*))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) x (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -pi/2 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (* *needle_len* 0.5) 200)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (- 0 (* *needle_len* 0.5)) 200)) :translate #f(-10.0 0.0 0.0)) :rotate -pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1) (send *pr2* :rarm :move-end-pos (float-vector 0 0 -50) :local) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq i (1+ i))) nil) + 2: at (dotimes (i 5) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (+ *target-ypos* (* *traj_len* 0.2)) *target-zpos*))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) x (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -pi/2 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (* *needle_len* 0.5) 200)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (- 0 (* *needle_len* 0.5)) 200)) :translate #f(-10.0 0.0 0.0)) :rotate -pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1) (send *pr2* :rarm :move-end-pos (float-vector 0 0 -50) :local) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects)) + 3: at (apply #'ros::load-org-for-ros ros::fullname args) + 4: at (apply #'ros::load-org-for-ros ros::fullname args) + 5: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 6: at (load "main.l") + 7: at # +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: unbound variable x in (while (< i #:dotimes871122) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (+ *target-ypos* (* *traj_len* 0.2)) *target-zpos*))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) x (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -pi/2 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (* *needle_len* 0.5) 200)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (- 0 (* *needle_len* 0.5)) 200)) :translate #f(-10.0 0.0 0.0)) :rotate -pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1) (send *pr2* :rarm :move-end-pos (float-vector 0 0 -50) :local) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq i (1+ i))) +7.E1-irteusgl$ reset +8.irteusgl$ load "main.l" +[ WARN] [1732703992.655614622]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732703992.655669934]: expected goal id 1732703992654619800_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_12 +[ WARN] [1732703992.655700840]: received goal id /battery_warning-78-1732703712.966 +[ WARN] [1732703992.656042650]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732703992.656073044]: expected goal id 1732703992654619800_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_12 +[ WARN] [1732703992.656096993]: received goal id /battery_warning-79-1732703896.966 +[ INFO] [1732703996.564565394]: wait-interpolation debug: start +[ERROR] [1732703998.167052915]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732703998.167127825]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732703998.167929981]: wait-interpolation debug: end +[ INFO] [1732703998.690659529]: wait-interpolation debug: start +[ERROR] [1732704000.288795333]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704000.288891799]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704000.293471841]: wait-interpolation debug: end +[ WARN] [1732704000.701062586]: [robotsound_jp] :wait-for-result finished with preempted status +[ INFO] [1732704002.559222371]: wait-interpolation debug: start +[ INFO] [1732704002.568909708]: wait-interpolation debug: end +[ WARN] [1732704005.580903340]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732704005.581063220]: expected goal id 1732704005571026285_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_14 +[ WARN] [1732704005.581177732]: received goal id 1732704000422308794_/tweet_client_warning_473265_robotsound_jp_66 +[ WARN] [1732704005.586908017]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732704005.587086654]: expected goal id 1732704005571026285_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_14 +[ WARN] [1732704005.587197558]: received goal id 1732704001425731067_/tweet_client_warning_473265_robotsound_jp_67 +[ WARN] [1732704005.588812146]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732704005.588946754]: expected goal id 1732704005571026285_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_14 +[ WARN] [1732704005.589048037]: received goal id 1732704002485925043_/tweet_client_warning_473265_robotsound_jp_68 +[ INFO] [1732704012.283733463]: wait-interpolation debug: start +[ INFO] [1732704012.283969176]: wait-interpolation debug: end +[ INFO] [1732704018.874739535]: wait-interpolation debug: start +[ INFO] [1732704019.886548361]: wait-interpolation debug: end +[ WARN] [1732704019.941859221]: continuous joint (l_forearm_roll_joint) moves 184.273 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704019.944397257]: continuous joint (l_forearm_roll_joint) moves 184.273 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704019.944530069]: original trajectory command : +[ WARN] [1732704019.944564288]: : (#f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914)) (1000) +[ WARN] [1732704019.944593892]: current angle vector : #f(50.0 17.4201 14.0475 46.1304 -78.127 5.7373 -34.263 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) +[ WARN] [1732704019.944612628]: new trajectory command : dvi = 2 +[ WARN] [1732704019.944647913]: : #f(50.0 2.27643 22.141 19.3617 -87.1344 97.8737 -49.6376 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) 500 +[ WARN] [1732704019.944699100]: : #f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) 500 +[ WARN] [1732704019.944731058]: new trajectory command : +[ WARN] [1732704019.944791725]: : (#f(50.0 2.27643 22.141 19.3617 -87.1344 97.8737 -49.6376 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) #f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914)) (500 500) +[ INFO] [1732704019.956490337]: wait-interpolation debug: start +[ INFO] [1732704021.152284291]: wait-interpolation debug: end +-0.768267 +#f(700.0 19.2317 790.0) +Call Stack (max depth: 20): + 0: at (while (< i #:dotimes1145063) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (print (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (+ *target-ypos* (* *traj_len* 0.2)) *target-zpos*)))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) x (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -pi/2 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (* *needle_len* 0.5) 200)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (- 0 (* *needle_len* 0.5)) 200)) :translate #f(-10.0 0.0 0.0)) :rotate -pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1) (send *pr2* :rarm :move-end-pos (float-vector 0 0 -50) :local) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq i (1+ i))) + 1: at (let ((i 0) (#:dotimes1145063 5)) (declare (integer i #:dotimes1145063)) (while (< i #:dotimes1145063) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (print (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (+ *target-ypos* (* *traj_len* 0.2)) *target-zpos*)))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) x (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -pi/2 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (* *needle_len* 0.5) 200)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (- 0 (* *needle_len* 0.5)) 200)) :translate #f(-10.0 0.0 0.0)) :rotate -pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1) (send *pr2* :rarm :move-end-pos (float-vector 0 0 -50) :local) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq i (1+ i))) nil) + 2: at (dotimes (i 5) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (print (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (+ *target-ypos* (* *traj_len* 0.2)) *target-zpos*)))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) x (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -pi/2 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (* *needle_len* 0.5) 200)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (- 0 (* *needle_len* 0.5)) 200)) :translate #f(-10.0 0.0 0.0)) :rotate -pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1) (send *pr2* :rarm :move-end-pos (float-vector 0 0 -50) :local) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects)) + 3: at (apply #'ros::load-org-for-ros ros::fullname args) + 4: at (apply #'ros::load-org-for-ros ros::fullname args) + 5: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 6: at (load "main.l") + 7: at # +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: unbound variable x in (while (< i #:dotimes1145063) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (print (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (+ *target-ypos* (* *traj_len* 0.2)) *target-zpos*)))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) x (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -pi/2 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (* *needle_len* 0.5) 200)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 0 (- 0 (* *needle_len* 0.5)) 200)) :translate #f(-10.0 0.0 0.0)) :rotate -pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1) (send *pr2* :rarm :move-end-pos (float-vector 0 0 -50) :local) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq i (1+ i))) +9.E1-irteusgl$ reset +10.irteusgl$ load "main.l" +[ INFO] [1732704073.472375224]: wait-interpolation debug: start +[ERROR] [1732704075.068490952]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704075.068548957]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704075.070509360]: wait-interpolation debug: end +[ INFO] [1732704075.501493446]: wait-interpolation debug: start +[ERROR] [1732704077.108676322]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704077.108729534]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704077.113607238]: wait-interpolation debug: end +[ WARN] [1732704080.970374641]: [robotsound_jp] :wait-for-result finished with preempted status +[ INFO] [1732704082.809870724]: wait-interpolation debug: start +[ INFO] [1732704082.820778965]: wait-interpolation debug: end +[ WARN] [1732704085.853541133]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732704085.853577127]: expected goal id 1732704085823197239_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_18 +[ WARN] [1732704085.853590873]: received goal id /battery_warning-80-1732704080.966 +[ INFO] [1732704092.656960255]: wait-interpolation debug: start +[ INFO] [1732704092.657784285]: wait-interpolation debug: end +[ INFO] [1732704099.242181024]: wait-interpolation debug: start +[ INFO] [1732704100.271459370]: wait-interpolation debug: end +[ WARN] [1732704100.317790631]: continuous joint (l_forearm_roll_joint) moves 184.273 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704100.321258614]: continuous joint (l_forearm_roll_joint) moves 184.273 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704100.321338211]: original trajectory command : +[ WARN] [1732704100.321369419]: : (#f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914)) (1000) +[ WARN] [1732704100.321392552]: current angle vector : #f(50.0 17.4201 14.0475 46.1304 -78.127 5.7373 -34.263 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) +[ WARN] [1732704100.321404651]: new trajectory command : dvi = 2 +[ WARN] [1732704100.321432581]: : #f(50.0 2.27643 22.141 19.3617 -87.1344 97.8737 -49.6376 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) 500 +[ WARN] [1732704100.321454299]: : #f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) 500 +[ WARN] [1732704100.321465991]: new trajectory command : +[ WARN] [1732704100.321495530]: : (#f(50.0 2.27643 22.141 19.3617 -87.1344 97.8737 -49.6376 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) #f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914)) (500 500) +[ INFO] [1732704100.323915114]: wait-interpolation debug: start +[ INFO] [1732704101.499980288]: wait-interpolation debug: end +[ WARN] [1732704101.668415048]: continuous joint (r_forearm_roll_joint) moves 187.079 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704101.673892001]: continuous joint (r_forearm_roll_joint) moves 187.079 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704101.674017957]: original trajectory command : +[ WARN] [1732704101.674080776]: : (#f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 32.3349 42.6874 31.4011 -95.2666 167.079 -44.9768 76.3966 0.0 42.3914)) (500) +[ WARN] [1732704101.674132175]: current angle vector : #f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.3914) +[ WARN] [1732704101.674167233]: new trajectory command : dvi = 2 +[ WARN] [1732704101.674214982]: : #f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -13.8326 58.3437 -19.2995 -107.633 73.5394 -37.4884 128.198 0.0 42.3914) 250 +[ WARN] [1732704101.674280543]: : #f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 32.3349 42.6874 31.4011 -95.2666 167.079 -44.9768 76.3966 0.0 42.3914) 250 +[ WARN] [1732704101.674309354]: new trajectory command : +[ WARN] [1732704101.674359927]: : (#f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 -13.8326 58.3437 -19.2995 -107.633 73.5394 -37.4884 128.198 0.0 42.3914) #f(50.0 -12.8673 30.2345 -7.40696 -96.1417 190.01 -65.0122 172.928 32.3349 42.6874 31.4011 -95.2666 167.079 -44.9768 76.3966 0.0 42.3914)) (250 250) +[ INFO] [1732704101.719353659]: wait-interpolation debug: start +[ERROR] [1732704103.313266647]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704103.313342078]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704103.313938218]: wait-interpolation debug: end +[ INFO] [1732704103.767684532]: wait-interpolation debug: start +[ERROR] [1732704105.366371727]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704105.366413522]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704105.370420386]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732704105.494688368]: wait-interpolation debug: start +[ INFO] [1732704106.526821922]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732704106.573793173]: wait-interpolation debug: start +[ INFO] [1732704107.579593815]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732704107.620738439]: wait-interpolation debug: start +[ INFO] [1732704108.626769296]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732704108.685269953]: wait-interpolation debug: start +[ INFO] [1732704109.691531607]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732704109.755102683]: wait-interpolation debug: start +[ INFO] [1732704110.756206303]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732704110.800989964]: wait-interpolation debug: start +[ INFO] [1732704111.813285064]: wait-interpolation debug: end +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +[ INFO] [1732704111.873393764]: wait-interpolation debug: start +[ INFO] [1732704112.886282713]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732704112.931767668]: wait-interpolation debug: start +[ INFO] [1732704113.932237322]: wait-interpolation debug: end +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +;; # :joint-angle(88.0739) violate max-angle(88.0) +[ INFO] [1732704113.975056935]: wait-interpolation debug: start +[ INFO] [1732704115.025061040]: wait-interpolation debug: end +;; # :joint-angle(88.0739) violate max-angle(88.0) +[ INFO] [1732704117.191084400]: wait-interpolation debug: start +[ INFO] [1732704117.191372075]: wait-interpolation debug: end +[ INFO] [1732704120.036755907]: wait-interpolation debug: start +[ INFO] [1732704120.043390584]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732704120.085370873]: wait-interpolation debug: start +[ INFO] [1732704121.107482754]: wait-interpolation debug: end +[ INFO] [1732704121.192087501]: wait-interpolation debug: start +[ERROR] [1732704126.165548999]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704126.165636150]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704126.170128770]: wait-interpolation debug: end +[ INFO] [1732704127.384348364]: wait-interpolation debug: start +[ INFO] [1732704128.381964809]: wait-interpolation debug: end +[ INFO] [1732704130.350729480]: wait-interpolation debug: start +[ INFO] [1732704130.352157743]: wait-interpolation debug: end +[ INFO] [1732704131.368739370]: wait-interpolation debug: start +[ INFO] [1732704131.383040702]: wait-interpolation debug: end +[ WARN] [1732704132.114799655]: [robotsound_jp] :wait-for-result finished with preempted status +[ INFO] [1732704133.168575893]: wait-interpolation debug: start +[ INFO] [1732704134.164057516]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732704134.212963417]: wait-interpolation debug: start +[ INFO] [1732704135.258527357]: wait-interpolation debug: end +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +[ INFO] [1732704135.302333812]: wait-interpolation debug: start +[ INFO] [1732704136.359006947]: wait-interpolation debug: end +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +[ INFO] [1732704136.403597517]: wait-interpolation debug: start +[ INFO] [1732704137.403767564]: wait-interpolation debug: end +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +[ INFO] [1732704137.483608571]: wait-interpolation debug: start +[ INFO] [1732704138.484117903]: wait-interpolation debug: end +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +[ INFO] [1732704138.561862326]: wait-interpolation debug: start +[ INFO] [1732704139.631363377]: wait-interpolation debug: end +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +[ INFO] [1732704139.687722356]: wait-interpolation debug: start +[ INFO] [1732704140.699600787]: wait-interpolation debug: end +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +[ INFO] [1732704140.778142897]: wait-interpolation debug: start +[ INFO] [1732704150.868336513]: wait-interpolation debug: end +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +[ INFO] [1732704150.945412914]: wait-interpolation debug: start +[ WARN] [1732704150.958355046]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704150.958714597]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704150.959057384]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704150.959383120]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704150.959772851]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704150.960148980]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704150.960572236]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704150.961043934]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704153.950690843]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704153.958173849]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704153.959415178]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704153.960492791]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704153.961540497]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.423488563]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.430400381]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.432642602]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.432998852]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.433382316]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.433779189]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.434127054]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.434902255]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.435315486]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.440611930]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.441477145]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.441772447]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.442066565]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.442356463]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.442735793]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.443029741]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.443318368]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.450354034]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.450843474]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.451140855]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.451433950]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.451727624]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.452744785]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.453085944]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732704154.453399207]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ INFO] [1732704154.543138304]: wait-interpolation debug: end +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +[ INFO] [1732704154.587040986]: wait-interpolation debug: start +[ INFO] [1732704155.617616036]: wait-interpolation debug: end +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +[ INFO] [1732704155.668379657]: wait-interpolation debug: start +[ INFO] [1732704156.686120148]: wait-interpolation debug: end +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +;; # :joint-angle(88.0695) violate max-angle(88.0) +[ INFO] [1732704156.724879371]: wait-interpolation debug: start +[ INFO] [1732704157.728927577]: wait-interpolation debug: end +;; # :joint-angle(88.0695) violate max-angle(88.0) +[ INFO] [1732704159.869592888]: wait-interpolation debug: start +[ INFO] [1732704159.870322588]: wait-interpolation debug: end +[ INFO] [1732704162.774758062]: wait-interpolation debug: start +[ INFO] [1732704162.778834222]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732704162.818811069]: wait-interpolation debug: start +[ INFO] [1732704163.821591819]: wait-interpolation debug: end +[ INFO] [1732704163.944456349]: wait-interpolation debug: start +[ERROR] [1732704166.668627715]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704166.668666581]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704166.674195931]: wait-interpolation debug: end +[ INFO] [1732704167.452716658]: wait-interpolation debug: start +[ INFO] [1732704168.491196265]: wait-interpolation debug: end +[ INFO] [1732704170.464906084]: wait-interpolation debug: start +[ INFO] [1732704170.465050251]: wait-interpolation debug: end +[ INFO] [1732704171.473277482]: wait-interpolation debug: start +[ INFO] [1732704171.474256388]: wait-interpolation debug: end +[ WARN] [1732704171.475523557]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732704171.475555981]: expected goal id 1732704171474757486_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_21 +[ WARN] [1732704171.475586622]: received goal id 1732704132104723610_/tweet_client_uptime_473244_robotsound_jp_9 +[ WARN] [1732704171.475905188]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732704171.475935417]: expected goal id 1732704171474757486_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_21 +[ WARN] [1732704171.475961522]: received goal id 1732704133108675725_/tweet_client_uptime_473244_robotsound_jp_10 +[ WARN] [1732704171.476242503]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732704171.476284789]: expected goal id 1732704171474757486_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_21 +[ WARN] [1732704171.476326634]: received goal id 1732704133988762873_/tweet_client_uptime_473244_robotsound_jp_11 +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732704176.907448212]: wait-interpolation debug: start +[ INFO] [1732704177.910566081]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732704177.953969220]: wait-interpolation debug: start +[ INFO] [1732704178.958785924]: wait-interpolation debug: end +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +[ INFO] [1732704179.003970570]: wait-interpolation debug: start +[ INFO] [1732704180.003608607]: wait-interpolation debug: end +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +[ INFO] [1732704180.064135432]: wait-interpolation debug: start +[ INFO] [1732704181.070489613]: wait-interpolation debug: end +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +[ INFO] [1732704181.113521863]: wait-interpolation debug: start +[ INFO] [1732704182.113322778]: wait-interpolation debug: end +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +[ INFO] [1732704182.158921184]: wait-interpolation debug: start +[ INFO] [1732704183.168493117]: wait-interpolation debug: end +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +[ INFO] [1732704183.208584854]: wait-interpolation debug: start +[ INFO] [1732704184.213774485]: wait-interpolation debug: end +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +[ INFO] [1732704184.254496944]: wait-interpolation debug: start +[ INFO] [1732704185.267535922]: wait-interpolation debug: end +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +[ INFO] [1732704185.314407984]: wait-interpolation debug: start +[ INFO] [1732704186.319450404]: wait-interpolation debug: end +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +[ INFO] [1732704186.369979608]: wait-interpolation debug: start +[ INFO] [1732704187.382487348]: wait-interpolation debug: end +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +[ INFO] [1732704187.428822922]: wait-interpolation debug: start +[ INFO] [1732704188.429272839]: wait-interpolation debug: end +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +;; # :joint-angle(88.0647) violate max-angle(88.0) +[ INFO] [1732704188.493115503]: wait-interpolation debug: start +[ INFO] [1732704189.499045828]: wait-interpolation debug: end +;; # :joint-angle(88.0647) violate max-angle(88.0) +[ INFO] [1732704191.629224971]: wait-interpolation debug: start +[ INFO] [1732704191.630110460]: wait-interpolation debug: end +[ INFO] [1732704194.485811651]: wait-interpolation debug: start +[ INFO] [1732704194.493574920]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732704194.533974311]: wait-interpolation debug: start +[ INFO] [1732704195.563984514]: wait-interpolation debug: end +[ INFO] [1732704195.650411997]: wait-interpolation debug: start +[ERROR] [1732704197.469595397]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704197.469648630]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704197.473420146]: wait-interpolation debug: end +[ INFO] [1732704198.077444217]: wait-interpolation debug: start +[ INFO] [1732704199.093513332]: wait-interpolation debug: end +[ INFO] [1732704201.063008847]: wait-interpolation debug: start +[ INFO] [1732704201.063203615]: wait-interpolation debug: end + C-c C-cinterrupt11.B1-irteusgl$ load "main.l" +[ WARN] [1732704260.978353895]: [robotsound_jp] :wait-for-result finished with preempted status +[ WARN] [1732704261.014530879]: continuous joint (r_forearm_roll_joint) moves -182.094 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704261.059045794]: continuous joint (r_forearm_roll_joint) moves -182.094 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704261.059137225]: original trajectory command : +[ WARN] [1732704261.059181469]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732704261.059220990]: current angle vector : #f(173.77 1.6717 -13.3171 82.758 -33.2965 88.5807 -105.062 237.341 -6.5154 33.0941 -42.409 -95.3215 162.094 -66.558 133.406 0.0 42.3914) +[ WARN] [1732704261.059247548]: new trajectory command : dvi = 2 +[ WARN] [1732704261.059283825]: : #f(111.885 30.8358 30.3414 76.379 -76.6483 54.2904 -67.5312 208.67 -33.2577 53.5471 -56.2045 -107.661 71.0469 -48.279 156.703 0.0 21.1957) 500 +[ WARN] [1732704261.059314402]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732704261.059330291]: new trajectory command : +[ WARN] [1732704261.059362926]: : (#f(111.885 30.8358 30.3414 76.379 -76.6483 54.2904 -67.5312 208.67 -33.2577 53.5471 -56.2045 -107.661 71.0469 -48.279 156.703 0.0 21.1957) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732704261.063596511]: wait-interpolation debug: start +[ERROR] [1732704270.677581006]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704270.677637829]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704270.684621311]: wait-interpolation debug: end +[ INFO] [1732704273.131179181]: wait-interpolation debug: start +[ERROR] [1732704274.748147136]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704274.748191652]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704274.751204479]: wait-interpolation debug: end +[ WARN] [1732704274.789516270]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732704274.789561264]: expected goal id 1732704274788542054_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_23 +[ WARN] [1732704274.789577432]: received goal id /battery_warning-81-1732704260.966 +[ INFO] [1732704280.641017752]: wait-interpolation debug: start +[ INFO] [1732704280.642882859]: wait-interpolation debug: end +[ INFO] [1732704290.370694918]: wait-interpolation debug: start +[ INFO] [1732704290.370992617]: wait-interpolation debug: end +[ INFO] [1732704296.940526940]: wait-interpolation debug: start +[ INFO] [1732704297.971500146]: wait-interpolation debug: end +[ WARN] [1732704298.016687775]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704298.019472989]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704298.019543282]: original trajectory command : +[ WARN] [1732704298.019568471]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (1000) +[ WARN] [1732704298.019591533]: current angle vector : #f(50.0 17.8275 14.7726 46.824 -78.4543 6.11414 -34.739 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732704298.019603945]: new trajectory command : dvi = 2 +[ WARN] [1732704298.019632690]: : #f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732704298.019655311]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732704298.019672582]: new trajectory command : +[ WARN] [1732704298.019706410]: : (#f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (500 500) +[ INFO] [1732704298.022204721]: wait-interpolation debug: start +[ INFO] [1732704299.197539087]: wait-interpolation debug: end +[ WARN] [1732704299.342211735]: continuous joint (r_forearm_roll_joint) moves 187.266 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704299.348408637]: continuous joint (r_forearm_roll_joint) moves 187.266 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704299.348484626]: original trajectory command : +[ WARN] [1732704299.348551388]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2605 43.8798 31.2238 -95.0236 167.266 -43.8152 77.0466 0.0 42.8986)) (500) +[ WARN] [1732704299.348605256]: current angle vector : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732704299.348623710]: new trajectory command : dvi = 2 +[ WARN] [1732704299.348688782]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8698 58.9399 -19.3881 -107.512 73.6332 -36.9076 128.523 0.0 42.8986) 250 +[ WARN] [1732704299.348737376]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2605 43.8798 31.2238 -95.0236 167.266 -43.8152 77.0466 0.0 42.8986) 250 +[ WARN] [1732704299.348751747]: new trajectory command : +[ WARN] [1732704299.348804958]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8698 58.9399 -19.3881 -107.512 73.6332 -36.9076 128.523 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2605 43.8798 31.2238 -95.0236 167.266 -43.8152 77.0466 0.0 42.8986)) (250 250) +[ INFO] [1732704299.355270068]: wait-interpolation debug: start +[ERROR] [1732704300.957094949]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704300.957148230]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704300.963818500]: wait-interpolation debug: end +[ INFO] [1732704301.411969411]: wait-interpolation debug: start +[ INFO] [1732704302.721605284]: wait-interpolation debug: end +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +[ INFO] [1732704302.782699023]: wait-interpolation debug: start +[ INFO] [1732704303.784433080]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732704303.824372912]: wait-interpolation debug: start +[ INFO] [1732704304.857833046]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732704304.903721029]: wait-interpolation debug: start +[ INFO] [1732704305.910444710]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732704305.951330901]: wait-interpolation debug: start +[ INFO] [1732704306.949888492]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732704307.002045908]: wait-interpolation debug: start +[ INFO] [1732704308.010741585]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732704308.053955137]: wait-interpolation debug: start +[ INFO] [1732704309.053289012]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732704309.142144219]: wait-interpolation debug: start +[ INFO] [1732704310.146481535]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732704310.239267631]: wait-interpolation debug: start +[ INFO] [1732704311.273247332]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732704311.362911129]: wait-interpolation debug: start +[ INFO] [1732704312.369192288]: wait-interpolation debug: end +;; # :joint-angle(88.0775) violate max-angle(88.0) +[ INFO] [1732704314.512760114]: wait-interpolation debug: start +[ INFO] [1732704314.512954921]: wait-interpolation debug: end +[ INFO] [1732704317.350830504]: wait-interpolation debug: start +[ INFO] [1732704317.351271689]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732704317.392572123]: wait-interpolation debug: start +[ INFO] [1732704318.393497181]: wait-interpolation debug: end +[ INFO] [1732704318.473184222]: wait-interpolation debug: start +[ERROR] [1732704323.030931209]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704323.030971882]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704323.031551711]: wait-interpolation debug: end +[ INFO] [1732704325.166874839]: wait-interpolation debug: start +[ INFO] [1732704326.163149492]: wait-interpolation debug: end +[ INFO] [1732704328.143357540]: wait-interpolation debug: start +[ INFO] [1732704328.143581241]: wait-interpolation debug: end +[ INFO] [1732704329.151667398]: wait-interpolation debug: start +[ INFO] [1732704329.158691615]: wait-interpolation debug: end +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +[ INFO] [1732704334.557334139]: wait-interpolation debug: start +[ INFO] [1732704335.551767889]: wait-interpolation debug: end +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +;; # :joint-angle(88.0769) violate max-angle(88.0) +[ INFO] [1732704335.630844663]: wait-interpolation debug: start +[ INFO] [1732704336.643599734]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732704336.741726252]: wait-interpolation debug: start +[ INFO] [1732704337.779591173]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732704337.821276079]: wait-interpolation debug: start +[ INFO] [1732704338.828294738]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732704338.871010315]: wait-interpolation debug: start +[ INFO] [1732704339.898295275]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732704339.942643518]: wait-interpolation debug: start +[ INFO] [1732704340.954570088]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732704340.996632622]: wait-interpolation debug: start +[ INFO] [1732704342.002101529]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732704342.075981702]: wait-interpolation debug: start +[ INFO] [1732704343.084145439]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732704343.172863392]: wait-interpolation debug: start +[ INFO] [1732704344.159785715]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732704344.238153691]: wait-interpolation debug: start +[ INFO] [1732704345.219883642]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732704345.268510904]: wait-interpolation debug: start +[ INFO] [1732704346.273659167]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732704346.322364583]: wait-interpolation debug: start +[ INFO] [1732704347.342457063]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732704349.462759500]: wait-interpolation debug: start +[ INFO] [1732704349.464455176]: wait-interpolation debug: end +[ INFO] [1732704352.308038144]: wait-interpolation debug: start +[ INFO] [1732704352.310734585]: wait-interpolation debug: end +remaining 300 +[ INFO] [1732704352.401979642]: wait-interpolation debug: start +[ INFO] [1732704353.402666525]: wait-interpolation debug: end +[ INFO] [1732704353.499233032]: wait-interpolation debug: start +[ERROR] [1732704356.095635553]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704356.095685741]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704356.102149107]: wait-interpolation debug: end +[ INFO] [1732704356.823878789]: wait-interpolation debug: start +[ INFO] [1732704357.829700074]: wait-interpolation debug: end +[ INFO] [1732704359.783059277]: wait-interpolation debug: start +[ INFO] [1732704359.783237419]: wait-interpolation debug: end +[ INFO] [1732704360.798729753]: wait-interpolation debug: start +[ INFO] [1732704360.804810422]: wait-interpolation debug: end +[ INFO] [1732704360.804810422]: wait-interpolation debug: end C-c C-cinterrupt12.B2-irteusgl$ load "main.l" +[ WARN] [1732704508.289016431]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732704508.289055620]: expected goal id 1732704360808994868_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_27 +[ WARN] [1732704508.289072250]: received goal id /battery_warning-82-1732704444.966 +[ WARN] [1732704512.183829345]: [/r_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732704512.183870313]: expected goal id 1732704512173982219_/pr2_eus_interface_1732703530848654340_74049_/r_gripper_controller/gripper_action_20 +[ WARN] [1732704512.183897657]: received goal id 1732704360783698607_/pr2_eus_interface_1732703530848654340_74049_/r_gripper_controller/gripper_action_19 +[ WARN] [1732704514.349268662]: continuous joint (r_forearm_roll_joint) moves -182.015 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704514.352060888]: continuous joint (r_forearm_roll_joint) moves -182.015 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704514.352138336]: original trajectory command : +[ WARN] [1732704514.352200606]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732704514.352249414]: current angle vector : #f(143.044 0.505148 -14.46 80.015 -30.3223 91.1331 -107.476 239.087 1.02488 36.0182 -26.6208 -96.3262 162.015 -64.8275 120.038 0.0 42.8986) +[ WARN] [1732704514.352289452]: new trajectory command : dvi = 2 +[ WARN] [1732704514.352365725]: : #f(96.5222 30.2526 29.77 75.0075 -75.1611 55.5666 -68.7381 209.544 -29.4876 55.0091 -48.3104 -108.163 71.0076 -47.4138 150.019 0.0 21.4493) 500 +[ WARN] [1732704514.352423296]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732704514.352460820]: new trajectory command : +[ WARN] [1732704514.352555090]: : (#f(96.5222 30.2526 29.77 75.0075 -75.1611 55.5666 -68.7381 209.544 -29.4876 55.0091 -48.3104 -108.163 71.0076 -47.4138 150.019 0.0 21.4493) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732704514.358851049]: wait-interpolation debug: start +[ERROR] [1732704521.618751696]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704521.618811649]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704521.661741247]: wait-interpolation debug: end +[ INFO] [1732704523.574132547]: wait-interpolation debug: start +[ERROR] [1732704525.176647881]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704525.176723529]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704525.189500248]: wait-interpolation debug: end +[ INFO] [1732704531.195038979]: wait-interpolation debug: start +[ INFO] [1732704531.197978980]: wait-interpolation debug: end +[ INFO] [1732704540.930305313]: wait-interpolation debug: start +[ INFO] [1732704540.930923052]: wait-interpolation debug: end +[ INFO] [1732704547.491215601]: wait-interpolation debug: start +[ INFO] [1732704548.520393186]: wait-interpolation debug: end +[ WARN] [1732704548.570762311]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704548.573130596]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704548.573204547]: original trajectory command : +[ WARN] [1732704548.573232340]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (1000) +[ WARN] [1732704548.573256518]: current angle vector : #f(50.0 17.8275 14.7726 46.824 -78.4543 6.11414 -34.739 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732704548.573270136]: new trajectory command : dvi = 2 +[ WARN] [1732704548.573304259]: : #f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732704548.573331329]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732704548.573357694]: new trajectory command : +[ WARN] [1732704548.573390120]: : (#f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (500 500) +[ INFO] [1732704548.576818829]: wait-interpolation debug: start +[ INFO] [1732704549.750485096]: wait-interpolation debug: end +[ WARN] [1732704549.893221860]: continuous joint (r_forearm_roll_joint) moves 187.267 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704549.898249194]: continuous joint (r_forearm_roll_joint) moves 187.267 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704549.898329585]: original trajectory command : +[ WARN] [1732704549.898368575]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2604 43.8797 31.2245 -95.0238 167.267 -43.8154 77.0455 0.0 42.8986)) (500) +[ WARN] [1732704549.898401875]: current angle vector : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732704549.898423922]: new trajectory command : dvi = 2 +[ WARN] [1732704549.898466297]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8698 58.9398 -19.3878 -107.512 73.6336 -36.9077 128.523 0.0 42.8986) 250 +[ WARN] [1732704549.898514682]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2604 43.8797 31.2245 -95.0238 167.267 -43.8154 77.0455 0.0 42.8986) 250 +[ WARN] [1732704549.898547847]: new trajectory command : +[ WARN] [1732704549.898610783]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8698 58.9398 -19.3878 -107.512 73.6336 -36.9077 128.523 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2604 43.8797 31.2245 -95.0238 167.267 -43.8154 77.0455 0.0 42.8986)) (250 250) +[ INFO] [1732704549.904421484]: wait-interpolation debug: start +[ERROR] [1732704551.509364576]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704551.509402655]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704551.510034184]: wait-interpolation debug: end +[ INFO] [1732704551.913662608]: wait-interpolation debug: start +[ INFO] [1732704553.273867902]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +;; # :joint-angle(88.0751) violate max-angle(88.0) +[ INFO] [1732704553.358474699]: wait-interpolation debug: start +[ INFO] [1732704554.379520204]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732704554.423471907]: wait-interpolation debug: start +[ INFO] [1732704555.429201193]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732704555.483114550]: wait-interpolation debug: start +[ INFO] [1732704556.482513530]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732704556.522604998]: wait-interpolation debug: start +[ INFO] [1732704557.553602484]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732704557.592184290]: wait-interpolation debug: start +[ INFO] [1732704558.632514116]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732704558.681343318]: wait-interpolation debug: start +[ INFO] [1732704559.677176677]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732704559.759050134]: wait-interpolation debug: start +[ INFO] [1732704560.757607598]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732704560.831649589]: wait-interpolation debug: start +[ INFO] [1732704561.833201690]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732704561.877897788]: wait-interpolation debug: start +[ INFO] [1732704562.880333928]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732704565.027782811]: wait-interpolation debug: start +[ INFO] [1732704565.034550412]: wait-interpolation debug: end +[ INFO] [1732704567.875506894]: wait-interpolation debug: start +[ INFO] [1732704567.875711590]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732704567.913156251]: wait-interpolation debug: start +[ INFO] [1732704572.918387591]: wait-interpolation debug: end +[ INFO] [1732704573.027064166]: wait-interpolation debug: start +[ERROR] [1732704577.577869997]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704577.577948697]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704577.583094138]: wait-interpolation debug: end +[ INFO] [1732704578.689612865]: wait-interpolation debug: start +[ INFO] [1732704579.688157155]: wait-interpolation debug: end +[ INFO] [1732704581.682359016]: wait-interpolation debug: start +[ INFO] [1732704581.683133541]: wait-interpolation debug: end +[ INFO] [1732704582.693583000]: wait-interpolation debug: start +[ INFO] [1732704582.698516525]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732704588.077457503]: wait-interpolation debug: start +[ INFO] [1732704589.081087493]: wait-interpolation debug: end +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +;; # :joint-angle(88.0745) violate max-angle(88.0) +[ INFO] [1732704589.122718174]: wait-interpolation debug: start +[ INFO] [1732704590.165827647]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732704590.226696617]: wait-interpolation debug: start +[ INFO] [1732704591.222425321]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732704591.302775874]: wait-interpolation debug: start +[ INFO] [1732704592.310403849]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732704592.349285418]: wait-interpolation debug: start +[ INFO] [1732704593.398526203]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732704593.439538368]: wait-interpolation debug: start +[ INFO] [1732704594.449078906]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732704594.492195343]: wait-interpolation debug: start +[ INFO] [1732704595.493305801]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732704595.539121844]: wait-interpolation debug: start +[ INFO] [1732704596.542049586]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732704596.584674827]: wait-interpolation debug: start +[ INFO] [1732704597.582328265]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732704597.626636264]: wait-interpolation debug: start +[ INFO] [1732704598.622264151]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732704598.666625986]: wait-interpolation debug: start +[ INFO] [1732704599.708820685]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732704599.746471898]: wait-interpolation debug: start +[ INFO] [1732704600.749489182]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732704602.870174949]: wait-interpolation debug: start +[ INFO] [1732704602.870344553]: wait-interpolation debug: end +[ INFO] [1732704605.718719035]: wait-interpolation debug: start +[ INFO] [1732704605.719213448]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732704605.757759582]: wait-interpolation debug: start +[ INFO] [1732704610.776144505]: wait-interpolation debug: end +[ INFO] [1732704610.902379946]: wait-interpolation debug: start +[ERROR] [1732704613.493666161]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704613.493705309]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704613.495215353]: wait-interpolation debug: end +[ INFO] [1732704614.270012691]: wait-interpolation debug: start +[ INFO] [1732704615.270164443]: wait-interpolation debug: end +[ INFO] [1732704617.236593079]: wait-interpolation debug: start +[ INFO] [1732704617.236972004]: wait-interpolation debug: end +[ INFO] [1732704618.266166679]: wait-interpolation debug: start +[ INFO] [1732704618.273578062]: wait-interpolation debug: end +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +[ INFO] [1732704623.672707061]: wait-interpolation debug: start +[ INFO] [1732704624.672773242]: wait-interpolation debug: end +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +;; # :joint-angle(88.0754) violate max-angle(88.0) +[ INFO] [1732704624.716996706]: wait-interpolation debug: start +[ INFO] [1732704625.723556142]: wait-interpolation debug: end +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +[ INFO] [1732704625.773519967]: wait-interpolation debug: start +[ INFO] [1732704626.779102139]: wait-interpolation debug: end +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +[ INFO] [1732704626.821719261]: wait-interpolation debug: start +[ INFO] [1732704627.829159643]: wait-interpolation debug: end +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +[ INFO] [1732704627.876209308]: wait-interpolation debug: start +[ INFO] [1732704628.894225802]: wait-interpolation debug: end +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +[ INFO] [1732704628.943272153]: wait-interpolation debug: start +[ INFO] [1732704629.950382779]: wait-interpolation debug: end +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +[ INFO] [1732704629.993059873]: wait-interpolation debug: start +[ INFO] [1732704630.991145605]: wait-interpolation debug: end +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +[ INFO] [1732704631.037807914]: wait-interpolation debug: start +[ INFO] [1732704632.037931055]: wait-interpolation debug: end +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +[ INFO] [1732704632.081186680]: wait-interpolation debug: start +[ INFO] [1732704633.090754220]: wait-interpolation debug: end +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +[ INFO] [1732704633.133085815]: wait-interpolation debug: start +[ INFO] [1732704634.132486429]: wait-interpolation debug: end +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +[ INFO] [1732704634.178299122]: wait-interpolation debug: start +[ INFO] [1732704635.209092504]: wait-interpolation debug: end +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +;; # :joint-angle(88.06) violate max-angle(88.0) +[ INFO] [1732704635.262939253]: wait-interpolation debug: start +[ INFO] [1732704636.266644999]: wait-interpolation debug: end +;; # :joint-angle(88.06) violate max-angle(88.0) +[ INFO] [1732704638.390525650]: wait-interpolation debug: start +[ INFO] [1732704638.401844524]: wait-interpolation debug: end +[ INFO] [1732704641.238421270]: wait-interpolation debug: start +[ INFO] [1732704641.239125374]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732704641.279020421]: wait-interpolation debug: start +[ INFO] [1732704646.311696820]: wait-interpolation debug: end +[ INFO] [1732704646.385776395]: wait-interpolation debug: start +[ERROR] [1732704648.388451363]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704648.388515363]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704648.392362559]: wait-interpolation debug: end +[ INFO] [1732704648.826944833]: wait-interpolation debug: start + C-c C-cinterrupt13.B3-irteusgl$ load "main.l" +[ WARN] [1732704756.841464756]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732704756.841507582]: expected goal id 1732704756840545462_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_34 +[ WARN] [1732704756.841522810]: received goal id /battery_warning-83-1732704628.966 +[ WARN] [1732704762.721805502]: continuous joint (r_forearm_roll_joint) moves -181.804 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704762.729260230]: continuous joint (r_forearm_roll_joint) moves -181.804 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704762.729317993]: original trajectory command : +[ WARN] [1732704762.729341374]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732704762.729363458]: current angle vector : #f(166.852 1.81794 -13.0893 82.9127 -33.6939 88.4801 -104.779 237.113 -6.54072 33.4686 -42.4657 -95.3089 161.804 -66.2762 133.53 0.0 42.8986) +[ WARN] [1732704762.729377411]: new trajectory command : dvi = 2 +[ WARN] [1732704762.729405596]: : #f(108.426 30.909 30.4554 76.4563 -76.8469 54.2401 -67.3896 208.556 -33.2704 53.7343 -56.2329 -107.654 70.9021 -48.1381 156.765 0.0 21.4493) 500 +[ WARN] [1732704762.729430435]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732704762.729444678]: new trajectory command : +[ WARN] [1732704762.729472403]: : (#f(108.426 30.909 30.4554 76.4563 -76.8469 54.2401 -67.3896 208.556 -33.2704 53.7343 -56.2329 -107.654 70.9021 -48.1381 156.765 0.0 21.4493) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732704762.732009397]: wait-interpolation debug: start +[ERROR] [1732704771.815805428]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704771.815850668]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704771.819549205]: wait-interpolation debug: end +[ INFO] [1732704774.161845288]: wait-interpolation debug: start +[ERROR] [1732704775.756038463]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704775.756093658]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704775.760633131]: wait-interpolation debug: end +[ INFO] [1732704781.751598806]: wait-interpolation debug: start +[ INFO] [1732704781.762425416]: wait-interpolation debug: end +[ INFO] [1732704791.471460508]: wait-interpolation debug: start +[ INFO] [1732704791.471659564]: wait-interpolation debug: end +[ INFO] [1732704798.019803810]: wait-interpolation debug: start +[ INFO] [1732704799.054248788]: wait-interpolation debug: end +[ WARN] [1732704799.118428453]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704799.122070962]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704799.122233664]: original trajectory command : +[ WARN] [1732704799.122293609]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (1000) +[ WARN] [1732704799.122329087]: current angle vector : #f(50.0 17.8275 14.7726 46.824 -78.4543 6.11414 -34.739 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732704799.122342534]: new trajectory command : dvi = 2 +[ WARN] [1732704799.122390796]: : #f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732704799.122437925]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732704799.122453885]: new trajectory command : +[ WARN] [1732704799.122508984]: : (#f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (500 500) +[ INFO] [1732704799.127591564]: wait-interpolation debug: start +[ INFO] [1732704800.303803696]: wait-interpolation debug: end +[ WARN] [1732704800.451139103]: continuous joint (r_forearm_roll_joint) moves 187.258 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704800.457995246]: continuous joint (r_forearm_roll_joint) moves 187.258 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704800.458055250]: original trajectory command : +[ WARN] [1732704800.458101150]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2607 43.8807 31.2166 -95.0216 167.258 -43.814 77.0579 0.0 42.8986)) (500) +[ WARN] [1732704800.458146846]: current angle vector : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732704800.458178095]: new trajectory command : dvi = 2 +[ WARN] [1732704800.458235159]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8697 58.9404 -19.3917 -107.511 73.6289 -36.907 128.529 0.0 42.8986) 250 +[ WARN] [1732704800.458291579]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2607 43.8807 31.2166 -95.0216 167.258 -43.814 77.0579 0.0 42.8986) 250 +[ WARN] [1732704800.458322310]: new trajectory command : +[ WARN] [1732704800.458382848]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8697 58.9404 -19.3917 -107.511 73.6289 -36.907 128.529 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2607 43.8807 31.2166 -95.0216 167.258 -43.814 77.0579 0.0 42.8986)) (250 250) +[ INFO] [1732704800.463726329]: wait-interpolation debug: start +[ERROR] [1732704802.079280029]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704802.079343946]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704802.083267669]: wait-interpolation debug: end +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0021) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0852) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0956) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.092) violate max-angle(88.0) +;; # :joint-angle(88.092) violate max-angle(88.0) +;; # :joint-angle(88.0888) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0819) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +[ INFO] [1732704802.627715617]: wait-interpolation debug: start +[ INFO] [1732704803.809129240]: wait-interpolation debug: end +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +[ INFO] [1732704803.928806353]: wait-interpolation debug: start +[ INFO] [1732704804.932129995]: wait-interpolation debug: end +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +[ INFO] [1732704805.006237902]: wait-interpolation debug: start +[ INFO] [1732704806.029892549]: wait-interpolation debug: end +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +[ INFO] [1732704806.071399802]: wait-interpolation debug: start +[ INFO] [1732704807.071270879]: wait-interpolation debug: end +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +[ INFO] [1732704807.125499964]: wait-interpolation debug: start +[ INFO] [1732704808.128004848]: wait-interpolation debug: end +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +[ INFO] [1732704808.171591206]: wait-interpolation debug: start +[ INFO] [1732704809.172873330]: wait-interpolation debug: end +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +[ INFO] [1732704809.216888205]: wait-interpolation debug: start +[ INFO] [1732704810.219956723]: wait-interpolation debug: end +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +[ INFO] [1732704810.269998597]: wait-interpolation debug: start +[ INFO] [1732704811.308108071]: wait-interpolation debug: end +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +[ INFO] [1732704811.358868662]: wait-interpolation debug: start +[ INFO] [1732704812.362997418]: wait-interpolation debug: end +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +;; # :joint-angle(88.0784) violate max-angle(88.0) +[ INFO] [1732704812.440833040]: wait-interpolation debug: start +[ INFO] [1732704813.439191487]: wait-interpolation debug: end +;; # :joint-angle(88.0784) violate max-angle(88.0) +[ INFO] [1732704815.581439251]: wait-interpolation debug: start +[ INFO] [1732704815.581598401]: wait-interpolation debug: end +[ INFO] [1732704818.431629101]: wait-interpolation debug: start +[ INFO] [1732704818.432583382]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732704818.501139983]: wait-interpolation debug: start +[ INFO] [1732704823.506122797]: wait-interpolation debug: end +[ INFO] [1732704823.580756664]: wait-interpolation debug: start +[ERROR] [1732704837.959182737]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732704837.959224607]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732704837.960055556]: wait-interpolation debug: end +[ INFO] [1732704841.602624940]: wait-interpolation debug: start +[ INFO] [1732704842.611177004]: wait-interpolation debug: end +[ INFO] [1732704844.629430655]: wait-interpolation debug: start +[ INFO] [1732704844.629654855]: wait-interpolation debug: end +[ INFO] [1732704845.655656496]: wait-interpolation debug: start +[ INFO] [1732704845.661865949]: wait-interpolation debug: end +[ WARN] [1732704845.663731658]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732704845.663791614]: expected goal id 1732704845662559003_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_38 +[ WARN] [1732704845.663833529]: received goal id /battery_warning-84-1732704812.966 +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +[ INFO] [1732704851.046811496]: wait-interpolation debug: start +[ INFO] [1732704852.051413093]: wait-interpolation debug: end +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +;; # :joint-angle(88.0807) violate max-angle(88.0) +[ INFO] [1732704852.097118687]: wait-interpolation debug: start +[ INFO] [1732704853.103614554]: wait-interpolation debug: end +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +[ INFO] [1732704853.153245910]: wait-interpolation debug: start +[ INFO] [1732704854.176043145]: wait-interpolation debug: end +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +[ INFO] [1732704854.220798316]: wait-interpolation debug: start +[ INFO] [1732704855.222801302]: wait-interpolation debug: end +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +[ INFO] [1732704855.266424893]: wait-interpolation debug: start +[ INFO] [1732704856.266769916]: wait-interpolation debug: end +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +[ INFO] [1732704856.321146579]: wait-interpolation debug: start +[ INFO] [1732704857.318232207]: wait-interpolation debug: end +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +[ INFO] [1732704857.362097425]: wait-interpolation debug: start +[ INFO] [1732704858.367411922]: wait-interpolation debug: end +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +[ INFO] [1732704858.408553240]: wait-interpolation debug: start +[ INFO] [1732704859.438664646]: wait-interpolation debug: end +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +[ INFO] [1732704859.486773301]: wait-interpolation debug: start +[ INFO] [1732704860.489408500]: wait-interpolation debug: end +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +[ INFO] [1732704860.532257427]: wait-interpolation debug: start +[ INFO] [1732704861.538861547]: wait-interpolation debug: end +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +[ INFO] [1732704861.581426386]: wait-interpolation debug: start +[ INFO] [1732704862.580827515]: wait-interpolation debug: end +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +;; # :joint-angle(88.0558) violate max-angle(88.0) +[ INFO] [1732704862.622422252]: wait-interpolation debug: start +[ INFO] [1732704863.628099093]: wait-interpolation debug: end +;; # :joint-angle(88.0558) violate max-angle(88.0) +[ INFO] [1732704865.758645836]: wait-interpolation debug: start +[ INFO] [1732704865.760437189]: wait-interpolation debug: end +[ INFO] [1732704868.608471867]: wait-interpolation debug: start +[ INFO] [1732704868.609275395]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732704868.649267960]: wait-interpolation debug: start + C-c C-cinterrupt14.B4-irteusgl$ (send *ri* :stop-grasp) +(t t) +15.B4-irteusgl$ load "main.l" +[ WARN] [1732704988.862139722]: [/r_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732704988.862181778]: expected goal id 1732704988847826759_/pr2_eus_interface_1732703530848654340_74049_/r_gripper_controller/gripper_action_36 +[ WARN] [1732704988.862213845]: received goal id 1732704894059916263_/pr2_eus_interface_1732703530848654340_74049_/r_gripper_controller/gripper_action_35 +[ WARN] [1732704991.057790785]: continuous joint (r_forearm_roll_joint) moves -199.045 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704991.061383487]: continuous joint (r_forearm_roll_joint) moves -199.045 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732704991.061510415]: original trajectory command : +[ WARN] [1732704991.061569857]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732704991.061622901]: current angle vector : #f(237.178 4.52429 8.41601 82.8237 -41.1163 100.919 -88.3382 233.778 -30.6677 59.8345 -34.7846 -83.0633 179.045 -18.6748 107.564 0.0 42.8986) +[ WARN] [1732704991.061666061]: new trajectory command : dvi = 2 +[ WARN] [1732704991.061741451]: : #f(143.589 32.2621 41.208 76.4119 -80.5581 60.4596 -59.1691 206.889 -45.3338 66.9173 -52.3923 -101.532 79.5225 -24.3374 143.782 0.0 21.4493) 500 +[ WARN] [1732704991.061779054]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732704991.061793538]: new trajectory command : +[ WARN] [1732704991.061824998]: : (#f(143.589 32.2621 41.208 76.4119 -80.5581 60.4596 -59.1691 206.889 -45.3338 66.9173 -52.3923 -101.532 79.5225 -24.3374 143.782 0.0 21.4493) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732704991.073173395]: wait-interpolation debug: start +[ERROR] [1732705005.560068655]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732705005.560121796]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732705005.560792004]: wait-interpolation debug: end +[ INFO] [1732705009.095800070]: wait-interpolation debug: start +[ERROR] [1732705010.689171311]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732705010.689232421]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732705010.690567676]: wait-interpolation debug: end +[ WARN] [1732705010.855643446]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732705010.855694498]: expected goal id 1732705010854637621_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_40 +[ WARN] [1732705010.855729359]: received goal id /battery_warning-85-1732704992.966 +[ WARN] [1732705010.856001302]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732705010.856031994]: expected goal id 1732705010854637621_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_40 +[ WARN] [1732705010.856062703]: received goal id 1732705000449842754_/tweet_client_warning_473265_robotsound_jp_69 +[ WARN] [1732705010.856454750]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732705010.856493043]: expected goal id 1732705010854637621_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_40 +[ WARN] [1732705010.856534962]: received goal id 1732705001453728487_/tweet_client_warning_473265_robotsound_jp_70 +[ WARN] [1732705010.856736197]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732705010.856770537]: expected goal id 1732705010854637621_/pr2_eus_interface_1732703530848654340_74049_robotsound_jp_40 +[ WARN] [1732705010.856801069]: received goal id 1732705002488341444_/tweet_client_warning_473265_robotsound_jp_71 +[ INFO] [1732705016.713619547]: wait-interpolation debug: start +[ INFO] [1732705016.716765365]: wait-interpolation debug: end +[ INFO] [1732705026.461665401]: wait-interpolation debug: start +[ INFO] [1732705026.462360460]: wait-interpolation debug: end +[ INFO] [1732705032.987106430]: wait-interpolation debug: start +[ INFO] [1732705033.984935877]: wait-interpolation debug: end +[ WARN] [1732705034.038675438]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705034.041766609]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705034.041924481]: original trajectory command : +[ WARN] [1732705034.041960257]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (1000) +[ WARN] [1732705034.041997788]: current angle vector : #f(50.0 17.8275 14.7726 46.824 -78.4543 6.11414 -34.739 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732705034.042029438]: new trajectory command : dvi = 2 +[ WARN] [1732705034.042091323]: : #f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732705034.042139397]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732705034.042169033]: new trajectory command : +[ WARN] [1732705034.042225477]: : (#f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (500 500) +[ INFO] [1732705034.047419913]: wait-interpolation debug: start +[ INFO] [1732705035.220878083]: wait-interpolation debug: end +[ WARN] [1732705035.382699904]: continuous joint (r_forearm_roll_joint) moves 187.256 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705035.390038608]: continuous joint (r_forearm_roll_joint) moves 187.256 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705035.390103346]: original trajectory command : +[ WARN] [1732705035.390151330]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2607 43.881 31.2148 -95.0211 167.256 -43.8137 77.0607 0.0 42.8986)) (500) +[ WARN] [1732705035.390202995]: current angle vector : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732705035.390231698]: new trajectory command : dvi = 2 +[ WARN] [1732705035.390294572]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8696 58.9405 -19.3926 -107.511 73.6279 -36.9068 128.53 0.0 42.8986) 250 +[ WARN] [1732705035.390347084]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2607 43.881 31.2148 -95.0211 167.256 -43.8137 77.0607 0.0 42.8986) 250 +[ WARN] [1732705035.390372174]: new trajectory command : +[ WARN] [1732705035.390437467]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8696 58.9405 -19.3926 -107.511 73.6279 -36.9068 128.53 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2607 43.881 31.2148 -95.0211 167.256 -43.8137 77.0607 0.0 42.8986)) (250 250) +[ INFO] [1732705035.393000212]: wait-interpolation debug: start +[ERROR] [1732705036.996528904]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732705036.996613593]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732705037.006865556]: wait-interpolation debug: end +[ INFO] [1732705037.400086975]: wait-interpolation debug: start +[ INFO] [1732705038.698684621]: wait-interpolation debug: end +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +[ INFO] [1732705038.791185341]: wait-interpolation debug: start +[ INFO] [1732705039.802510319]: wait-interpolation debug: end +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +[ INFO] [1732705039.892890819]: wait-interpolation debug: start +[ INFO] [1732705040.895309685]: wait-interpolation debug: end +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +[ INFO] [1732705040.937725647]: wait-interpolation debug: start +[ INFO] [1732705041.944797840]: wait-interpolation debug: end +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +[ INFO] [1732705041.991205426]: wait-interpolation debug: start +[ INFO] [1732705042.989919995]: wait-interpolation debug: end +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +[ INFO] [1732705043.032934634]: wait-interpolation debug: start +[ INFO] [1732705044.032334400]: wait-interpolation debug: end +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +[ INFO] [1732705044.075905441]: wait-interpolation debug: start +[ INFO] [1732705045.087955203]: wait-interpolation debug: end +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +[ INFO] [1732705045.131863591]: wait-interpolation debug: start +[ INFO] [1732705046.125206584]: wait-interpolation debug: end +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +[ INFO] [1732705046.170438367]: wait-interpolation debug: start +[ INFO] [1732705047.177674664]: wait-interpolation debug: end +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +;; # :joint-angle(88.0778) violate max-angle(88.0) +[ INFO] [1732705047.228189555]: wait-interpolation debug: start +[ INFO] [1732705048.229120789]: wait-interpolation debug: end +;; # :joint-angle(88.0778) violate max-angle(88.0) +[ INFO] [1732705050.471990399]: wait-interpolation debug: start +[ INFO] [1732705050.472343044]: wait-interpolation debug: end +[ INFO] [1732705053.321189075]: wait-interpolation debug: start +[ INFO] [1732705053.322330900]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732705053.370494514]: wait-interpolation debug: start +[ INFO] [1732705058.387055677]: wait-interpolation debug: end +[ INFO] [1732705058.460004573]: wait-interpolation debug: start +[ERROR] [1732705072.838115120]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732705072.838164481]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732705072.841786640]: wait-interpolation debug: end +[ INFO] [1732705076.516809335]: wait-interpolation debug: start +[ INFO] [1732705077.519615182]: wait-interpolation debug: end +[ INFO] [1732705079.510603482]: wait-interpolation debug: start +[ INFO] [1732705079.518212305]: wait-interpolation debug: end +[ INFO] [1732705080.546077467]: wait-interpolation debug: start +[ INFO] [1732705080.552313432]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705086.069302646]: wait-interpolation debug: start +[ INFO] [1732705087.068553291]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705087.118184598]: wait-interpolation debug: start +[ INFO] [1732705088.120831756]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705088.163618152]: wait-interpolation debug: start +[ INFO] [1732705089.191804803]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705089.243597465]: wait-interpolation debug: start +[ INFO] [1732705090.244082435]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705090.287556206]: wait-interpolation debug: start +[ INFO] [1732705091.306064147]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705091.357847095]: wait-interpolation debug: start +[ INFO] [1732705092.358305712]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705092.401554511]: wait-interpolation debug: start +[ INFO] [1732705093.400716495]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705093.440752763]: wait-interpolation debug: start +[ INFO] [1732705094.453401415]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705094.527174832]: wait-interpolation debug: start +[ INFO] [1732705095.527226442]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705095.573877208]: wait-interpolation debug: start +[ INFO] [1732705096.571597789]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705096.614825686]: wait-interpolation debug: start +[ INFO] [1732705107.156725952]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705107.256488980]: wait-interpolation debug: start +[ INFO] [1732705108.267871680]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705110.462931775]: wait-interpolation debug: start +[ INFO] [1732705110.464587053]: wait-interpolation debug: end +[ INFO] [1732705113.300521348]: wait-interpolation debug: start +[ INFO] [1732705113.301555444]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732705113.340068391]: wait-interpolation debug: start + C-c C-cinterrupt16.B5-irteusgl$ C-c C-cinterrupt16.B6-irteusgl$ C-c C-cinterrupt16.B7-irteusgl$ C-c C-cinterrupt16.B8-irteusgl$ C-c C-cinterrupt16.B9-irteusgl$ exit +[ INFO] [1732705318.980374431]: cell* ROSEUS_EXIT(context*, int, cell**) +[ INFO] [1732705318.980555926]: exiting roseus 0 +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rosssetmaster +rosssetmaster: command not found +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rossetmaster +set ROS_MASTER_URI to http://localhost:11311 +mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ roseus +configuring by "/opt/ros/noetic/share/euslisp/jskeus/eus//lib/eusrt.l" +;; readmacro ;; object ;; packsym ;; common ;; constants ;; stream ;; string ;; loader ;; pprint ;; process ;; hashtab ;; array ;; mathtran ;; eusdebug ;; eusforeign ;; extnum ;; coordinates ;; tty ;; history ;; toplevel ;; trans ;; comp ;; builtins ;; par ;; intersection ;; geoclasses ;; geopack ;; geobody ;; primt ;; compose ;; polygon ;; viewing ;; viewport ;; viewsurface ;; hid ;; shadow ;; bodyrel ;; dda ;; helpsub ;; eushelp ;; xforeign ;; Xdecl ;; Xgraphics ;; Xcolor ;; Xeus ;; Xevent ;; Xpanel ;; Xitem ;; Xtext ;; Xmenu ;; Xscroll ;; Xcanvas ;; Xtop ;; Xapplwin +connected to Xserver DISPLAY=:0 +X events are being asynchronously monitored. +;; pixword ;; RGBHLS ;; convolve ;; piximage ;; pbmfile ;; image_correlation ;; oglforeign ;; gldecl ;; glconst ;; glforeign ;; gluconst ;; gluforeign ;; glxconst ;; glxforeign ;; eglforeign ;; eglfunc ;; glutil ;; gltexture ;; glprim ;; gleus ;; glview ;; toiv-undefined ;; fstringdouble irtmath irtutil irtc irtgeoc irtgraph gnuplotlib ___time ___pgsql irtgeo euspqp pqp irtscene irtmodel irtdyna irtrobot irtsensor irtbvh irtcollada irtstl irtwrl irtpointcloud eusbullet bullet irtcollision irtx eusjpeg euspng png irtimage irtglrgb +;; extending gcstack 0x55a69c978680[16374] --> 0x55a69ce08c90[32748] top=3d4b +irtgl irtglc irtviewer +EusLisp 9.29( 1.2.5) for Linux64 created on ip-10-0-1-5(Tue Jun 20 10:34:21 PST 2023) +roseus ;; loading roseus("1.7.5") on euslisp((9.29 ip-10-0-1-5 Tue Jun 20 10:34:21 PST 2023 1.2.5)) +eustf roseus_c_util 1.irteusgl$ load "main.l" +;; roseus_resume is disabled. + +;; extending gcstack 0x55a69ce08c90[32738] --> 0x55a69e9266e0[65476] top=7ed2 +[ WARN] [1732705344.211431521]: [l_arm_controller/follow_joint_trajectory] action server is not found +[ WARN] [1732705344.214936597]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732705344.215152218]: # is not respond, pr2-interface is disabled +[ WARN] [1732705344.215237296]: Starting 'Kinematics Simulator' +[ WARN] [1732705344.215293804]: (If you do not intend to start Kinematics Simulator, make sure that you can run 'rostopic info /l_arm_controller/follow_joint_trajectory/goal' and 'rostopic info /l_arm_controller/follow_joint_trajectory/cancel' and check whether Subscribers exists. If there is no Subscribers, please check joint_trajectory_action node.) +[ WARN] [1732705344.215419897]: (Please also check 'rostopic info /l_arm_controller/follow_joint_trajectory/feedback' and 'rostopic info /l_arm_controller/follow_joint_trajectory/result' and check whether Publishers exists. If there is no Publishers, please check joint_trajectory_action node.) +[ WARN] [1732705344.215532111]: (If joint_trajectory_action node already exists, you might have a network problem. Please make sure that you can run 'rosnode ping JOINT_TRAJECTORY_ACTION_SERVER_NODE_NAME' and 'rosnode ping /pr2_eus_interface_1732705339688653773') +current *timer-job* is ((lambda nil (send # :robot-interface-simulation-callback)) lisp::count-up-timer) +[ WARN] [1732705347.528305088]: [/base_controller/follow_joint_trajectory] action server is not found +[ WARN] [1732705347.528389728]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732705347.528423343]: move-base-trajectory-action is not found +[ WARN] [1732705347.559116227]: # is not respond, pr2-interface is disabled +;; (make-irtviewer) executed +[ WARN] [1732705348.745963281]: [robotsound_jp] action server is not found +[ WARN] [1732705348.746062416]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732705348.746108483]: action server /robotsound_jp not found. +[ WARN] [1732705350.472564656]: topic /robotsound_jp/goal already advertised +[ WARN] [1732705350.472607831]: topic /robotsound_jp/cancel already advertised +[ WARN] [1732705351.579634400]: [robotsound_jp] action server is not found +[ WARN] [1732705351.579695302]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732705351.579723273]: action server /robotsound_jp not found. +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +[ WARN] [1732705354.587867335]: topic /robotsound_jp/goal already advertised +[ WARN] [1732705354.587945915]: topic /robotsound_jp/cancel already advertised +[ WARN] [1732705355.697883792]: [robotsound_jp] action server is not found +[ WARN] [1732705355.698025203]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732705355.698087496]: action server /robotsound_jp not found. +[ WARN] [1732705355.712252934]: topic /robotsound_jp/goal already advertised +[ WARN] [1732705355.712313946]: topic /robotsound_jp/cancel already advertised +[ WARN] [1732705356.816792157]: [robotsound_jp] action server is not found +[ WARN] [1732705356.816962657]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732705356.817026715]: action server /robotsound_jp not found. +[ WARN] [1732705359.258397253]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705359.628300332]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705359.628368895]: continuous joint (r_forearm_roll_joint) moves 187.158 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +[ WARN] [1732705360.257289329]: continuous joint (l_forearm_roll_joint) moves 279.035 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705360.257425307]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705360.888749233]: continuous joint (l_forearm_roll_joint) moves 358.252 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705360.888850965]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705361.496108217]: continuous joint (l_forearm_roll_joint) moves 358.422 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705361.496180247]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705362.069529167]: continuous joint (l_forearm_roll_joint) moves 358.577 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705362.069618018]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705362.668857714]: continuous joint (l_forearm_roll_joint) moves 358.718 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705362.668946783]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705363.279399907]: continuous joint (l_forearm_roll_joint) moves 358.846 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705363.279514022]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705363.871442489]: continuous joint (l_forearm_roll_joint) moves 358.963 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705363.871516953]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705364.468870472]: continuous joint (l_forearm_roll_joint) moves 359.069 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705364.468989485]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705365.111052658]: continuous joint (l_forearm_roll_joint) moves 359.165 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705365.111128026]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705365.670491863]: continuous joint (l_forearm_roll_joint) moves 359.253 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705365.670603975]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +remaining 280 +[ WARN] [1732705367.307244670]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705367.307359247]: continuous joint (r_forearm_roll_joint) moves 392.218 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705369.023004155]: continuous joint (l_forearm_roll_joint) moves 365.653 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705369.023124067]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705373.803405452]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705373.803494267]: continuous joint (r_forearm_roll_joint) moves 320.767 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +[ WARN] [1732705375.411506762]: topic /robotsound_jp/goal already advertised +[ WARN] [1732705375.411556089]: topic /robotsound_jp/cancel already advertised +[ WARN] [1732705376.516825364]: [robotsound_jp] action server is not found +[ WARN] [1732705376.516880256]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732705376.516902268]: action server /robotsound_jp not found. +[ WARN] [1732705377.572708449]: continuous joint (l_forearm_roll_joint) moves 361.109 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705377.572780250]: continuous joint (r_forearm_roll_joint) moves 365.025 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(-8.59437) violate max-angle(-8.59437) +;; # :joint-angle(-8.59437) violate max-angle(-8.59437) +[ WARN] [1732705378.168032627]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705378.168132879]: continuous joint (r_forearm_roll_joint) moves 333.219 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(-8.59437) violate max-angle(-8.59437) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(-8.59437) violate max-angle(-8.59437) +;; # :joint-angle(-8.59437) violate max-angle(-8.59437) +[ WARN] [1732705378.792309242]: continuous joint (l_forearm_roll_joint) moves 365.515 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705378.792377566]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(-8.59437) violate max-angle(-8.59437) +[ WARN] [1732705379.383569591]: continuous joint (l_forearm_roll_joint) moves 359.023 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705379.383649925]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705379.988238276]: continuous joint (l_forearm_roll_joint) moves 359.079 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705379.988435832]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705380.592923583]: continuous joint (l_forearm_roll_joint) moves 359.131 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705380.593017734]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705381.238780767]: continuous joint (l_forearm_roll_joint) moves 359.181 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705381.238927255]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705381.803146255]: continuous joint (l_forearm_roll_joint) moves 359.228 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705381.803241536]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705382.406217064]: continuous joint (l_forearm_roll_joint) moves 359.272 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705382.406289202]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705383.002002950]: continuous joint (l_forearm_roll_joint) moves 359.314 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705383.002120907]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705383.596825122]: continuous joint (l_forearm_roll_joint) moves 359.353 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705383.596893882]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705384.215352660]: continuous joint (l_forearm_roll_joint) moves 359.391 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705384.215431410]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +remaining 280 +[ WARN] [1732705385.863259647]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705385.863380369]: continuous joint (r_forearm_roll_joint) moves 400.517 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705387.616268034]: continuous joint (l_forearm_roll_joint) moves 359.204 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705387.616402478]: continuous joint (r_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705388.325889927]: continuous joint (l_forearm_roll_joint) moves 360.0 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705388.325979566]: continuous joint (r_forearm_roll_joint) moves 334.069 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +;; # :joint-angle(45.0) violate max-angle(31.3981) +[ WARN] [1732705389.924307847]: topic /robotsound_jp/goal already advertised +[ WARN] [1732705389.924493403]: topic /robotsound_jp/cancel already advertised +[ WARN] [1732705391.039380193]: [robotsound_jp] action server is not found +[ WARN] [1732705391.039683288]: goal=0, cancel=0, feedback=0, result=0 +[ WARN] [1732705391.039871080]: action server /robotsound_jp not found. + C-c C-cinterrupt2.B1-irteusgl$ exit +[ INFO] [1732705395.623946046]: cell* ROSEUS_EXIT(context*, int, cell**) +[ INFO] [1732705395.623982885]: exiting roseus 0 +mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rossetamaster pr1040 +rossetamaster: command not found +mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ rossetmaster pr1040 +set ROS_MASTER_URI to http://pr1040:11311 +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ load "main.l" + +Command 'load' not found, did you mean: + + command 'tload' from deb procps (2:3.3.16-1ubuntu2.4) + command 'nload' from deb nload (0.7.4-2build3) + command 'xload' from deb x11-apps (7.7+8) + +Try: sudo apt install + +[http://pr1040:11311][133.11.216.48] mech-user@ki00119:~/semi_ws/jsk_demos/jsk_2024_10_semi/pr2_surgery$ roseus +configuring by "/opt/ros/noetic/share/euslisp/jskeus/eus//lib/eusrt.l" +;; readmacro ;; object ;; packsym ;; common ;; constants ;; stream ;; string ;; loader ;; pprint ;; process ;; hashtab ;; array ;; mathtran ;; eusdebug ;; eusforeign ;; extnum ;; coordinates ;; tty ;; history ;; toplevel ;; trans ;; comp ;; builtins ;; par ;; intersection ;; geoclasses ;; geopack ;; geobody ;; primt ;; compose ;; polygon ;; viewing ;; viewport ;; viewsurface ;; hid ;; shadow ;; bodyrel ;; dda ;; helpsub ;; eushelp ;; xforeign ;; Xdecl ;; Xgraphics ;; Xcolor ;; Xeus ;; Xevent ;; Xpanel ;; Xitem ;; Xtext ;; Xmenu ;; Xscroll ;; Xcanvas ;; Xtop ;; Xapplwin +connected to Xserver DISPLAY=:0 +X events are being asynchronously monitored. +;; pixword ;; RGBHLS ;; convolve ;; piximage ;; pbmfile ;; image_correlation ;; oglforeign ;; gldecl ;; glconst ;; glforeign ;; gluconst ;; gluforeign ;; glxconst ;; glxforeign ;; eglforeign ;; eglfunc ;; glutil ;; gltexture ;; glprim ;; gleus ;; glview ;; toiv-undefined ;; fstringdouble irtmath irtutil irtc irtgeoc irtgraph gnuplotlib ___time ___pgsql irtgeo euspqp pqp irtscene irtmodel irtdyna irtrobot irtsensor irtbvh irtcollada irtstl irtwrl irtpointcloud eusbullet bullet irtcollision irtx eusjpeg euspng png irtimage irtglrgb +;; extending gcstack 0x55a527fba680[16374] --> 0x55a52844ac90[32748] top=3d4b +irtgl irtglc irtviewer +EusLisp 9.29( 1.2.5) for Linux64 created on ip-10-0-1-5(Tue Jun 20 10:34:21 PST 2023) +roseus ;; loading roseus("1.7.5") on euslisp((9.29 ip-10-0-1-5 Tue Jun 20 10:34:21 PST 2023 1.2.5)) +eustf roseus_c_util 1.irteusgl$ load "main.l" +;; roseus_resume is disabled. + +;; extending gcstack 0x55a52844ac90[32738] --> 0x55a529f686e0[65476] top=7ed2 +;; (make-irtviewer) executed +[ WARN] [1732705428.659142896]: continuous joint (r_forearm_roll_joint) moves -199.042 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705428.671268104]: continuous joint (r_forearm_roll_joint) moves -199.042 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705428.671328119]: original trajectory command : +[ WARN] [1732705428.671349819]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732705428.671375406]: current angle vector : #f(237.178 4.52538 8.41599 82.824 -41.1171 100.919 -88.3381 233.778 -30.6668 59.8348 -34.7846 -83.0638 179.042 -18.6753 107.566 0.0 42.8986) +[ WARN] [1732705428.671388421]: new trajectory command : dvi = 2 +[ WARN] [1732705428.671417315]: : #f(143.589 32.2627 41.208 76.412 -80.5586 60.4595 -59.1691 206.889 -45.3334 66.9174 -52.3923 -101.532 79.521 -24.3377 143.783 0.0 21.4493) 500 +[ WARN] [1732705428.671445841]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 500 +[ WARN] [1732705428.671458341]: new trajectory command : +[ WARN] [1732705428.671484597]: : (#f(143.589 32.2627 41.208 76.412 -80.5586 60.4595 -59.1691 206.889 -45.3334 66.9174 -52.3923 -101.532 79.521 -24.3377 143.783 0.0 21.4493) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (500 500) +[ INFO] [1732705428.677055732]: wait-interpolation debug: start +[ERROR] [1732705443.159221771]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732705443.159260350]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732705443.159981981]: wait-interpolation debug: end +[ INFO] [1732705446.741269229]: wait-interpolation debug: start +[ERROR] [1732705448.338654613]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732705448.338713007]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732705448.339367226]: wait-interpolation debug: end +[ INFO] [1732705454.398366293]: wait-interpolation debug: start +[ INFO] [1732705454.406893248]: wait-interpolation debug: end +[ INFO] [1732705464.142230630]: wait-interpolation debug: start +[ INFO] [1732705464.142382736]: wait-interpolation debug: end +[ INFO] [1732705470.691112868]: wait-interpolation debug: start +[ INFO] [1732705471.691010920]: wait-interpolation debug: end +[ WARN] [1732705471.748988861]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705471.753967685]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705471.754089094]: original trajectory command : +[ WARN] [1732705471.754137082]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (1000) +[ WARN] [1732705471.754185375]: current angle vector : #f(50.0 17.8275 14.7726 46.824 -78.4543 6.11414 -34.739 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732705471.754215689]: new trajectory command : dvi = 2 +[ WARN] [1732705471.754274156]: : #f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732705471.754324459]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732705471.754356570]: new trajectory command : +[ WARN] [1732705471.754420898]: : (#f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (500 500) +[ INFO] [1732705471.760640077]: wait-interpolation debug: start +[ INFO] [1732705472.940537355]: wait-interpolation debug: end +[ WARN] [1732705473.082064732]: continuous joint (r_forearm_roll_joint) moves 187.257 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705473.087386806]: continuous joint (r_forearm_roll_joint) moves 187.257 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705473.087443159]: original trajectory command : +[ WARN] [1732705473.087486191]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2607 43.8809 31.2156 -95.0214 167.257 -43.8138 77.0594 0.0 42.8986)) (500) +[ WARN] [1732705473.087540734]: current angle vector : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732705473.087563705]: new trajectory command : dvi = 2 +[ WARN] [1732705473.087593004]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8696 58.9404 -19.3922 -107.511 73.6284 -36.9069 128.53 0.0 42.8986) 250 +[ WARN] [1732705473.087642720]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2607 43.8809 31.2156 -95.0214 167.257 -43.8138 77.0594 0.0 42.8986) 250 +[ WARN] [1732705473.087671250]: new trajectory command : +[ WARN] [1732705473.087701361]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8696 58.9404 -19.3922 -107.511 73.6284 -36.9069 128.53 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2607 43.8809 31.2156 -95.0214 167.257 -43.8138 77.0594 0.0 42.8986)) (250 250) +[ INFO] [1732705473.090903289]: wait-interpolation debug: start +[ERROR] [1732705474.693962456]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732705474.694002443]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732705474.696471469]: wait-interpolation debug: end +[ INFO] [1732705475.078006567]: wait-interpolation debug: start +[ INFO] [1732705476.397040373]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705476.442942218]: wait-interpolation debug: start +[ INFO] [1732705477.447256289]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705477.490841405]: wait-interpolation debug: start +[ INFO] [1732705478.491552435]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705478.555707807]: wait-interpolation debug: start +[ INFO] [1732705479.559335720]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705479.610317668]: wait-interpolation debug: start +[ INFO] [1732705480.631533888]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705480.680736047]: wait-interpolation debug: start +[ INFO] [1732705481.696387565]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705481.779093110]: wait-interpolation debug: start +[ INFO] [1732705482.807451532]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705482.850762996]: wait-interpolation debug: start +[ INFO] [1732705483.899131360]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705483.943056732]: wait-interpolation debug: start +[ INFO] [1732705484.949161283]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705485.042898907]: wait-interpolation debug: start +[ INFO] [1732705486.038091964]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705488.262204897]: wait-interpolation debug: start +[ INFO] [1732705488.265874521]: wait-interpolation debug: end +[ INFO] [1732705491.101927406]: wait-interpolation debug: start +[ INFO] [1732705491.102144254]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732705491.150828899]: wait-interpolation debug: start +[ INFO] [1732705496.151876134]: wait-interpolation debug: end +[ INFO] [1732705496.222820853]: wait-interpolation debug: start +[ERROR] [1732705510.605951267]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732705510.606016315]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732705510.609822876]: wait-interpolation debug: end +[ INFO] [1732705514.234501663]: wait-interpolation debug: start +[ INFO] [1732705515.236230872]: wait-interpolation debug: end +[ INFO] [1732705517.225176718]: wait-interpolation debug: start +[ INFO] [1732705517.225464904]: wait-interpolation debug: end +[ INFO] [1732705518.294579068]: wait-interpolation debug: start +[ INFO] [1732705518.297939634]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732705523.761954594]: wait-interpolation debug: start +[ INFO] [1732705524.769214405]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732705524.819260288]: wait-interpolation debug: start +[ INFO] [1732705525.821892532]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732705525.862038795]: wait-interpolation debug: start +[ INFO] [1732705526.869745249]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732705526.911262007]: wait-interpolation debug: start +[ INFO] [1732705527.908962208]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732705527.967447700]: wait-interpolation debug: start +[ INFO] [1732705528.971579435]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732705529.012380255]: wait-interpolation debug: start +[ INFO] [1732705530.018992522]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732705530.062724748]: wait-interpolation debug: start +[ INFO] [1732705531.066808132]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732705531.108484606]: wait-interpolation debug: start +[ INFO] [1732705532.112938659]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732705532.159247318]: wait-interpolation debug: start +[ INFO] [1732705533.152711213]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732705533.196071418]: wait-interpolation debug: start +[ INFO] [1732705534.205462114]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732705534.245901878]: wait-interpolation debug: start +[ INFO] [1732705535.278914618]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732705535.320515590]: wait-interpolation debug: start +[ INFO] [1732705536.333415473]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732705538.528284823]: wait-interpolation debug: start +[ INFO] [1732705538.529667928]: wait-interpolation debug: end +[ INFO] [1732705541.379842450]: wait-interpolation debug: start +[ INFO] [1732705541.382706745]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732705541.429589618]: wait-interpolation debug: start +[ INFO] [1732705546.438035706]: wait-interpolation debug: end +[ INFO] [1732705546.518887551]: wait-interpolation debug: start +[ERROR] [1732705548.513627101]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732705548.513667373]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732705548.518158472]: wait-interpolation debug: end +[ INFO] [1732705549.087223538]: wait-interpolation debug: start +[ INFO] [1732705550.088480098]: wait-interpolation debug: end +[ INFO] [1732705552.056200645]: wait-interpolation debug: start +[ INFO] [1732705552.057034922]: wait-interpolation debug: end +[ INFO] [1732705553.075615775]: wait-interpolation debug: start +[ INFO] [1732705553.087630070]: wait-interpolation debug: end +[ WARN] [1732705553.091687366]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732705553.091770287]: expected goal id 1732705553089156642_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_5 +[ WARN] [1732705553.091803995]: received goal id /battery_warning-88-1732705540.966 +[ INFO] [1732705553.075615775]: wait-interpolation debug: start C-c C-cinterrupt2.B1-irteusgl$ C-c C-cinterrupt2.B2-irteusgl$ load "main.l" +[ WARN] [1732705721.421896725]: [/r_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732705721.421942016]: expected goal id 1732705721413297913_/pr2_eus_interface_1732705419350276377_79054_/r_gripper_controller/gripper_action_7 +[ WARN] [1732705721.421964275]: received goal id 1732705553057619237_/pr2_eus_interface_1732705419350276377_79054_/r_gripper_controller/gripper_action_6 +[ INFO] [1732705723.630913463]: wait-interpolation debug: start +[ERROR] [1732705739.888282694]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732705739.888343715]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732705739.890978528]: wait-interpolation debug: end +[ INFO] [1732705744.538805659]: wait-interpolation debug: start +[ERROR] [1732705746.133218857]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732705746.133259985]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732705746.137847263]: wait-interpolation debug: end +[ WARN] [1732705746.198274340]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732705746.198315178]: expected goal id 1732705746197379883_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_7 +[ WARN] [1732705746.198330877]: received goal id /battery_warning-89-1732705724.966 + C-c C-cinterrupt3.B3-irteusgl$ load "main.l" +[ INFO] [1732705828.642144602]: wait-interpolation debug: start +[ERROR] [1732705830.239605076]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732705830.239659507]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732705830.240109739]: wait-interpolation debug: end +[ INFO] [1732705830.496571049]: wait-interpolation debug: start +[ERROR] [1732705832.114383935]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732705832.114437728]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732705832.118758316]: wait-interpolation debug: end +[ INFO] [1732705837.987146031]: wait-interpolation debug: start +[ INFO] [1732705837.987282748]: wait-interpolation debug: end +[ INFO] [1732705847.751291762]: wait-interpolation debug: start +[ INFO] [1732705847.752873500]: wait-interpolation debug: end +[ INFO] [1732705854.310910379]: wait-interpolation debug: start +[ INFO] [1732705855.332701408]: wait-interpolation debug: end +[ WARN] [1732705855.377670539]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705855.380851716]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705855.380930694]: original trajectory command : +[ WARN] [1732705855.380959204]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (1000) +[ WARN] [1732705855.380982482]: current angle vector : #f(50.0 17.8275 14.7726 46.824 -78.4543 6.11414 -34.739 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732705855.380995024]: new trajectory command : dvi = 2 +[ WARN] [1732705855.381025037]: : #f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732705855.381050463]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732705855.381065028]: new trajectory command : +[ WARN] [1732705855.381094422]: : (#f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (500 500) +[ INFO] [1732705855.385489735]: wait-interpolation debug: start +[ INFO] [1732705856.554115086]: wait-interpolation debug: end +[ WARN] [1732705856.712047881]: continuous joint (r_forearm_roll_joint) moves 187.256 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705856.719057490]: continuous joint (r_forearm_roll_joint) moves 187.256 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732705856.719147534]: original trajectory command : +[ WARN] [1732705856.719197811]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2607 43.8809 31.2153 -95.0213 167.256 -43.8138 77.06 0.0 42.8986)) (500) +[ WARN] [1732705856.719242899]: current angle vector : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732705856.719272857]: new trajectory command : dvi = 2 +[ WARN] [1732705856.719328636]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8696 58.9405 -19.3924 -107.511 73.6282 -36.9069 128.53 0.0 42.8986) 250 +[ WARN] [1732705856.719384157]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2607 43.8809 31.2153 -95.0213 167.256 -43.8138 77.06 0.0 42.8986) 250 +[ WARN] [1732705856.719418048]: new trajectory command : +[ WARN] [1732705856.719478823]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8696 58.9405 -19.3924 -107.511 73.6282 -36.9069 128.53 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2607 43.8809 31.2153 -95.0213 167.256 -43.8138 77.06 0.0 42.8986)) (250 250) +[ INFO] [1732705856.729852487]: wait-interpolation debug: start +[ERROR] [1732705858.327904876]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732705858.327954911]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732705858.330114340]: wait-interpolation debug: end +;; # :joint-angle(88.0546) violate max-angle(88.0) +;; # :joint-angle(88.0546) violate max-angle(88.0) +;; # :joint-angle(88.0546) violate max-angle(88.0) +;; # :joint-angle(88.0546) violate max-angle(88.0) +[ INFO] [1732705858.801503431]: wait-interpolation debug: start +[ INFO] [1732705860.046919992]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732705860.123071185]: wait-interpolation debug: start +[ INFO] [1732705861.142210775]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732705861.184850551]: wait-interpolation debug: start +[ INFO] [1732705862.182176284]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732705862.225229120]: wait-interpolation debug: start +[ INFO] [1732705863.221742427]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732705863.266609502]: wait-interpolation debug: start +[ INFO] [1732705864.269185453]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732705864.358596923]: wait-interpolation debug: start +[ INFO] [1732705865.359604307]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732705865.438341415]: wait-interpolation debug: start +[ INFO] [1732705866.440754318]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732705866.482096100]: wait-interpolation debug: start +[ INFO] [1732705867.478006889]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732705867.526712483]: wait-interpolation debug: start +[ INFO] [1732705868.519902506]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732705868.568772643]: wait-interpolation debug: start +[ INFO] [1732705869.569436976]: wait-interpolation debug: end +;; # :joint-angle(88.0781) violate max-angle(88.0) +[ INFO] [1732705871.799817230]: wait-interpolation debug: start +[ INFO] [1732705871.800773729]: wait-interpolation debug: end +[ INFO] [1732705874.651245082]: wait-interpolation debug: start +[ INFO] [1732705874.651395601]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732705874.697734534]: wait-interpolation debug: start +[ INFO] [1732705879.703544810]: wait-interpolation debug: end +[ INFO] [1732705879.823049229]: wait-interpolation debug: start +[ERROR] [1732705894.204066145]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732705894.204105079]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732705894.205227216]: wait-interpolation debug: end +[ INFO] [1732705897.831628198]: wait-interpolation debug: start +[ INFO] [1732705898.837801490]: wait-interpolation debug: end +[ INFO] [1732705900.791612435]: wait-interpolation debug: start +[ INFO] [1732705900.793724471]: wait-interpolation debug: end +[ INFO] [1732705901.804215712]: wait-interpolation debug: start +[ INFO] [1732705901.808587886]: wait-interpolation debug: end +[ WARN] [1732705904.972431719]: [robotsound_jp] :wait-for-result finished with preempted status +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705906.050180840]: wait-interpolation debug: start +[ INFO] [1732705907.068734438]: wait-interpolation debug: end +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +;; # :joint-angle(88.0757) violate max-angle(88.0) +[ INFO] [1732705907.117464072]: wait-interpolation debug: start +[ INFO] [1732705908.152083734]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732705908.191825203]: wait-interpolation debug: start +[ INFO] [1732705909.196738487]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732705909.305613467]: wait-interpolation debug: start +[ INFO] [1732705910.355451045]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732705910.419334163]: wait-interpolation debug: start +[ INFO] [1732705911.429667852]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732705911.508512859]: wait-interpolation debug: start +[ INFO] [1732705912.504799050]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732705912.548760462]: wait-interpolation debug: start +[ INFO] [1732705913.551514202]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732705913.591451024]: wait-interpolation debug: start +[ INFO] [1732705914.597136014]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732705914.676889500]: wait-interpolation debug: start +[ INFO] [1732705915.681819910]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732705915.774456282]: wait-interpolation debug: start +[ INFO] [1732705916.786290752]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732705916.863924139]: wait-interpolation debug: start +[ INFO] [1732705917.868982005]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732705917.954747545]: wait-interpolation debug: start +[ INFO] [1732705918.950264495]: wait-interpolation debug: end +;; # :joint-angle(88.0748) violate max-angle(88.0) +[ INFO] [1732705921.142575621]: wait-interpolation debug: start +[ INFO] [1732705921.145956802]: wait-interpolation debug: end +[ INFO] [1732705923.988773286]: wait-interpolation debug: start +[ INFO] [1732705923.990231473]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732705924.086184170]: wait-interpolation debug: start +[ INFO] [1732705929.148132917]: wait-interpolation debug: end +[ INFO] [1732705929.220976412]: wait-interpolation debug: start +[ERROR] [1732705931.221131174]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732705931.221205161]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732705931.223024760]: wait-interpolation debug: end +[ INFO] [1732705931.780531319]: wait-interpolation debug: start +[ INFO] [1732705932.776855269]: wait-interpolation debug: end +[ INFO] [1732705934.755460733]: wait-interpolation debug: start +[ INFO] [1732705934.759288016]: wait-interpolation debug: end +[ INFO] [1732705935.768764187]: wait-interpolation debug: start +[ INFO] [1732705935.771056189]: wait-interpolation debug: end +[ WARN] [1732705935.772714874]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732705935.772751494]: expected goal id 1732705935771768687_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_13 +[ WARN] [1732705935.772777746]: received goal id /battery_warning-90-1732705904.966 + C-c C-cinterrupt4.B4-irteusgl$ load "main.l" +[ WARN] [1732706010.741006031]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732706010.741046247]: expected goal id 1732705935771768687_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_13 +[ WARN] [1732706010.741064874]: received goal id 1732706000424076291_/tweet_client_warning_473265_robotsound_jp_72 +[ WARN] [1732706010.741343787]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732706010.741366168]: expected goal id 1732705935771768687_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_13 +[ WARN] [1732706010.741379105]: received goal id 1732706001429023229_/tweet_client_warning_473265_robotsound_jp_73 +[ WARN] [1732706010.741609458]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732706010.741630122]: expected goal id 1732705935771768687_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_13 +[ WARN] [1732706010.741651760]: received goal id 1732706002485270952_/tweet_client_warning_473265_robotsound_jp_74 +[ WARN] [1732706014.640378760]: [/r_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732706014.640471601]: expected goal id 1732706014621190756_/pr2_eus_interface_1732705419350276377_79054_/r_gripper_controller/gripper_action_15 +[ WARN] [1732706014.640541737]: received goal id 1732705935760550112_/pr2_eus_interface_1732705419350276377_79054_/r_gripper_controller/gripper_action_14 +[ INFO] [1732706016.834384677]: wait-interpolation debug: start +[ERROR] [1732706033.114743847]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732706033.114872080]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732706033.132915798]: wait-interpolation debug: end +[ INFO] [1732706037.706674161]: wait-interpolation debug: start +[ERROR] [1732706039.293102733]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732706039.293143929]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732706039.297730917]: wait-interpolation debug: end +[ INFO] [1732706045.376039265]: wait-interpolation debug: start +[ INFO] [1732706045.380094736]: wait-interpolation debug: end +[ INFO] [1732706055.170400096]: wait-interpolation debug: start +[ INFO] [1732706055.170865757]: wait-interpolation debug: end +[ INFO] [1732706061.739910074]: wait-interpolation debug: start +[ INFO] [1732706062.739197875]: wait-interpolation debug: end +[ WARN] [1732706062.797873869]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732706062.800604151]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732706062.800835658]: original trajectory command : +[ WARN] [1732706062.800964599]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (1000) +[ WARN] [1732706062.801029375]: current angle vector : #f(50.0 17.8275 14.7726 46.824 -78.4543 6.11414 -34.739 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732706062.801065389]: new trajectory command : dvi = 2 +[ WARN] [1732706062.801157367]: : #f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732706062.801214458]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732706062.801244830]: new trajectory command : +[ WARN] [1732706062.801295712]: : (#f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (500 500) +[ INFO] [1732706062.807116020]: wait-interpolation debug: start +[ INFO] [1732706063.984118139]: wait-interpolation debug: end +[ WARN] [1732706064.131727957]: continuous joint (r_forearm_roll_joint) moves 187.256 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732706064.136460938]: continuous joint (r_forearm_roll_joint) moves 187.256 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732706064.136647693]: original trajectory command : +[ WARN] [1732706064.136722649]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2607 43.8809 31.2151 -95.0212 167.256 -43.8137 77.0602 0.0 42.8986)) (500) +[ WARN] [1732706064.136786340]: current angle vector : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732706064.136821170]: new trajectory command : dvi = 2 +[ WARN] [1732706064.136898137]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8696 58.9405 -19.3924 -107.511 73.6281 -36.9069 128.53 0.0 42.8986) 250 +[ WARN] [1732706064.136965338]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2607 43.8809 31.2151 -95.0212 167.256 -43.8137 77.0602 0.0 42.8986) 250 +[ WARN] [1732706064.137000594]: new trajectory command : +[ WARN] [1732706064.137066207]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8696 58.9405 -19.3924 -107.511 73.6281 -36.9069 128.53 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2607 43.8809 31.2151 -95.0212 167.256 -43.8137 77.0602 0.0 42.8986)) (250 250) +[ INFO] [1732706064.142363042]: wait-interpolation debug: start +[ERROR] [1732706065.742015591]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732706065.742066444]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732706065.748263861]: wait-interpolation debug: end +[ INFO] [1732706066.152852248]: wait-interpolation debug: start +[ INFO] [1732706067.445710473]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732706067.541654649]: wait-interpolation debug: start +[ INFO] [1732706068.545688175]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732706068.588156602]: wait-interpolation debug: start +[ INFO] [1732706069.594185982]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732706069.653328319]: wait-interpolation debug: start +[ INFO] [1732706070.646999668]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732706070.692029452]: wait-interpolation debug: start +[ INFO] [1732706071.697801865]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732706071.750591826]: wait-interpolation debug: start +[ INFO] [1732706072.774816794]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732706072.817874767]: wait-interpolation debug: start +[ INFO] [1732706073.845495022]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732706073.892711472]: wait-interpolation debug: start +[ INFO] [1732706074.881563963]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732706074.960220461]: wait-interpolation debug: start +[ INFO] [1732706075.967451935]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732706076.010300833]: wait-interpolation debug: start +[ INFO] [1732706076.998468184]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732706079.230401023]: wait-interpolation debug: start +[ INFO] [1732706079.230617071]: wait-interpolation debug: end +[ INFO] [1732706082.074519571]: wait-interpolation debug: start +[ INFO] [1732706082.081539321]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732706082.127383627]: wait-interpolation debug: start +[ INFO] [1732706087.120785074]: wait-interpolation debug: end +[ INFO] [1732706087.226003965]: wait-interpolation debug: start +[ERROR] [1732706100.192351030]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732706100.192404286]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732706100.195307610]: wait-interpolation debug: end +[ INFO] [1732706103.421259554]: wait-interpolation debug: start +[ INFO] [1732706104.416268985]: wait-interpolation debug: end +[ INFO] [1732706106.401301165]: wait-interpolation debug: start +[ INFO] [1732706106.401525116]: wait-interpolation debug: end +[ INFO] [1732706107.412960393]: wait-interpolation debug: start +[ INFO] [1732706107.418007095]: wait-interpolation debug: end +[ WARN] [1732706107.419414676]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732706107.419456483]: expected goal id 1732706107418556892_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_18 +[ WARN] [1732706107.419489458]: received goal id /battery_warning-91-1732706084.966 +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732706112.887601515]: wait-interpolation debug: start +[ INFO] [1732706113.878308145]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732706113.920987213]: wait-interpolation debug: start +[ INFO] [1732706114.918263776]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732706114.959472746]: wait-interpolation debug: start +[ INFO] [1732706115.956911017]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732706115.999866358]: wait-interpolation debug: start +[ INFO] [1732706116.999478083]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732706117.039393648]: wait-interpolation debug: start +[ INFO] [1732706118.033662860]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732706118.075574023]: wait-interpolation debug: start +[ INFO] [1732706119.075188758]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732706119.113858725]: wait-interpolation debug: start +[ INFO] [1732706120.109726950]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732706120.154568595]: wait-interpolation debug: start +[ INFO] [1732706121.178204511]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732706121.236211142]: wait-interpolation debug: start +[ INFO] [1732706122.233462185]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732706122.277478816]: wait-interpolation debug: start +[ INFO] [1732706123.274308299]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732706123.320033881]: wait-interpolation debug: start +[ INFO] [1732706124.317458589]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732706124.398466379]: wait-interpolation debug: start +[ INFO] [1732706125.397311270]: wait-interpolation debug: end +;; # :joint-angle(88.076) violate max-angle(88.0) +[ INFO] [1732706127.586804674]: wait-interpolation debug: start +[ INFO] [1732706127.586951986]: wait-interpolation debug: end +[ INFO] [1732706130.418386455]: wait-interpolation debug: start +[ INFO] [1732706130.418882477]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732706130.494650987]: wait-interpolation debug: start +[ INFO] [1732706135.520888934]: wait-interpolation debug: end +[ INFO] [1732706135.605482602]: wait-interpolation debug: start +[ INFO] [1732706137.599366617]: wait-interpolation debug: end +[ INFO] [1732706137.670183700]: wait-interpolation debug: start +[ INFO] [1732706138.670018099]: wait-interpolation debug: end +[ INFO] [1732706140.615290968]: wait-interpolation debug: start +[ INFO] [1732706140.615463703]: wait-interpolation debug: end +[ INFO] [1732706141.623373438]: wait-interpolation debug: start +[ INFO] [1732706141.627042441]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732706147.059187150]: wait-interpolation debug: start +[ INFO] [1732706148.057990805]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732706148.117699794]: wait-interpolation debug: start +[ INFO] [1732706149.113379221]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732706149.152511938]: wait-interpolation debug: start +[ INFO] [1732706150.158005469]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732706150.199428165]: wait-interpolation debug: start +[ INFO] [1732706151.191581956]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732706151.271141003]: wait-interpolation debug: start +[ INFO] [1732706152.287262887]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732706152.329803890]: wait-interpolation debug: start +[ INFO] [1732706153.349504440]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732706153.411927565]: wait-interpolation debug: start +[ INFO] [1732706154.415574863]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732706154.460255702]: wait-interpolation debug: start +[ INFO] [1732706155.458504412]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732706155.508414421]: wait-interpolation debug: start +[ INFO] [1732706156.510091838]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732706156.549867949]: wait-interpolation debug: start +[ INFO] [1732706157.547145734]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732706157.589167399]: wait-interpolation debug: start +[ INFO] [1732706158.591164011]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732706158.630628002]: wait-interpolation debug: start +[ INFO] [1732706159.628724774]: wait-interpolation debug: end +;; # :joint-angle(88.0742) violate max-angle(88.0) +[ INFO] [1732706161.790713340]: wait-interpolation debug: start +[ INFO] [1732706161.791007945]: wait-interpolation debug: end +[ INFO] [1732706164.626196095]: wait-interpolation debug: start +[ INFO] [1732706164.626655285]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732706164.665048015]: wait-interpolation debug: start +[ INFO] [1732706169.670133200]: wait-interpolation debug: end +[ INFO] [1732706169.747914109]: wait-interpolation debug: start +[ INFO] [1732706171.776400527]: wait-interpolation debug: end +[ INFO] [1732706171.819090582]: wait-interpolation debug: start +[ INFO] [1732706172.858362020]: wait-interpolation debug: end + C-c C-cinterrupt5.B5-irteusgl$ (send *ri* :servo-off) +Call Stack (max depth: 20): + 0: at (send *ri* :servo-off) + 1: at sigint-handler + 2: at sigint-handler + 3: at (while (ros::ok) (ros::ros-debug "[~A] :wait-for-result ~A ~A" ros::name-space (ros::simple-goal-states-to-string ros::simple-state) (send ros::comm-state :state)) (send self :spin-once) (if (= ros::simple-state ros::*simple-goal-state-done*) (return)) (if (> ros::timeout 0) (let* ((ros::tm (ros::time- (ros::time-now) ros::start))) (if (> (send ros::tm :to-sec) ros::timeout) (return-from :wait-for-result nil)))) (when ros::return-if-server-down (when (= (ros::get-num-publishers ros::result-topic) 0) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : no publishers found for ~A" ros::name-space ros::result-topic) (return-from :wait-for-result nil)) (when (and ros::status-stamp ros::maximum-status-interval (> (send (ros::time- (ros::time-now) ros::status-stamp) :to-sec) ros::maximum-status-interval)) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : status did not received for 5 seconds" ros::name-space) (return-from :wait-for-result nil))) (ros::sleep)) + 4: at (let ((ros::start (ros::time-now)) (ros::result-topic (format nil "~A/result" ros::name-space))) (ros::ros-debug "[~A] :wait-for-result ~A, timeout=~A" ros::name-space (if ros::goal_id (send ros::goal_id :id)) ros::timeout) (unless ros::goal_id (ros::ros-error "[~A] :wait-for-result (return nil when no goal exists)" ros::name-space) (return-from :wait-for-result nil)) (ros::rate ros::wait-rate) (while (ros::ok) (ros::ros-debug "[~A] :wait-for-result ~A ~A" ros::name-space (ros::simple-goal-states-to-string ros::simple-state) (send ros::comm-state :state)) (send self :spin-once) (if (= ros::simple-state ros::*simple-goal-state-done*) (return)) (if (> ros::timeout 0) (let* ((ros::tm (ros::time- (ros::time-now) ros::start))) (if (> (send ros::tm :to-sec) ros::timeout) (return-from :wait-for-result nil)))) (when ros::return-if-server-down (when (= (ros::get-num-publishers ros::result-topic) 0) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : no publishers found for ~A" ros::name-space ros::result-topic) (return-from :wait-for-result nil)) (when (and ros::status-stamp ros::maximum-status-interval (> (send (ros::time- (ros::time-now) ros::status-stamp) :to-sec) ros::maximum-status-interval)) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : status did not received for 5 seconds" ros::name-space) (return-from :wait-for-result nil))) (ros::sleep)) (ros::ros-debug "[~A] :wait-for-result finished ~A" ros::name-space (ros::goal-status-to-string (send self :get-state))) (if (eq (send self :get-state) actionlib_msgs::goalstatus::*preempted*) (ros::ros-warn "[~A] :wait-for-result finished with preempted status" ros::name-space)) (eq (send self :get-state) actionlib_msgs::goalstatus::*succeeded*)) + 5: at (send-all clients :wait-for-result) + 6: at (send-all clients :wait-for-result) + 7: at (send-all clients :wait-for-result) + 8: at (progn (send-all clients :wait-for-result) (mapcar #'(lambda (res) (or (if ignore-stall nil (send res :stalled)) (send res :reached_goal))) (send-all clients :get-result))) + 9: at (if wait (progn (send-all clients :wait-for-result) (mapcar #'(lambda (res) (or (if ignore-stall nil (send res :stalled)) (send res :reached_goal))) (send-all clients :get-result))) (mapcar #'(lambda (ac) (send ac :spin-once) (not (null (memq (send ac :get-state) (list actionlib_msgs::goalstatus::*pending* actionlib_msgs::goalstatus::*active* actionlib_msgs::goalstatus::*succeeded*))))) clients)) + 10: at (setq result (if wait (progn (send-all clients :wait-for-result) (mapcar #'(lambda (res) (or (if ignore-stall nil (send res :stalled)) (send res :reached_goal))) (send-all clients :get-result))) (mapcar #'(lambda (ac) (send ac :spin-once) (not (null (memq (send ac :get-state) (list actionlib_msgs::goalstatus::*pending* actionlib_msgs::goalstatus::*active* actionlib_msgs::goalstatus::*succeeded*))))) clients))) + 11: at (let* (goal (clients (case arm (:rarm (list r-gripper-action)) (:larm (list l-gripper-action)) (:arms (list r-gripper-action l-gripper-action)) (t (ros::ros-warn "arm[~a] in :move-gripper is invalid type" arm)))) result) (dolist (client clients) (setq goal (instance pr2_controllers_msgs::pr2grippercommandactiongoal :init)) (send goal :goal :command :position pos) (send goal :goal :command :max_effort effort) (send client :send-goal goal)) (setq result (if wait (progn (send-all clients :wait-for-result) (mapcar #'(lambda (res) (or (if ignore-stall nil (send res :stalled)) (send res :reached_goal))) (send-all clients :get-result))) (mapcar #'(lambda (ac) (send ac :spin-once) (not (null (memq (send ac :get-state) (list actionlib_msgs::goalstatus::*pending* actionlib_msgs::goalstatus::*active* actionlib_msgs::goalstatus::*succeeded*))))) clients))) (case arm (:arms result) (t (car result)))) + 12: at (send self :move-gripper arm 0.0 :effort (* 2000 g) :wait wait) + 13: at (send *ri* :start-grasp :larm) + 14: at (while (< i #:dotimes6902002) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (+ *target-ypos* (* *traj_len* 0.2)) *target-zpos*))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -pi/2 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 5000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 50 (* *needle_len* 0.5) 150)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 50 (- 0 (* *needle_len* 0.5)) 150)) :translate #f(-10.0 0.0 0.0)) :rotate -pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1) (send *pr2* :rarm :move-end-pos (float-vector 0 0 -50) :local) (send *pr2* :larm :move-end-pos (float-vector 0 0 -100) :local) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq i (1+ i))) + 15: at (let ((i 0) (#:dotimes6902002 5)) (declare (integer i #:dotimes6902002)) (while (< i #:dotimes6902002) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (+ *target-ypos* (* *traj_len* 0.2)) *target-zpos*))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -pi/2 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 5000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 50 (* *needle_len* 0.5) 150)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 50 (- 0 (* *needle_len* 0.5)) 150)) :translate #f(-10.0 0.0 0.0)) :rotate -pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1) (send *pr2* :rarm :move-end-pos (float-vector 0 0 -50) :local) (send *pr2* :larm :move-end-pos (float-vector 0 0 -100) :local) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq i (1+ i))) nil) + 16: at (dotimes (i 5) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (+ *target-ypos* (* *traj_len* 0.2)) *target-zpos*))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -pi/2 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 5000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 50 (* *needle_len* 0.5) 150)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 50 (- 0 (* *needle_len* 0.5)) 150)) :translate #f(-10.0 0.0 0.0)) :rotate -pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1) (send *pr2* :rarm :move-end-pos (float-vector 0 0 -50) :local) (send *pr2* :larm :move-end-pos (float-vector 0 0 -100) :local) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects)) + 17: at (apply #'ros::load-org-for-ros ros::fullname args) + 18: at (apply #'ros::load-org-for-ros ros::fullname args) + 19: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + And more... +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: cannot find method :servo-off in (send *ri* :servo-off) +6.E6-irteusgl$ (send *ri* :methods) +(:init :state :publish-joint-state :wait-interpolation :larm-controller :rarm-controller :head-controller :torso-controller :default-controller :midbody-controller :fullbody-controller :controller-angle-vector :larm-angle-vector :rarm-angle-vector :head-angle-vector :move-gripper :gripper :start-grasp :get-grasp-result :stop-grasp :pr2-gripper-state-callback :pr2-fingertip-callback :reset-fingertip :finger-pressure :wait-torso :check-continuous-joint-move-over-180 :angle-vector :angle-vector-sequence :angle-vector-with-constraint :list-controllers :switch-controller :start-mannequin-mode :stop-mannequin-mode :change-inflation-range :init :odom-callback :go-stop :make-plan :move-to :move-to-send :move-to-wait :go-waitp :go-pos :go-pos-no-wait :go-wait :send-cmd-vel-raw :go-velocity :go-pos-unsafe :go-pos-unsafe-no-wait :go-pos-unsafe-wait :move-trajectory-sequence :move-trajectory :state :robot-interface-simulation-callback :clear-costmap :change-inflation-range :init :add-controller :robot-interface-simulation-callback :publish-joint-state :angle-vector-safe :angle-vector-duration :angle-vector-simulation :angle-vector :angle-vector-sequence :wait-interpolation :interpolatingp :wait-interpolation-smooth :interpolating-smoothp :stop-motion :cancel-angle-vector :worldcoords :torque-vector :potentio-vector :reference-vector :actual-vector :error-vector :state-vector :stamp :send-ros-controller :set-robot-state1 :get-robot-state :ros-state-callback :wait-until-update-all-joints :update-robot-state :state :default-controller :sub-angle-vector :robot :viewer :objects :set-simulation-default-look-at :draw-objects :find-object :joint-action-enable :simulation-modep :warningp :spin-once :send-trajectory :send-trajectory-each :ros-wait :go-pos :go-pos-no-wait :go-wait :go-velocity :go-stop :gripper :joint-trajectory-to-angle-vector-list :show-goal-hand-coords :find-descendants-dae-links :show-mesh-traj-with-color :nod :eus-mannequin-mode :play-sound :speak :speak-en :speak-jp :plist :get :put :name :remprop :prin1 :prin1 :warning :error :slots :methods :super :get-val :set-val) +7.E6-irteusgl$ (send *ri* :potentio-vector) +#f(232.545 -6.17213 -4.00819 84.3552 -11.7189 95.3003 -95.1299 251.876 -4.35909 42.8946 -38.5775 -81.4197 150.179 -47.1797 140.741 0.02353 44.166) +8.E6-irteusgl$ (send *ri* :stop-grasp) +[ WARN] [1732706868.187112810]: [/l_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732706868.187223778]: expected goal id 1732706868170142507_/pr2_eus_interface_1732705419350276377_79054_/l_gripper_controller/gripper_action_24 +[ WARN] [1732706868.187284901]: received goal id 1732706172875313204_/pr2_eus_interface_1732705419350276377_79054_/l_gripper_controller/gripper_action_23 +(t t) +9.E6-irteusgl$ (send *ri* :rarm :stop-grasp) +Call Stack (max depth: 20): + 0: at (send *ri* :rarm :stop-grasp) + 1: at euserror + 2: at euserror + 3: at (send *ri* :servo-off) + 4: at sigint-handler + 5: at sigint-handler + 6: at (while (ros::ok) (ros::ros-debug "[~A] :wait-for-result ~A ~A" ros::name-space (ros::simple-goal-states-to-string ros::simple-state) (send ros::comm-state :state)) (send self :spin-once) (if (= ros::simple-state ros::*simple-goal-state-done*) (return)) (if (> ros::timeout 0) (let* ((ros::tm (ros::time- (ros::time-now) ros::start))) (if (> (send ros::tm :to-sec) ros::timeout) (return-from :wait-for-result nil)))) (when ros::return-if-server-down (when (= (ros::get-num-publishers ros::result-topic) 0) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : no publishers found for ~A" ros::name-space ros::result-topic) (return-from :wait-for-result nil)) (when (and ros::status-stamp ros::maximum-status-interval (> (send (ros::time- (ros::time-now) ros::status-stamp) :to-sec) ros::maximum-status-interval)) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : status did not received for 5 seconds" ros::name-space) (return-from :wait-for-result nil))) (ros::sleep)) + 7: at (let ((ros::start (ros::time-now)) (ros::result-topic (format nil "~A/result" ros::name-space))) (ros::ros-debug "[~A] :wait-for-result ~A, timeout=~A" ros::name-space (if ros::goal_id (send ros::goal_id :id)) ros::timeout) (unless ros::goal_id (ros::ros-error "[~A] :wait-for-result (return nil when no goal exists)" ros::name-space) (return-from :wait-for-result nil)) (ros::rate ros::wait-rate) (while (ros::ok) (ros::ros-debug "[~A] :wait-for-result ~A ~A" ros::name-space (ros::simple-goal-states-to-string ros::simple-state) (send ros::comm-state :state)) (send self :spin-once) (if (= ros::simple-state ros::*simple-goal-state-done*) (return)) (if (> ros::timeout 0) (let* ((ros::tm (ros::time- (ros::time-now) ros::start))) (if (> (send ros::tm :to-sec) ros::timeout) (return-from :wait-for-result nil)))) (when ros::return-if-server-down (when (= (ros::get-num-publishers ros::result-topic) 0) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : no publishers found for ~A" ros::name-space ros::result-topic) (return-from :wait-for-result nil)) (when (and ros::status-stamp ros::maximum-status-interval (> (send (ros::time- (ros::time-now) ros::status-stamp) :to-sec) ros::maximum-status-interval)) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : status did not received for 5 seconds" ros::name-space) (return-from :wait-for-result nil))) (ros::sleep)) (ros::ros-debug "[~A] :wait-for-result finished ~A" ros::name-space (ros::goal-status-to-string (send self :get-state))) (if (eq (send self :get-state) actionlib_msgs::goalstatus::*preempted*) (ros::ros-warn "[~A] :wait-for-result finished with preempted status" ros::name-space)) (eq (send self :get-state) actionlib_msgs::goalstatus::*succeeded*)) + 8: at (send-all clients :wait-for-result) + 9: at (send-all clients :wait-for-result) + 10: at (send-all clients :wait-for-result) + 11: at (progn (send-all clients :wait-for-result) (mapcar #'(lambda (res) (or (if ignore-stall nil (send res :stalled)) (send res :reached_goal))) (send-all clients :get-result))) + 12: at (if wait (progn (send-all clients :wait-for-result) (mapcar #'(lambda (res) (or (if ignore-stall nil (send res :stalled)) (send res :reached_goal))) (send-all clients :get-result))) (mapcar #'(lambda (ac) (send ac :spin-once) (not (null (memq (send ac :get-state) (list actionlib_msgs::goalstatus::*pending* actionlib_msgs::goalstatus::*active* actionlib_msgs::goalstatus::*succeeded*))))) clients)) + 13: at (setq result (if wait (progn (send-all clients :wait-for-result) (mapcar #'(lambda (res) (or (if ignore-stall nil (send res :stalled)) (send res :reached_goal))) (send-all clients :get-result))) (mapcar #'(lambda (ac) (send ac :spin-once) (not (null (memq (send ac :get-state) (list actionlib_msgs::goalstatus::*pending* actionlib_msgs::goalstatus::*active* actionlib_msgs::goalstatus::*succeeded*))))) clients))) + 14: at (let* (goal (clients (case arm (:rarm (list r-gripper-action)) (:larm (list l-gripper-action)) (:arms (list r-gripper-action l-gripper-action)) (t (ros::ros-warn "arm[~a] in :move-gripper is invalid type" arm)))) result) (dolist (client clients) (setq goal (instance pr2_controllers_msgs::pr2grippercommandactiongoal :init)) (send goal :goal :command :position pos) (send goal :goal :command :max_effort effort) (send client :send-goal goal)) (setq result (if wait (progn (send-all clients :wait-for-result) (mapcar #'(lambda (res) (or (if ignore-stall nil (send res :stalled)) (send res :reached_goal))) (send-all clients :get-result))) (mapcar #'(lambda (ac) (send ac :spin-once) (not (null (memq (send ac :get-state) (list actionlib_msgs::goalstatus::*pending* actionlib_msgs::goalstatus::*active* actionlib_msgs::goalstatus::*succeeded*))))) clients))) (case arm (:arms result) (t (car result)))) + 15: at (send self :move-gripper arm 0.0 :effort (* 2000 g) :wait wait) + 16: at (send *ri* :start-grasp :larm) + 17: at (while (< i #:dotimes6902002) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (+ *target-ypos* (* *traj_len* 0.2)) *target-zpos*))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -pi/2 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 5000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 50 (* *needle_len* 0.5) 150)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 50 (- 0 (* *needle_len* 0.5)) 150)) :translate #f(-10.0 0.0 0.0)) :rotate -pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1) (send *pr2* :rarm :move-end-pos (float-vector 0 0 -50) :local) (send *pr2* :larm :move-end-pos (float-vector 0 0 -100) :local) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq i (1+ i))) + 18: at (let ((i 0) (#:dotimes6902002 5)) (declare (integer i #:dotimes6902002)) (while (< i #:dotimes6902002) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (+ *target-ypos* (* *traj_len* 0.2)) *target-zpos*))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -pi/2 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 5000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 50 (* *needle_len* 0.5) 150)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 50 (- 0 (* *needle_len* 0.5)) 150)) :translate #f(-10.0 0.0 0.0)) :rotate -pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1) (send *pr2* :rarm :move-end-pos (float-vector 0 0 -50) :local) (send *pr2* :larm :move-end-pos (float-vector 0 0 -100) :local) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq i (1+ i))) nil) + 19: at (dotimes (i 5) (setq r (instance traj :init)) (send r :rotate pi/2 :z) (setq *target* (v+ (send *center* :pos) (float-vector (+ *target-xpos* (* i 3)) (+ *target-ypos* (* *traj_len* 0.2)) *target-zpos*))) (send r :locate *target* :world) (objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) (setq *r-pos* (send (elt (send r :points) 9) :copy-worldcoords)) (send *r-pos* :rotate pi/2 :y :local) (send *r-pos* :rotate -pi/2 :z :local) (send *r-pos* :translate #f(-10.0 0.0 0.0) :local) (send *pr2* :rarm :inverse-kinematics *r-pos* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (dolist (e (send r :points)) (let (ee) (setq ee (send e :copy-worldcoords)) (send ee :translate (float-vector (- *needle_len* *rarm_offset*) 0 0) :local) (send ee :rotate pi :z :local) (send ee :rotate pi/2 :y :local) (send ee :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics ee :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects))) (send *ri* :start-grasp :rarm :wait t) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :larm :wait t) (send *ri* :wait-interpolation) (send *pr2* :larm :end-coords :dissoc *needle*) (send *pr2* :rarm :end-coords :assoc *needle*) (send *pr2* :rarm :move-end-pos (float-vector 0 0 (- 0 *remain*)) :local) (- *remain* *diff_remain*) (format t "remaining ~A ~%" *remain*) (send *irtviewer* :draw-objects) (send *ri* :angle-vector (send *pr2* :angle-vector) 5000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-larm* (send (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 50 (* *needle_len* 0.5) 150)) :rotate pi/2 :z) :rotate pi/2 :y) :rotate pi :x)) (send *pass-larm* :draw-on :flush t :size 100) (send *pr2* :larm :inverse-kinematics *pass-larm* :rotation-axis t :use-torso t) (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (setq *pass-rarm* (send (send (send (send *center* :copy-worldcoords) :translate (float-vector 50 (- 0 (* *needle_len* 0.5)) 150)) :translate #f(-10.0 0.0 0.0)) :rotate -pi/2 :x)) (send *pass-rarm* :draw-on :flush t :size 100) (send *pr2* :rarm :inverse-kinematics *pass-rarm* :rotation-axis t) (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects) (send *ri* :start-grasp :larm) (send *ri* :wait-interpolation) (unix:sleep 1) (send *ri* :stop-grasp :rarm) (send *ri* :wait-interpolation) (send *pr2* :rarm :end-coords :dissoc *needle*) (send *pr2* :larm :end-coords :assoc *needle*) (send *ri* :speak-jp "繰り返し次の経路を縫います.注意してください." :wait t) (unix:sleep 1) (send *pr2* :rarm :move-end-pos (float-vector 0 0 -50) :local) (send *pr2* :larm :move-end-pos (float-vector 0 0 -100) :local) (send *ri* :angle-vector (send *pr2* :angle-vector) 500) (send *ri* :wait-interpolation) (send *irtviewer* :draw-objects)) + And more... +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: cannot find method :rarm in (send *ri* :rarm :stop-grasp) +10.E7-irteusgl$ (send *ri* :rarm :start-grasp) +Call Stack (max depth: 20): + 0: at (send *ri* :rarm :start-grasp) + 1: at euserror + 2: at euserror + 3: at (send *ri* :rarm :stop-grasp) + 4: at euserror + 5: at euserror + 6: at (send *ri* :servo-off) + 7: at sigint-handler + 8: at sigint-handler + 9: at (while (ros::ok) (ros::ros-debug "[~A] :wait-for-result ~A ~A" ros::name-space (ros::simple-goal-states-to-string ros::simple-state) (send ros::comm-state :state)) (send self :spin-once) (if (= ros::simple-state ros::*simple-goal-state-done*) (return)) (if (> ros::timeout 0) (let* ((ros::tm (ros::time- (ros::time-now) ros::start))) (if (> (send ros::tm :to-sec) ros::timeout) (return-from :wait-for-result nil)))) (when ros::return-if-server-down (when (= (ros::get-num-publishers ros::result-topic) 0) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : no publishers found for ~A" ros::name-space ros::result-topic) (return-from :wait-for-result nil)) (when (and ros::status-stamp ros::maximum-status-interval (> (send (ros::time- (ros::time-now) ros::status-stamp) :to-sec) ros::maximum-status-interval)) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : status did not received for 5 seconds" ros::name-space) (return-from :wait-for-result nil))) (ros::sleep)) + 10: at (let ((ros::start (ros::time-now)) (ros::result-topic (format nil "~A/result" ros::name-space))) (ros::ros-debug "[~A] :wait-for-result ~A, timeout=~A" ros::name-space (if ros::goal_id (send ros::goal_id :id)) ros::timeout) (unless ros::goal_id (ros::ros-error "[~A] :wait-for-result (return nil when no goal exists)" ros::name-space) (return-from :wait-for-result nil)) (ros::rate ros::wait-rate) (while (ros::ok) (ros::ros-debug "[~A] :wait-for-result ~A ~A" ros::name-space (ros::simple-goal-states-to-string ros::simple-state) (send ros::comm-state :state)) (send self :spin-once) (if (= ros::simple-state ros::*simple-goal-state-done*) (return)) (if (> ros::timeout 0) (let* ((ros::tm (ros::time- (ros::time-now) ros::start))) (if (> (send ros::tm :to-sec) ros::timeout) (return-from :wait-for-result nil)))) (when ros::return-if-server-down (when (= (ros::get-num-publishers ros::result-topic) 0) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : no publishers found for ~A" ros::name-space ros::result-topic) (return-from :wait-for-result nil)) (when (and ros::status-stamp ros::maximum-status-interval (> (send (ros::time- (ros::time-now) ros::status-stamp) :to-sec) ros::maximum-status-interval)) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : status did not received for 5 seconds" ros::name-space) (return-from :wait-for-result nil))) (ros::sleep)) (ros::ros-debug "[~A] :wait-for-result finished ~A" ros::name-space (ros::goal-status-to-string (send self :get-state))) (if (eq (send self :get-state) actionlib_msgs::goalstatus::*preempted*) (ros::ros-warn "[~A] :wait-for-result finished with preempted status" ros::name-space)) (eq (send self :get-state) actionlib_msgs::goalstatus::*succeeded*)) + 11: at (send-all clients :wait-for-result) + 12: at (send-all clients :wait-for-result) + 13: at (send-all clients :wait-for-result) + 14: at (progn (send-all clients :wait-for-result) (mapcar #'(lambda (res) (or (if ignore-stall nil (send res :stalled)) (send res :reached_goal))) (send-all clients :get-result))) + 15: at (if wait (progn (send-all clients :wait-for-result) (mapcar #'(lambda (res) (or (if ignore-stall nil (send res :stalled)) (send res :reached_goal))) (send-all clients :get-result))) (mapcar #'(lambda (ac) (send ac :spin-once) (not (null (memq (send ac :get-state) (list actionlib_msgs::goalstatus::*pending* actionlib_msgs::goalstatus::*active* actionlib_msgs::goalstatus::*succeeded*))))) clients)) + 16: at (setq result (if wait (progn (send-all clients :wait-for-result) (mapcar #'(lambda (res) (or (if ignore-stall nil (send res :stalled)) (send res :reached_goal))) (send-all clients :get-result))) (mapcar #'(lambda (ac) (send ac :spin-once) (not (null (memq (send ac :get-state) (list actionlib_msgs::goalstatus::*pending* actionlib_msgs::goalstatus::*active* actionlib_msgs::goalstatus::*succeeded*))))) clients))) + 17: at (let* (goal (clients (case arm (:rarm (list r-gripper-action)) (:larm (list l-gripper-action)) (:arms (list r-gripper-action l-gripper-action)) (t (ros::ros-warn "arm[~a] in :move-gripper is invalid type" arm)))) result) (dolist (client clients) (setq goal (instance pr2_controllers_msgs::pr2grippercommandactiongoal :init)) (send goal :goal :command :position pos) (send goal :goal :command :max_effort effort) (send client :send-goal goal)) (setq result (if wait (progn (send-all clients :wait-for-result) (mapcar #'(lambda (res) (or (if ignore-stall nil (send res :stalled)) (send res :reached_goal))) (send-all clients :get-result))) (mapcar #'(lambda (ac) (send ac :spin-once) (not (null (memq (send ac :get-state) (list actionlib_msgs::goalstatus::*pending* actionlib_msgs::goalstatus::*active* actionlib_msgs::goalstatus::*succeeded*))))) clients))) (case arm (:arms result) (t (car result)))) + 18: at (send self :move-gripper arm 0.0 :effort (* 2000 g) :wait wait) + 19: at (send *ri* :start-grasp :larm) + And more... +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: cannot find method :rarm in (send *ri* :rarm :start-grasp) +11.E8-irteusgl$ (send *ri* :start-grasp) +[ WARN] [1732707011.850544755]: [/r_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732707011.850587451]: expected goal id 1732707011843654946_/pr2_eus_interface_1732705419350276377_79054_/r_gripper_controller/gripper_action_25 +[ WARN] [1732707011.850612095]: received goal id 1732706868169910908_/pr2_eus_interface_1732705419350276377_79054_/r_gripper_controller/gripper_action_24 +[ WARN] [1732707011.850918309]: [/l_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732707011.850939928]: expected goal id 1732707011843825497_/pr2_eus_interface_1732705419350276377_79054_/l_gripper_controller/gripper_action_25 +[ WARN] [1732707011.850968682]: received goal id 1732706868170142507_/pr2_eus_interface_1732705419350276377_79054_/l_gripper_controller/gripper_action_24 +;; # :joint-angle(81.732) violate max-angle(74.2702) +;; # :joint-angle(45.7101) violate max-angle(37.2423) +;; # :joint-angle(3.38331) violate max-angle(-5.72958) +;; # :joint-angle(81.732) violate max-angle(74.2702) +;; # :joint-angle(45.7101) violate max-angle(37.2423) +;; # :joint-angle(3.38331) violate max-angle(-5.72958) +(87.4534 84.1306) +12.E8-irteusgl$ (send *ri* :start-grasp) +;; # :joint-angle(81.732) violate max-angle(74.2702) +;; # :joint-angle(45.7101) violate max-angle(37.2423) +;; # :joint-angle(3.38331) violate max-angle(-5.72958) +;; # :joint-angle(81.732) violate max-angle(74.2702) +;; # :joint-angle(45.7101) violate max-angle(37.2423) +;; # :joint-angle(3.38331) violate max-angle(-5.72958) +(87.4534 84.1306) +13.E8-irteusgl$ (send *ri* :stop-grasp) +(t t) +14.E8-irteusgl$ (send *ri* :start-grasp :arms) +[ WARN] [1732707077.917144621]: [/r_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732707077.917199625]: expected goal id 1732707077916457093_/pr2_eus_interface_1732705419350276377_79054_/r_gripper_controller/gripper_action_32 +[ WARN] [1732707077.917225614]: received goal id 1732707033307152992_/pr2_eus_interface_1732705419350276377_79054_/r_gripper_controller/gripper_action_31 +[ WARN] [1732707077.917936693]: [/l_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732707077.917975353]: expected goal id 1732707077916723151_/pr2_eus_interface_1732705419350276377_79054_/l_gripper_controller/gripper_action_32 +[ WARN] [1732707077.918002924]: received goal id 1732707033307359069_/pr2_eus_interface_1732705419350276377_79054_/l_gripper_controller/gripper_action_31 +;; # :joint-angle(75.588) violate max-angle(74.2702) +;; # :joint-angle(37.3769) violate max-angle(37.2423) +;; # :joint-angle(-4.908) violate max-angle(-5.72958) +;; # :joint-angle(75.588) violate max-angle(74.2702) +;; # :joint-angle(37.3677) violate max-angle(37.2423) +;; # :joint-angle(-4.908) violate max-angle(-5.72958) +(23.5396 1.2969) +15.E8-irteusgl$ (send *ri* :stop-grasp :arms) +(t t) +16.E8-irteusgl$ (send *ri* :start-grasp :arms) +[ WARN] [1732707102.532940835]: [/r_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732707102.533012124]: expected goal id 1732707102498743704_/pr2_eus_interface_1732705419350276377_79054_/r_gripper_controller/gripper_action_36 +[ WARN] [1732707102.533046843]: received goal id 1732707096921412785_/pr2_eus_interface_1732705419350276377_79054_/r_gripper_controller/gripper_action_35 +[ WARN] [1732707102.535251286]: [/l_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732707102.535295368]: expected goal id 1732707102499667538_/pr2_eus_interface_1732705419350276377_79054_/l_gripper_controller/gripper_action_36 +[ WARN] [1732707102.535318375]: received goal id 1732707096921631228_/pr2_eus_interface_1732705419350276377_79054_/l_gripper_controller/gripper_action_35 +;; # :joint-angle(75.588) violate max-angle(74.2702) +;; # :joint-angle(37.386) violate max-angle(37.2423) +;; # :joint-angle(-5.01768) violate max-angle(-5.72958) +;; # :joint-angle(75.588) violate max-angle(74.2702) +;; # :joint-angle(37.386) violate max-angle(37.2423) +;; # :joint-angle(-5.01768) violate max-angle(-5.72958) +(14.6742 1.12465) +17.E8-irteusgl$ (send *ri* :potentio-vector) +#f(232.546 61.808 -4.02273 67.5418 -15.5926 95.3434 -95.1324 251.873 -31.877 41.6199 37.2423 -25.8615 289.314 -5.72958 123.971 2.24953 74.2702) +18.E8-irteusgl$ (send *ri* :potentio-vector) +#f(232.546 61.808 -4.02273 67.5418 -15.5926 95.3434 -95.1324 251.873 -31.877 41.6199 37.2423 -25.8615 289.314 -5.72958 123.971 2.24953 74.2702) +19.E8-irteusgl$ (send *ri* :potentio-vector) +#f(232.546 61.808 -4.02273 67.5418 -15.5926 95.3434 -95.1324 251.873 -31.877 41.6199 37.2423 -25.8615 289.314 -5.72958 123.971 2.24953 74.2702) +20.E8-irteusgl$ (send *ri* :potentio-vector) +#f(232.546 61.808 -4.02273 67.5418 -15.5926 95.3434 -95.1324 251.873 -31.877 41.6199 37.2423 -25.8615 289.314 -5.72958 123.971 2.24953 74.2702) +21.E8-irteusgl$ (send *ri* :potentio-vector) +#f(232.546 61.808 -4.02273 67.5418 -15.5926 95.3434 -95.1324 251.873 -31.877 41.6199 37.2423 -25.8615 289.314 -5.72958 123.971 2.24953 74.2702) +22.E8-irteusgl$ send *ri* :state :potentio-vector +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.62381) violate max-angle(-5.72958) +#f(232.413 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7285 3.48553 74.2702) +23.E8-irteusgl$ send *ri* :state :potentio-vector +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.64874) violate max-angle(-5.72958) +#f(232.413 63.4563 -3.8434 67.1559 -17.1686 95.4893 -95.1324 251.873 -28.9746 28.252 -93.1062 -107.673 379.134 -5.72958 91.7535 3.52753 74.2702) +24.E8-irteusgl$ send *ri* :spin-once +nil +25.E8-irteusgl$ send *ri* :state :potentio-vector +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.67367) violate max-angle(-5.72958) +#f(232.412 63.442 -3.85309 67.1743 -17.1769 95.4893 -95.1324 251.873 -26.8085 28.1987 -93.143 -107.648 379.134 -5.72958 91.7285 3.46153 74.2702) +26.E8-irteusgl$ send *ri* :spin-once +nil +27.E8-irteusgl$ send *ri* :state :potentio-vector +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.69361) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -25.5687 28.2423 -93.097 -107.664 379.134 -5.72958 91.7235 3.47353 74.2702) +28.E8-irteusgl$ (do-until-key (print (send *ri* :state :potentio-vector))) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1651 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1142 28.2229 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2278 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2278 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2278 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2278 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2278 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2278 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2278 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1047 28.2326 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1047 28.2326 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1047 28.2326 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1047 28.2326 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1047 28.2326 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1047 28.2326 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1047 28.2326 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1047 28.2326 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1047 28.2326 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1047 28.2326 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1047 28.2326 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1047 28.2326 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1047 28.2326 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1047 28.2326 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.1047 28.2326 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0952 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0952 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0952 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0952 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0952 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0952 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0952 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0952 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0952 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0952 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0952 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.48553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0429 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0382 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0382 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0382 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0382 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0382 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0382 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0382 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0382 28.2375 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0334 28.2423 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0334 28.2423 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0334 28.2423 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0334 28.2423 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0334 28.2423 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0334 28.2423 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0334 28.2423 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0334 28.2423 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0334 28.2423 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0334 28.2423 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0334 28.2423 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0334 28.2423 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -36.0334 28.2423 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9954 28.2472 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9764 28.2472 -93.097 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9669 28.2472 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9669 28.2472 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.9574 28.252 -93.097 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.8909 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.8814 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.8814 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.8814 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.8814 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.8814 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.8814 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.8814 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.8814 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.8767 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.8767 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.8767 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.8767 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.8767 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8719 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8672 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8672 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8672 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8672 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8672 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8672 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8672 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.8624 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.8624 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.8624 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.8624 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.8624 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.8624 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.8624 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.8624 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.8624 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.8624 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -35.8624 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8529 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8529 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8529 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8529 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8529 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8529 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8529 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8529 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8529 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8434 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -35.8434 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.4871 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.4871 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.4871 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.4871 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.4254 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.3494 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.2686 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.49753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1879 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1879 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1879 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1879 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1879 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1879 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1879 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1879 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1879 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1879 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1879 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1879 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1879 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1879 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1879 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1071 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.1071 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.0121 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.0121 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.0121 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.0121 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.0121 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.0121 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.0121 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.0121 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -35.0121 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -34.7936 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -34.5704 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -34.4326 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -34.4326 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -34.4326 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -34.3091 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -34.3091 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -34.3091 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -34.3091 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -34.3091 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -34.3091 28.2326 -93.1154 -107.664 379.134 -5.72958 91.736 3.50353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -33.8721 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -33.7391 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -33.7391 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -33.5681 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -33.5681 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -33.5681 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -33.5681 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -33.5681 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -33.5681 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -33.5681 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -33.5681 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1559 -17.1686 95.4859 -95.1324 251.873 -32.9078 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1559 -17.1686 95.4859 -95.1324 251.873 -32.9078 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1559 -17.1686 95.4859 -95.1324 251.873 -32.9078 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1559 -17.1686 95.4859 -95.1324 251.873 -32.9078 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1559 -17.1686 95.4859 -95.1324 251.873 -32.9078 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1559 -17.1686 95.4859 -95.1324 251.873 -32.9078 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1559 -17.1686 95.4859 -95.1324 251.873 -32.9078 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1559 -17.1686 95.4859 -95.1324 251.873 -32.9078 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1559 -17.1686 95.4859 -95.1324 251.873 -32.9078 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4859 -95.1324 251.873 -32.1763 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4859 -95.1324 251.873 -32.1763 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4859 -95.1324 251.873 -32.1763 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -31.9957 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -31.9957 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -31.9957 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -31.9957 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -31.9957 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -31.9957 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -31.9957 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -31.9957 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -31.9957 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4859 -95.1324 251.873 -31.9957 28.2375 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -31.2357 28.2423 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -31.0362 28.2423 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -31.0362 28.2423 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -31.0362 28.2423 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -31.0362 28.2423 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -31.0362 28.2423 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -31.0362 28.2423 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -31.0362 28.2423 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -31.0362 28.2423 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -31.0362 28.2423 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4859 -95.1324 251.873 -31.0362 28.2423 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -30.2619 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -30.2619 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -30.0672 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -30.0672 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -30.0672 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -30.0672 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -30.0672 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -29.8867 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -29.8867 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -29.8867 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -29.8867 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1559 -17.1686 95.4859 -95.1324 251.873 -29.3214 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4859 -95.1324 251.873 -29.1456 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4859 -95.1324 251.873 -29.1456 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4859 -95.1324 251.873 -29.1456 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4859 -95.1324 251.873 -29.1456 28.252 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4859 -95.1324 251.873 -28.9604 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4859 -95.1324 251.873 -28.9604 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4859 -95.1324 251.873 -28.9604 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4859 -95.1324 251.873 -28.9604 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4859 -95.1324 251.873 -28.9604 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4859 -95.1324 251.873 -28.9604 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -28.4473 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -28.2763 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -28.1053 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -28.1053 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -28.1053 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -28.1053 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -28.1053 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -27.9581 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -27.9581 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -27.9581 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -27.9581 28.2569 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.8085 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.8085 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.8085 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.8085 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.8085 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.8085 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.8085 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.8085 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.6755 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.6755 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.6755 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.6755 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.6755 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.6755 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.6755 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.6755 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.6755 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.6755 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.6755 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.6755 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1559 -17.1686 95.4859 -95.1324 251.873 -26.6755 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.5568 28.2666 -93.1154 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.039 28.2666 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.039 28.2666 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.039 28.2666 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.039 28.2666 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.039 28.2666 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.039 28.2666 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.039 28.2666 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.039 28.2666 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.039 28.2666 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.039 28.2666 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.039 28.2666 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.039 28.2666 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.039 28.2666 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.039 28.2666 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.039 28.2666 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -26.039 28.2666 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4859 -95.1324 251.873 -25.9487 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -25.8395 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -25.8395 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -25.8395 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -25.8395 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -25.8395 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1743 -17.1686 95.4859 -95.1324 251.873 -25.621 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1743 -17.1686 95.4859 -95.1324 251.873 -25.4927 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1743 -17.1769 95.4859 -95.1324 251.873 -25.4262 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1743 -17.1769 95.4859 -95.1324 251.873 -25.4262 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1743 -17.1769 95.4859 -95.1324 251.873 -25.4262 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1769 95.4826 -95.1324 251.873 -25.3645 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1769 95.4826 -95.1324 251.873 -25.3645 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1769 95.4826 -95.1324 251.873 -25.3645 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1769 95.4826 -95.1324 251.873 -25.3645 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1769 95.4826 -95.1324 251.873 -25.3645 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1769 95.4826 -95.1324 251.873 -25.3645 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2837 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2362 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2362 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2362 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2362 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2362 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2362 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2362 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2362 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2362 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2362 28.2714 -93.1154 -107.673 379.134 -5.72958 91.736 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2763 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2811 -93.1154 -107.673 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.0652 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.07 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.07 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.07 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.07 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.07 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.07 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.07 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.07 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.07 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.07 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.07 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.07 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.089 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.0937 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.0937 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.0937 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.0937 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.0937 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.0985 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.0985 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.0985 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.0985 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.0985 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.0985 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.127 28.2811 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1317 28.286 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1317 28.286 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1317 28.286 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1317 28.286 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1317 28.286 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1317 28.286 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1317 28.286 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1317 28.286 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1317 28.286 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1317 28.286 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1317 28.286 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.1317 28.286 -93.1062 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.1365 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.146 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1507 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1507 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1507 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1507 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1507 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1507 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1507 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1507 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1507 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1507 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1745 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1887 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1887 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1887 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1887 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1887 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1887 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1887 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1887 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1887 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1887 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.1887 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.2077 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.2077 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.2077 28.286 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2932 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2932 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2932 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2932 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2932 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2932 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.2932 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.336 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.336 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.134 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.134 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.134 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.134 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.134 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.134 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.134 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.134 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.134 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.134 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.2338 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.2338 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.2338 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.2338 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.2338 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.2338 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.2338 28.2908 -93.097 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -27.5781 28.286 -93.0787 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.3096 28.2811 -93.0787 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.4331 28.2811 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.4331 28.2811 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.4331 28.2811 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.4331 28.2811 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.4331 28.2811 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.4331 28.2811 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.4331 28.2811 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.4331 28.2811 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.4331 28.2811 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.4331 28.2811 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.4331 28.2811 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.4331 28.2811 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.4331 28.2811 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.4331 28.2811 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.4331 28.2811 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.5614 28.2763 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.5614 28.2763 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.5614 28.2763 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.5614 28.2763 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.5614 28.2763 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.5614 28.2763 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.5614 28.2763 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.5614 28.2763 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.5614 28.2763 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.5614 28.2763 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.5614 28.2763 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.5614 28.2763 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.5614 28.2763 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.5614 28.2763 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -29.3119 28.2617 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -29.4354 28.252 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -29.4354 28.252 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -29.4354 28.252 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -29.4354 28.252 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -29.4354 28.252 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -29.4354 28.252 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -29.4354 28.252 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -29.4354 28.252 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -29.4354 28.252 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -29.4354 28.252 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -29.4354 28.252 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -29.4354 28.252 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -29.4354 28.252 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -29.5541 28.2472 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -29.5541 28.2472 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -29.5541 28.2472 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -29.5541 28.2472 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -29.5541 28.2472 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -29.5541 28.2472 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -29.5541 28.2472 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -29.5541 28.2472 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -29.9009 28.2278 -93.0787 -107.664 379.134 -5.72958 91.736 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -30.2287 28.2036 -93.0787 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -30.2287 28.2036 -93.0787 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -30.2287 28.2036 -93.0787 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -30.2287 28.2036 -93.0787 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -30.2287 28.2036 -93.0787 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -30.2287 28.2036 -93.0787 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -30.2287 28.2036 -93.0787 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.3332 28.1939 -93.0787 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.3332 28.1939 -93.0787 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.3332 28.1939 -93.0787 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.1122 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.1122 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.1122 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.1122 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.1122 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.1122 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.1122 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.1122 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.1122 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.1122 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.1122 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.2072 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.2072 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.2072 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.2072 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.2072 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.2072 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.2072 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.2072 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.2072 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.2072 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.2072 28.1842 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -31.5777 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -31.5777 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -31.5777 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -31.5777 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -31.5777 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -31.5777 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -31.5777 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -31.5777 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.668 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.668 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4468 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.668 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -32.0147 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -32.0147 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -32.0147 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -32.0147 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -32.1002 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -32.1002 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -32.1002 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -32.1002 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -32.1002 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -32.1002 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -32.1002 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -32.4328 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -32.5088 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -32.5088 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.5848 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.5848 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.5848 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.5848 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.5848 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.5848 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.5848 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.5848 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.8033 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.8698 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.8698 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.8698 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.8698 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.8698 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.8698 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.8698 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.8698 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.8698 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.8698 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -32.9363 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -32.9363 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -33.0075 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -33.0075 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -33.0075 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -33.0075 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -33.0075 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -33.0075 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -33.0075 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -33.0075 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4658 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -33.0075 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.2688 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.3923 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.4493 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.4493 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.5111 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.5111 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.5111 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.5111 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.5111 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.5111 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.5111 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.6251 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.6773 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.6773 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.6773 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.6773 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.6773 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.6773 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.6773 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1743 -17.1686 95.4826 -95.1324 251.873 -33.7343 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1743 -17.1686 95.4826 -95.1324 251.873 -33.7343 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1743 -17.1686 95.4826 -95.1324 251.873 -33.7343 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.8958 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.9433 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.9433 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.9433 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.9433 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.9433 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.9433 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.9433 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.9433 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.9433 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.9433 28.189 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.1333 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.1333 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.1333 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.1333 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.1333 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.1333 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.1761 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.1761 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.1761 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.1761 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.1761 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.3043 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.3043 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.3043 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.3043 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.3043 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.3043 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.3471 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.3471 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.3898 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.3898 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.3898 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.5419 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.6179 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.6179 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.6559 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.6559 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.6559 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.6559 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.6559 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.6559 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.6559 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.6559 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.7936 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8221 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8221 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8554 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8554 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8554 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8554 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8554 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8554 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8554 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8554 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9456 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9741 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9741 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9741 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9741 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9741 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9741 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9741 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9741 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9741 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9741 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.0834 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.0834 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1119 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1119 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1119 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1119 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1119 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1119 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1119 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1119 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1119 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1119 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1356 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1594 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1594 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1594 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1594 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1594 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1831 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1831 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1831 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.1831 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.3636 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.3826 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.4016 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.4206 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.4396 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.4396 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.4396 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.4396 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.4396 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.4396 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.4396 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.4396 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.4396 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5061 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5204 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5204 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5204 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5204 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5204 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5204 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5204 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5204 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5204 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5204 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5204 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5204 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5204 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5394 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5394 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5394 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5394 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5394 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70607) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.5394 28.1939 -93.0878 -107.664 379.134 -5.72958 91.736 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6439 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6676 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6676 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6819 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.6914 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7817 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7817 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7817 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7817 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7912 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7912 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7912 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7912 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7912 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7912 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7912 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7912 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7912 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7912 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7912 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7912 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7912 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7912 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7912 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.7912 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.8007 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.8007 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.8149 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.8244 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.8339 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.8339 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.8339 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.8387 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.8387 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.8387 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.8387 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.8387 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -35.8387 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -35.9194 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -35.9194 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -35.9194 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -35.9194 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -35.9194 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9242 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9242 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9242 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9242 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9242 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9242 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9242 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9242 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9242 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9242 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9242 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9242 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9242 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9289 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9289 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9289 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.461 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9289 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9479 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9479 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9479 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9527 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9527 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9527 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9527 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9527 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9527 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9527 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9527 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9764 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9812 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9859 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9859 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.1987 -93.0878 -107.664 379.134 -5.72958 91.7335 3.53353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.2036 -93.0878 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.2036 -93.0878 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.2036 -93.0878 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.2036 -93.0878 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.2036 -93.0878 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.2036 -93.0878 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.2036 -93.0878 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.2036 -93.0878 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.2036 -93.0878 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.2036 -93.0878 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.412 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9907 28.2036 -93.0878 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9717 28.2617 -93.0787 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9669 28.2763 -93.0787 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9574 28.2811 -93.0878 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9527 28.286 -93.097 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9527 28.286 -93.097 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9527 28.286 -93.097 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9527 28.286 -93.097 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9527 28.286 -93.097 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9527 28.286 -93.097 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9527 28.286 -93.097 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9527 28.286 -93.097 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9194 28.2811 -93.1154 -107.664 379.134 -5.72958 91.7335 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9194 28.2811 -93.1154 -107.664 379.134 -5.72958 91.7335 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9194 28.2811 -93.1154 -107.664 379.134 -5.72958 91.7335 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9194 28.2811 -93.1154 -107.664 379.134 -5.72958 91.7335 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9194 28.2811 -93.1154 -107.664 379.134 -5.72958 91.7335 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9194 28.2811 -93.1154 -107.664 379.134 -5.72958 91.7335 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9194 28.2811 -93.1154 -107.664 379.134 -5.72958 91.7335 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9194 28.2811 -93.1154 -107.664 379.134 -5.72958 91.7335 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9099 28.2763 -93.1154 -107.664 379.134 -5.72958 91.7335 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9099 28.2763 -93.1154 -107.664 379.134 -5.72958 91.7335 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.9099 28.2763 -93.1154 -107.664 379.134 -5.72958 91.7335 3.51553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.8529 28.2423 -93.1154 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.8529 28.2423 -93.1154 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.8529 28.2423 -93.1154 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.8529 28.2423 -93.1154 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.8529 28.2423 -93.1154 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.8529 28.2423 -93.1154 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.8529 28.2423 -93.1154 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.8529 28.2423 -93.1154 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.8529 28.2423 -93.1154 -107.664 379.134 -5.72958 91.7335 3.52153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.8434 28.2326 -93.1154 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.8434 28.2326 -93.1154 -107.664 379.134 -5.72958 91.7335 3.52753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.70857) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.7769 28.2278 -93.1154 -107.664 379.134 -5.72958 91.7335 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.7437 28.2375 -93.1154 -107.664 379.134 -5.72958 91.731 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.7437 28.2375 -93.1154 -107.664 379.134 -5.72958 91.731 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.7437 28.2375 -93.1154 -107.664 379.134 -5.72958 91.731 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4753 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.7342 28.2423 -93.1154 -107.664 379.134 -5.72958 91.731 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4753 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.7342 28.2423 -93.1154 -107.664 379.134 -5.72958 91.731 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4753 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.7342 28.2423 -93.1154 -107.664 379.134 -5.72958 91.731 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4753 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.7342 28.2423 -93.1154 -107.664 379.134 -5.72958 91.731 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4753 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.7342 28.2423 -93.1154 -107.664 379.134 -5.72958 91.731 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4753 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.7342 28.2423 -93.1154 -107.664 379.134 -5.72958 91.731 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4753 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.7342 28.2423 -93.1154 -107.664 379.134 -5.72958 91.731 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.8434 67.1743 -17.1603 95.4826 -95.1324 251.873 -35.7247 28.2472 -93.1154 -107.664 379.134 -5.72958 91.731 3.56953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.8434 67.1743 -17.1603 95.4826 -95.1324 251.873 -35.7247 28.2472 -93.1154 -107.664 379.134 -5.72958 91.731 3.56953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.8434 67.1743 -17.1603 95.4826 -95.1324 251.873 -35.7247 28.2472 -93.1154 -107.664 379.134 -5.72958 91.731 3.56953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.8434 67.1743 -17.1603 95.4826 -95.1324 251.873 -35.7247 28.2472 -93.1154 -107.664 379.134 -5.72958 91.731 3.56953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.8434 67.1743 -17.1603 95.4826 -95.1324 251.873 -35.7247 28.2472 -93.1154 -107.664 379.134 -5.72958 91.731 3.56953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.8434 67.1743 -17.1603 95.4826 -95.1324 251.873 -35.7247 28.2472 -93.1154 -107.664 379.134 -5.72958 91.731 3.56953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.8434 67.1743 -17.1603 95.4826 -95.1324 251.873 -35.7247 28.2472 -93.1154 -107.664 379.134 -5.72958 91.731 3.56953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.8434 67.1743 -17.1603 95.4826 -95.1324 251.873 -35.7247 28.2472 -93.1154 -107.664 379.134 -5.72958 91.731 3.56953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.8434 67.1743 -17.1603 95.4826 -95.1324 251.873 -35.7247 28.2472 -93.1154 -107.664 379.134 -5.72958 91.731 3.56953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.8434 67.1743 -17.1603 95.4826 -95.1324 251.873 -35.7247 28.2472 -93.1154 -107.664 379.134 -5.72958 91.731 3.56953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.8434 67.1743 -17.1603 95.4826 -95.1324 251.873 -35.7247 28.2472 -93.1154 -107.664 379.134 -5.72958 91.731 3.56953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4895 -3.8337 67.1559 -17.152 95.4826 -95.1324 251.873 -35.7057 28.2617 -93.1154 -107.664 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4895 -3.8337 67.1559 -17.152 95.4826 -95.1324 251.873 -35.6962 28.2617 -93.1154 -107.664 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4895 -3.8337 67.1559 -17.152 95.4826 -95.1324 251.873 -35.6962 28.2617 -93.1154 -107.664 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4895 -3.8337 67.1559 -17.152 95.4826 -95.1324 251.873 -35.6962 28.2617 -93.1154 -107.664 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4895 -3.8337 67.1559 -17.152 95.4826 -95.1324 251.873 -35.6962 28.2617 -93.1154 -107.664 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4895 -3.8337 67.1559 -17.152 95.4826 -95.1324 251.873 -35.6962 28.2617 -93.1154 -107.664 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4895 -3.8337 67.1559 -17.152 95.4826 -95.1324 251.873 -35.6962 28.2617 -93.1154 -107.664 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4895 -3.8337 67.1559 -17.152 95.4826 -95.1324 251.873 -35.6962 28.2617 -93.1154 -107.664 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4895 -3.8337 67.1559 -17.152 95.4826 -95.1324 251.873 -35.6962 28.2617 -93.1154 -107.664 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4895 -3.8337 67.1559 -17.152 95.4826 -95.1324 251.873 -35.6962 28.2617 -93.1154 -107.664 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4895 -3.8337 67.1559 -17.152 95.4826 -95.1324 251.873 -35.6962 28.2617 -93.1154 -107.664 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.4848 -3.82886 67.1743 -17.152 95.4826 -95.1324 251.873 -35.6344 28.2375 -93.1154 -107.656 379.134 -5.72958 91.731 3.58753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.82886 67.1743 -17.152 95.4826 -95.1324 251.873 -35.6201 28.2326 -93.1154 -107.656 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.82886 67.1743 -17.152 95.4826 -95.1324 251.873 -35.6201 28.2326 -93.1154 -107.656 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.82886 67.1743 -17.152 95.4826 -95.1324 251.873 -35.6201 28.2326 -93.1154 -107.656 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.82886 67.1743 -17.152 95.4826 -95.1324 251.873 -35.6201 28.2326 -93.1154 -107.656 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.82886 67.1743 -17.152 95.4826 -95.1324 251.873 -35.6201 28.2326 -93.1154 -107.656 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.82886 67.1743 -17.152 95.4826 -95.1324 251.873 -35.6201 28.2326 -93.1154 -107.656 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.82886 67.1743 -17.152 95.4826 -95.1324 251.873 -35.6201 28.2326 -93.1154 -107.656 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.82886 67.1743 -17.152 95.4826 -95.1324 251.873 -35.6201 28.2326 -93.1154 -107.656 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.82886 67.1743 -17.152 95.4826 -95.1324 251.873 -35.6201 28.2326 -93.1154 -107.656 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71106) violate max-angle(-5.72958) +#f(232.411 63.48 -3.82886 67.1743 -17.152 95.4826 -95.1324 251.873 -35.6201 28.2326 -93.1154 -107.656 379.134 -5.72958 91.731 3.58153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1559 -17.1852 95.4826 -95.1324 251.873 -35.4634 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.53953 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1559 -17.1852 95.4826 -95.1324 251.873 -35.4349 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1559 -17.1852 95.4826 -95.1324 251.873 -35.4349 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1559 -17.1852 95.4826 -95.1324 251.873 -35.3969 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1559 -17.1852 95.4826 -95.1324 251.873 -35.3969 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1559 -17.1852 95.4826 -95.1324 251.873 -35.3969 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1559 -17.1852 95.4826 -95.1324 251.873 -35.3969 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1559 -17.1852 95.4826 -95.1324 251.873 -35.3969 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1559 -17.1852 95.4826 -95.1324 251.873 -35.3969 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1559 -17.1852 95.4826 -95.1324 251.873 -35.3969 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1559 -17.1852 95.4826 -95.1324 251.873 -35.3969 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1559 -17.1852 95.4826 -95.1324 251.873 -35.3969 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1651 -17.1852 95.4826 -95.1324 251.873 -35.3494 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1651 -17.1852 95.4826 -95.1324 251.873 -35.3494 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1651 -17.1852 95.4826 -95.1324 251.873 -35.3494 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1651 -17.1852 95.4826 -95.1324 251.873 -35.3494 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1651 -17.1852 95.4826 -95.1324 251.873 -35.3494 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1651 -17.1852 95.4826 -95.1324 251.873 -35.3494 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1651 -17.1852 95.4826 -95.1324 251.873 -35.3494 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1651 -17.1852 95.4826 -95.1324 251.873 -35.3494 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1651 -17.1852 95.4826 -95.1324 251.873 -35.3494 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4325 -3.85794 67.1651 -17.1852 95.4826 -95.1324 251.873 -35.3494 28.2229 -93.1154 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.442 -3.85794 67.1743 -17.1852 95.4826 -95.1324 251.873 -35.2544 28.2229 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.442 -3.85794 67.1743 -17.1852 95.4826 -95.1324 251.873 -35.1974 28.2229 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.442 -3.85794 67.1743 -17.1852 95.4826 -95.1324 251.873 -35.1974 28.2229 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.442 -3.85794 67.1743 -17.1852 95.4826 -95.1324 251.873 -35.1974 28.2229 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.442 -3.85794 67.1743 -17.1852 95.4826 -95.1324 251.873 -35.1974 28.2229 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.442 -3.85794 67.1743 -17.1852 95.4826 -95.1324 251.873 -35.1974 28.2229 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.442 -3.85794 67.1743 -17.1852 95.4826 -95.1324 251.873 -35.1974 28.2229 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.442 -3.85794 67.1743 -17.1852 95.4826 -95.1324 251.873 -35.1974 28.2229 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.442 -3.85794 67.1743 -17.1852 95.4826 -95.1324 251.873 -35.1974 28.2229 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.442 -3.85794 67.1743 -17.1852 95.4826 -95.1324 251.873 -35.1974 28.2229 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.442 -3.85794 67.1743 -17.1852 95.4826 -95.1324 251.873 -35.1974 28.2229 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.3613 28.2278 -93.097 -107.664 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.3613 28.2278 -93.097 -107.664 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.3613 28.2278 -93.097 -107.664 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.3613 28.2278 -93.097 -107.664 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.3613 28.2278 -93.097 -107.664 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.3613 28.2278 -93.097 -107.664 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.82886 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.2426 28.2278 -93.097 -107.664 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.82401 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.1001 28.2326 -93.097 -107.664 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.82401 67.1743 -17.1603 95.4826 -95.1324 251.873 -33.9528 28.2326 -93.097 -107.664 379.134 -5.72958 91.7285 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.82401 67.1743 -17.1603 95.4826 -95.1324 251.873 -33.9528 28.2326 -93.097 -107.664 379.134 -5.72958 91.7285 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.82401 67.1743 -17.1603 95.4826 -95.1324 251.873 -33.9528 28.2326 -93.097 -107.664 379.134 -5.72958 91.7285 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.82401 67.1743 -17.1603 95.4826 -95.1324 251.873 -33.9528 28.2326 -93.097 -107.664 379.134 -5.72958 91.7285 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.82401 67.1743 -17.1603 95.4826 -95.1324 251.873 -33.9528 28.2326 -93.097 -107.664 379.134 -5.72958 91.7285 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.82401 67.1743 -17.1603 95.4826 -95.1324 251.873 -33.9528 28.2326 -93.097 -107.664 379.134 -5.72958 91.7285 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.82401 67.1743 -17.1603 95.4826 -95.1324 251.873 -33.8151 28.2326 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.82401 67.1743 -17.1603 95.4826 -95.1324 251.873 -33.8151 28.2326 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.82401 67.1743 -17.1603 95.4826 -95.1324 251.873 -33.8151 28.2326 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.82401 67.1743 -17.1603 95.4826 -95.1324 251.873 -33.8151 28.2326 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.82401 67.1743 -17.1603 95.4826 -95.1324 251.873 -33.8151 28.2326 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.82401 67.1743 -17.1603 95.4826 -95.1324 251.873 -33.8151 28.2326 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.82401 67.1743 -17.1603 95.4826 -95.1324 251.873 -33.8151 28.2326 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.82401 67.1743 -17.1603 95.4826 -95.1324 251.873 -33.8151 28.2326 -93.097 -107.664 379.134 -5.72958 91.7285 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.83855 67.1559 -17.1603 95.4826 -95.1324 251.873 -32.827 28.2375 -93.097 -107.664 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.83855 67.1559 -17.1603 95.4826 -95.1324 251.873 -32.827 28.2375 -93.097 -107.664 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.83855 67.1559 -17.1603 95.4826 -95.1324 251.873 -32.827 28.2375 -93.097 -107.664 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1603 95.4826 -95.1324 251.873 -32.6513 28.2375 -93.097 -107.664 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.934 28.2375 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.934 28.2375 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.934 28.2375 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.934 28.2375 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.934 28.2375 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.7582 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -31.5825 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -31.5825 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -31.5825 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -31.5825 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71355) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1651 -17.1686 95.4826 -95.1324 251.873 -31.5825 28.2423 -93.097 -107.673 379.134 -5.72958 91.7285 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.0362 28.2423 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.0362 28.2423 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.0362 28.2423 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.461 -3.85309 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.0362 28.2423 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -30.6847 28.2423 -93.097 -107.673 379.134 -5.72958 91.726 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -30.5137 28.2472 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -30.3427 28.2472 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -30.3427 28.2472 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -30.3427 28.2472 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -30.3427 28.2472 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.85309 67.1559 -17.1686 95.4826 -95.1324 251.873 -30.3427 28.2472 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -29.0031 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -29.0031 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.8701 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.8701 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.8701 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.8701 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.8701 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.8701 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.8701 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7086 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7086 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7086 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7086 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7086 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7086 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7086 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7086 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7086 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7086 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7086 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7086 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7086 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1651 -17.1686 95.4826 -95.1324 251.873 -28.2431 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.1053 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.1053 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.1053 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.1053 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -28.1053 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.9676 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.9676 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.9676 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.9676 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.9676 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1559 -17.1769 95.4826 -95.1324 251.873 -27.4166 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1559 -17.1769 95.4826 -95.1324 251.873 -27.4166 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1559 -17.1769 95.4826 -95.1324 251.873 -27.4166 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1559 -17.1769 95.4826 -95.1324 251.873 -27.4166 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1559 -17.1769 95.4826 -95.1324 251.873 -27.4166 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1559 -17.1769 95.4826 -95.1324 251.873 -27.4166 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1559 -17.1769 95.4826 -95.1324 251.873 -27.4166 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1559 -17.1769 95.4826 -95.1324 251.873 -27.4166 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1559 -17.1769 95.4826 -95.1324 251.873 -27.4166 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1559 -17.1769 95.4826 -95.1324 251.873 -27.4166 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71605) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1559 -17.1769 95.4826 -95.1324 251.873 -27.4166 28.252 -93.097 -107.673 379.134 -5.72958 91.726 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71854) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.8418 28.252 -93.097 -107.673 379.134 -5.72958 91.7235 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.71854) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.7373 28.2569 -93.097 -107.673 379.134 -5.72958 91.7235 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.628 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.628 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.5283 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.5283 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.5283 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.5283 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.5283 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.5283 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.5283 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -26.2623 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -26.2623 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -26.2623 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -26.2623 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -26.2623 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -26.2623 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -26.2623 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -26.2623 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -26.2623 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -26.2623 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -26.2623 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.9392 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.9392 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.9392 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.9392 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.9392 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.9392 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.9392 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.9392 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.8775 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.8775 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -25.8775 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1651 -17.1686 95.4826 -95.1324 251.873 -25.7017 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.697 28.2569 -93.1062 -107.681 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.83 28.2617 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8585 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8775 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8775 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.8775 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.9487 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.9487 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.9487 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.9487 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.9487 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.9487 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.9487 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.9487 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.9725 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.9725 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -25.9725 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -26.4095 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -26.4095 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -26.4095 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -26.4095 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -26.4095 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.4713 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.4713 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.4713 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.4713 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.4713 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.4713 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.4713 28.2666 -93.097 -107.673 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.5425 28.2617 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.5425 28.2617 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.5425 28.2617 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.5425 28.2617 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.5425 28.2617 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.5425 28.2617 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -26.5425 28.2617 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.6185 28.2617 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.6185 28.2617 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.6185 28.2617 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.78 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.78 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.78 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.78 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.78 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.78 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.78 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.78 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.78 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.8655 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.8655 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.8655 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.8655 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -26.8655 28.2569 -93.097 -107.673 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.82886 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.2503 28.252 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.82886 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.3548 28.252 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.82886 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.4641 28.252 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.5733 28.252 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.5733 28.252 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.5733 28.252 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.5733 28.252 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.5733 28.252 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.6826 28.252 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.6826 28.252 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.6826 28.252 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.6826 28.252 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8337 67.1743 -17.1686 95.4826 -95.1324 251.873 -27.6826 28.252 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.3856 28.2375 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.4996 28.2326 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.6184 28.2278 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7324 28.2229 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7324 28.2229 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7324 28.2229 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7324 28.2229 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7324 28.2229 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7324 28.2229 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7324 28.2229 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7324 28.2229 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7324 28.2229 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.7324 28.2229 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.8511 28.2229 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.8511 28.2229 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.8511 28.2229 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.8511 28.2229 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.8511 28.2229 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -28.8511 28.2229 -93.097 -107.664 379.134 -5.72958 91.721 3.56353 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -29.0791 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -29.0791 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -29.0791 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -29.0791 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -29.0791 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -29.0791 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -29.0791 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -29.0791 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -29.0791 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.55753 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -29.5161 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -29.6254 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.0387 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.1384 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.1384 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.1384 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.1384 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.1384 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.1384 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.1384 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.1384 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.1384 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.1384 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.1384 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.2429 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.2429 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.2429 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.2429 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.2429 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.2429 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.2429 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.442 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.2429 28.2133 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.5469 28.2036 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.5469 28.2036 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.5469 28.2036 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.5469 28.2036 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.5469 28.2036 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.5469 28.2036 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.5469 28.2036 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.5469 28.2036 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.5469 28.2036 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.5469 28.2036 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.5469 28.2036 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1651 -17.1686 95.4826 -95.1324 251.873 -30.9317 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.0267 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.0267 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.0267 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.0267 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.0267 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.0267 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.0267 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.0267 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.0267 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.0267 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -31.4875 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.83855 67.1651 -17.1686 95.4826 -95.1324 251.873 -31.5777 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.83855 67.1651 -17.1686 95.4826 -95.1324 251.873 -31.5777 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.6632 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.6632 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.6632 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.6632 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.6632 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.6632 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.6632 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -31.6632 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.01 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.01 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.01 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.01 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.01 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.01 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.01 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.01 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.01 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.01 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.01 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -32.7938 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -32.7938 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.461 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -32.7938 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.55153 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -32.8603 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -32.8603 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -32.8603 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -32.8603 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -32.8603 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -32.8603 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.9268 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.9268 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.9933 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.9933 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.9933 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.9933 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.9933 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.9933 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.9933 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.9933 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.9933 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.9933 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1559 -17.1686 95.4826 -95.1324 251.873 -32.9933 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.0598 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.0598 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.1263 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.188 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.188 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.188 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.188 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.188 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.188 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.188 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.2498 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -33.6963 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1743 -17.1686 95.4826 -95.1324 251.873 -33.7533 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.8056 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.8056 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4468 -3.83855 67.1651 -17.1686 95.4826 -95.1324 251.873 -33.8056 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.8578 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.8578 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.8578 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.8578 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9053 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9053 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9053 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9053 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9053 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9053 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9053 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9053 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9053 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9053 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9053 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9053 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9053 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9576 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9576 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9576 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9576 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -33.9576 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.0051 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.0051 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.0051 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.0051 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.0051 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.83855 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.0051 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.1903 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.2806 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.2806 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.3281 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.3281 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.3281 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.3281 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.3281 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.3281 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.3281 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.3281 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.4896 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.4896 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.4896 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.4896 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.4896 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.4896 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.4896 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.4896 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.5276 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.5276 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.5276 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.6369 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint +-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.6749 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.6749 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.6749 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.6749 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.6749 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.6749 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.6749 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1559 -17.1686 95.4826 -95.1324 251.873 -34.6749 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.7034 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4658 -3.8434 67.1651 -17.1686 95.4826 -95.1324 251.873 -34.7034 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4563 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8031 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8364 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8364 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8364 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8364 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8364 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8364 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8649 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8649 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8649 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.8649 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9504 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9789 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9789 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9789 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9789 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9789 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9789 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9789 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9789 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9789 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.84824 67.1743 -17.1686 95.4826 -95.1324 251.873 -34.9789 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.0074 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.0074 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.0074 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.0074 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.0074 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.0074 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.72103) violate max-angle(-5.72958) +#f(232.411 63.4515 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -35.0074 28.1987 -93.097 -107.664 379.134 -5.72958 91.721 3.54553 74.2702) +nil +29.E8-irteusgl$ (send *ri* :robot :larm :end-coords) +# +30.E8-irteusgl$ (do-until-key (print (send *ri* :robot :larm :end-coords))) +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +nil +31.E8-irteusgl$ (do-until-key (send *ri* :state :potentio-vector) (print (send *ri* :robot :larm :end-coords))) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74097) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74347) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74596) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74596) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74596) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74596) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74845) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74845) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74845) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74845) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74845) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.74845) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75095) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +nil +32.E8-irteusgl$ (do-until-key (send *ri* :state :potentio-vector) (print (send *ri* :robot :larm :end-coords)) (unix:usleep 10000)) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75344) violate max-angle(-5.72958) +# + +nil +33.E8-irteusgl$ (do-until-key (send *ri* :state :potentio-vector) (print (send *ri* :robot :larm :end-coords)) (unix:usleep 10000)) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.75842) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76092) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76092) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76092) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76092) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76092) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# + +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +# +nil +34.E8-irteusgl$ (send *ri* :state :potentio-vector) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +#f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4893 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.50353 74.2702) +35.E8-irteusgl$ (send *ri* :state :potentio-vector) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.76341) violate max-angle(-5.72958) +#f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702) +36.E8-irteusgl$ (send *ri* :state :potentio-vector) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-4.99275) violate max-angle(-5.72958) +#f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4826 -95.1324 251.873 -36.0762 26.7834 -79.1134 -106.885 386.621 -5.72958 91.7235 3.47953 74.2702) +37.E8-irteusgl$ (send *ri* :state :potentio-vector) +;; # :joint-angle(75.57) violate max-angle(74.2702) +;; # :joint-angle(-5.13983) violate max-angle(-5.72958) +#f(232.409 63.4515 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.0287 20.0704 -75.42 -95.7531 397.257 -5.72958 91.8606 3.52153 74.2702) +38.E8-irteusgl$ (progn (ros::rate 10) (do-until-key (print 0) (ros::sleep))) +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 + +nil +39.E8-irteusgl$ (progn (ros::rate 1) (do-until-key (print 0) (ros::sleep))) +0 +0 +0 +0 +0 +0 +0 +0 +0 +(progn (ros::rate 1) (do-until-key (print 0) (ros::sleep))) +nil +40.E8-irteusgl$ (progn (ros::rate 1) (do-until-key (print 0) (ros::sleep)(ros::spin-onec))) +0 +Call Stack (max depth: 20): + 0: at (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (print 0) (ros::sleep) (ros::spin-onec)) + 1: at (let ((#:prog110265183 (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (print 0) (ros::sleep) (ros::spin-onec)))) (progn (let ((strm (car (select-stream (list *standard-input*) 0.1)))) (if strm (read-line strm nil nil)))) #:prog110265183) + 2: at (prog1 (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (print 0) (ros::sleep) (ros::spin-onec)) (let ((strm (car (select-stream (list *standard-input*) 0.1)))) (if strm (read-line strm nil nil)))) + 3: at (do-until-key-with-check t (print 0) (ros::sleep) (ros::spin-onec)) + 4: at (do-until-key (print 0) (ros::sleep) (ros::spin-onec)) + 5: at (progn (ros::rate 1) (do-until-key (print 0) (ros::sleep) (ros::spin-onec))) + 6: at euserror + 7: at euserror + 8: at (send *ri* :rarm :start-grasp) + 9: at euserror + 10: at euserror + 11: at (send *ri* :rarm :stop-grasp) + 12: at euserror + 13: at euserror + 14: at (send *ri* :servo-off) + 15: at sigint-handler + 16: at sigint-handler + 17: at (while (ros::ok) (ros::ros-debug "[~A] :wait-for-result ~A ~A" ros::name-space (ros::simple-goal-states-to-string ros::simple-state) (send ros::comm-state :state)) (send self :spin-once) (if (= ros::simple-state ros::*simple-goal-state-done*) (return)) (if (> ros::timeout 0) (let* ((ros::tm (ros::time- (ros::time-now) ros::start))) (if (> (send ros::tm :to-sec) ros::timeout) (return-from :wait-for-result nil)))) (when ros::return-if-server-down (when (= (ros::get-num-publishers ros::result-topic) 0) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : no publishers found for ~A" ros::name-space ros::result-topic) (return-from :wait-for-result nil)) (when (and ros::status-stamp ros::maximum-status-interval (> (send (ros::time- (ros::time-now) ros::status-stamp) :to-sec) ros::maximum-status-interval)) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : status did not received for 5 seconds" ros::name-space) (return-from :wait-for-result nil))) (ros::sleep)) + 18: at (let ((ros::start (ros::time-now)) (ros::result-topic (format nil "~A/result" ros::name-space))) (ros::ros-debug "[~A] :wait-for-result ~A, timeout=~A" ros::name-space (if ros::goal_id (send ros::goal_id :id)) ros::timeout) (unless ros::goal_id (ros::ros-error "[~A] :wait-for-result (return nil when no goal exists)" ros::name-space) (return-from :wait-for-result nil)) (ros::rate ros::wait-rate) (while (ros::ok) (ros::ros-debug "[~A] :wait-for-result ~A ~A" ros::name-space (ros::simple-goal-states-to-string ros::simple-state) (send ros::comm-state :state)) (send self :spin-once) (if (= ros::simple-state ros::*simple-goal-state-done*) (return)) (if (> ros::timeout 0) (let* ((ros::tm (ros::time- (ros::time-now) ros::start))) (if (> (send ros::tm :to-sec) ros::timeout) (return-from :wait-for-result nil)))) (when ros::return-if-server-down (when (= (ros::get-num-publishers ros::result-topic) 0) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : no publishers found for ~A" ros::name-space ros::result-topic) (return-from :wait-for-result nil)) (when (and ros::status-stamp ros::maximum-status-interval (> (send (ros::time- (ros::time-now) ros::status-stamp) :to-sec) ros::maximum-status-interval)) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : status did not received for 5 seconds" ros::name-space) (return-from :wait-for-result nil))) (ros::sleep)) (ros::ros-debug "[~A] :wait-for-result finished ~A" ros::name-space (ros::goal-status-to-string (send self :get-state))) (if (eq (send self :get-state) actionlib_msgs::goalstatus::*preempted*) (ros::ros-warn "[~A] :wait-for-result finished with preempted status" ros::name-space)) (eq (send self :get-state) actionlib_msgs::goalstatus::*succeeded*)) + 19: at (send-all clients :wait-for-result) + And more... +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: undefined function ros::spin-onec in (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (print 0) (ros::sleep) (ros::spin-onec)) +41.E9-irteusgl$ (progn (ros::rate 1) (do-until-key (print 0) (ros::sleep)(ros::spin-once))) +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 +0 C-c C-cinterrupt42.B10-irteusgl$ +nil +42.B10-irteusgl$ (send *ri* :stop-grasp) +[ WARN] [1732709524.668655391]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.671577133]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.673793080]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.675481679]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.677315659]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.679354321]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.681289224]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.682400854]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.684398687]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.686470827]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.688324656]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.689843837]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.692444804]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.694417490]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.696102058]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.697802298]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.699593287]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.701225465]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.702191653]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.702917242]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.704314394]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.706034866]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.706629976]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.707466605]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.708269612]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.709186230]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.709724079]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.710215212]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.710929322]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.711643710]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.712166889]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.712632140]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732709524.712861919]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.712927142]: expected goal id 1732706171818207619_/pr2_eus_interface_1732705419350276377_79054_l_arm_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.713012643]: received goal id 1732708710967174113_/pr2_eus_interface_1732708671264581240_88405_l_arm_controller/follow_joint_trajectory_6 +[ WARN] [1732709524.713542544]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.713588657]: expected goal id 1732706171818536140_/pr2_eus_interface_1732705419350276377_79054_r_arm_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.713618721]: received goal id 1732708710967606753_/pr2_eus_interface_1732708671264581240_88405_r_arm_controller/follow_joint_trajectory_6 +[ WARN] [1732709524.714010585]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.714048918]: expected goal id 1732706171818787048_/pr2_eus_interface_1732705419350276377_79054_head_traj_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.714077410]: received goal id 1732708710968082370_/pr2_eus_interface_1732708671264581240_88405_head_traj_controller/follow_joint_trajectory_6 +[ WARN] [1732709524.714476671]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.714515734]: expected goal id 1732706171818975858_/pr2_eus_interface_1732705419350276377_79054_torso_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.714565516]: received goal id 1732708710968332713_/pr2_eus_interface_1732708671264581240_88405_torso_controller/follow_joint_trajectory_6 +[ WARN] [1732709524.714984936]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.715034246]: expected goal id 1732706171818207619_/pr2_eus_interface_1732705419350276377_79054_l_arm_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.715111140]: received goal id 1732708712013257523_/pr2_eus_interface_1732708671264581240_88405_l_arm_controller/follow_joint_trajectory_7 +[ERROR] [1732709524.715616417]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732709524.715663510]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ WARN] [1732709524.715797655]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.715852324]: expected goal id 1732706171818536140_/pr2_eus_interface_1732705419350276377_79054_r_arm_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.715906010]: received goal id 1732708712015390962_/pr2_eus_interface_1732708671264581240_88405_r_arm_controller/follow_joint_trajectory_7 +[ERROR] [1732709524.716584131]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732709524.716657719]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ WARN] [1732709524.716790855]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.716846330]: expected goal id 1732706171818787048_/pr2_eus_interface_1732705419350276377_79054_head_traj_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.716902737]: received goal id 1732708712017024388_/pr2_eus_interface_1732708671264581240_88405_head_traj_controller/follow_joint_trajectory_7 +[ WARN] [1732709524.717712830]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.717806508]: expected goal id 1732706171818975858_/pr2_eus_interface_1732705419350276377_79054_torso_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.717882177]: received goal id 1732708712018631593_/pr2_eus_interface_1732708671264581240_88405_torso_controller/follow_joint_trajectory_7 +[ WARN] [1732709524.718475980]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.718521010]: expected goal id 1732706171818207619_/pr2_eus_interface_1732705419350276377_79054_l_arm_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.718566494]: received goal id 1732708727075856901_/pr2_eus_interface_1732708671264581240_88405_l_arm_controller/follow_joint_trajectory_8 +[ WARN] [1732709524.719029207]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.719069565]: expected goal id 1732706171818536140_/pr2_eus_interface_1732705419350276377_79054_r_arm_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.719119864]: received goal id 1732708727076227448_/pr2_eus_interface_1732708671264581240_88405_r_arm_controller/follow_joint_trajectory_8 +[ WARN] [1732709524.719589184]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.719647400]: expected goal id 1732706171818787048_/pr2_eus_interface_1732705419350276377_79054_head_traj_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.719700510]: received goal id 1732708727076543850_/pr2_eus_interface_1732708671264581240_88405_head_traj_controller/follow_joint_trajectory_8 +[ WARN] [1732709524.720273563]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.720341305]: expected goal id 1732706171818975858_/pr2_eus_interface_1732705419350276377_79054_torso_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.720374571]: received goal id 1732708727076904222_/pr2_eus_interface_1732708671264581240_88405_torso_controller/follow_joint_trajectory_8 +[ WARN] [1732709524.720855608]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.720894523]: expected goal id 1732706171818207619_/pr2_eus_interface_1732705419350276377_79054_l_arm_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.720916639]: received goal id 1732708728093723138_/pr2_eus_interface_1732708671264581240_88405_l_arm_controller/follow_joint_trajectory_9 +[ERROR] [1732709524.721327338]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732709524.721374157]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ WARN] [1732709524.721478849]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.721531029]: expected goal id 1732706171818536140_/pr2_eus_interface_1732705419350276377_79054_r_arm_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.721557904]: received goal id 1732708728096153892_/pr2_eus_interface_1732708671264581240_88405_r_arm_controller/follow_joint_trajectory_9 +[ERROR] [1732709524.722046773]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732709524.722115745]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ WARN] [1732709524.722254558]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.722286113]: expected goal id 1732706171818787048_/pr2_eus_interface_1732705419350276377_79054_head_traj_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.722307895]: received goal id 1732708728096988627_/pr2_eus_interface_1732708671264581240_88405_head_traj_controller/follow_joint_trajectory_9 +[ WARN] [1732709524.722824917]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.722872270]: expected goal id 1732706171818975858_/pr2_eus_interface_1732705419350276377_79054_torso_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.722898426]: received goal id 1732708728097332568_/pr2_eus_interface_1732708671264581240_88405_torso_controller/follow_joint_trajectory_9 +[ WARN] [1732709524.723443900]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.723483297]: expected goal id 1732706171818207619_/pr2_eus_interface_1732705419350276377_79054_l_arm_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.723508120]: received goal id 1732709064228780327_/pr2_eus_interface_1732708671264581240_88405_l_arm_controller/follow_joint_trajectory_10 +[ WARN] [1732709524.723883448]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.723919904]: expected goal id 1732706171818536140_/pr2_eus_interface_1732705419350276377_79054_r_arm_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.723941898]: received goal id 1732709064425537319_/pr2_eus_interface_1732708671264581240_88405_r_arm_controller/follow_joint_trajectory_10 +[ WARN] [1732709524.724276937]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.724324021]: expected goal id 1732706171818787048_/pr2_eus_interface_1732705419350276377_79054_head_traj_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.724360060]: received goal id 1732709064613584499_/pr2_eus_interface_1732708671264581240_88405_head_traj_controller/follow_joint_trajectory_10 +[ WARN] [1732709524.724666384]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.724693876]: expected goal id 1732706171818975858_/pr2_eus_interface_1732705419350276377_79054_torso_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.724714544]: received goal id 1732709064724800240_/pr2_eus_interface_1732708671264581240_88405_torso_controller/follow_joint_trajectory_10 +[ WARN] [1732709524.724984422]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.725009473]: expected goal id 1732706171818207619_/pr2_eus_interface_1732705419350276377_79054_l_arm_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.725029905]: received goal id 1732709068433174760_/pr2_eus_interface_1732708671264581240_88405_l_arm_controller/follow_joint_trajectory_11 +[ WARN] [1732709524.725283035]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.725308879]: expected goal id 1732706171818536140_/pr2_eus_interface_1732705419350276377_79054_r_arm_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.725328799]: received goal id 1732709068633981117_/pr2_eus_interface_1732708671264581240_88405_r_arm_controller/follow_joint_trajectory_11 +[ WARN] [1732709524.725624222]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.725663654]: expected goal id 1732706171818787048_/pr2_eus_interface_1732705419350276377_79054_head_traj_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.725698580]: received goal id 1732709068799349386_/pr2_eus_interface_1732708671264581240_88405_head_traj_controller/follow_joint_trajectory_11 +[ WARN] [1732709524.725971696]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.725998006]: expected goal id 1732706171818975858_/pr2_eus_interface_1732705419350276377_79054_torso_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.726019468]: received goal id 1732709068916249094_/pr2_eus_interface_1732708671264581240_88405_torso_controller/follow_joint_trajectory_11 +[ WARN] [1732709524.726272439]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.726297438]: expected goal id 1732706171818207619_/pr2_eus_interface_1732705419350276377_79054_l_arm_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.726318442]: received goal id 1732709072007086474_/pr2_eus_interface_1732708671264581240_88405_l_arm_controller/follow_joint_trajectory_12 +[ WARN] [1732709524.726584540]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.726608840]: expected goal id 1732706171818536140_/pr2_eus_interface_1732705419350276377_79054_r_arm_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.726629496]: received goal id 1732709072216696859_/pr2_eus_interface_1732708671264581240_88405_r_arm_controller/follow_joint_trajectory_12 +[ WARN] [1732709524.727005510]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.727050292]: expected goal id 1732706171818787048_/pr2_eus_interface_1732705419350276377_79054_head_traj_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.727099994]: received goal id 1732709072374432967_/pr2_eus_interface_1732708671264581240_88405_head_traj_controller/follow_joint_trajectory_12 +[ WARN] [1732709524.727592138]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.727629021]: expected goal id 1732706171818975858_/pr2_eus_interface_1732705419350276377_79054_torso_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.727677059]: received goal id 1732709072482006629_/pr2_eus_interface_1732708671264581240_88405_torso_controller/follow_joint_trajectory_12 +[ WARN] [1732709524.728199636]: [l_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.728257478]: expected goal id 1732706171818207619_/pr2_eus_interface_1732705419350276377_79054_l_arm_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.728311841]: received goal id 1732709084595058622_/pr2_eus_interface_1732708671264581240_88405_l_arm_controller/follow_joint_trajectory_13 +[ WARN] [1732709524.728878548]: [r_arm_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.728928790]: expected goal id 1732706171818536140_/pr2_eus_interface_1732705419350276377_79054_r_arm_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.728973748]: received goal id 1732709084884182663_/pr2_eus_interface_1732708671264581240_88405_r_arm_controller/follow_joint_trajectory_13 +[ WARN] [1732709524.729462479]: [head_traj_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.729508679]: expected goal id 1732706171818787048_/pr2_eus_interface_1732705419350276377_79054_head_traj_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.729553644]: received goal id 1732709085113226827_/pr2_eus_interface_1732708671264581240_88405_head_traj_controller/follow_joint_trajectory_13 +[ WARN] [1732709524.729865945]: [torso_controller/follow_joint_trajectory] action-result-cb may received old client's goal +[ WARN] [1732709524.729894794]: expected goal id 1732706171818975858_/pr2_eus_interface_1732705419350276377_79054_torso_controller/follow_joint_trajectory_115 +[ WARN] [1732709524.729916657]: received goal id 1732709085260202375_/pr2_eus_interface_1732708671264581240_88405_torso_controller/follow_joint_trajectory_13 +(t t) +43.B10-irteusgl$ load "main.l" +Call Stack (max depth: 20): + 0: at (apply #'ros::load-org-for-ros ros::fullname args) + 1: at (apply #'ros::load-org-for-ros ros::fullname args) + 2: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 3: at (load "main.l") + 4: at sigint-handler + 5: at sigint-handler + 6: at (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (print 0) (ros::sleep) (ros::spin-once)) + 7: at (let ((#:prog110265185 (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (print 0) (ros::sleep) (ros::spin-once)))) (progn (let ((strm (car (select-stream (list *standard-input*) 0.1)))) (if strm (read-line strm nil nil)))) #:prog110265185) + 8: at (prog1 (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (print 0) (ros::sleep) (ros::spin-once)) (let ((strm (car (select-stream (list *standard-input*) 0.1)))) (if strm (read-line strm nil nil)))) + 9: at (do-until-key-with-check t (print 0) (ros::sleep) (ros::spin-once)) + 10: at (do-until-key (print 0) (ros::sleep) (ros::spin-once)) + 11: at (progn (ros::rate 1) (do-until-key (print 0) (ros::sleep) (ros::spin-once))) + 12: at euserror + 13: at euserror + 14: at (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (print 0) (ros::sleep) (ros::spin-onec)) + 15: at (let ((#:prog110265183 (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (print 0) (ros::sleep) (ros::spin-onec)))) (progn (let ((strm (car (select-stream (list *standard-input*) 0.1)))) (if strm (read-line strm nil nil)))) #:prog110265183) + 16: at (prog1 (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (print 0) (ros::sleep) (ros::spin-onec)) (let ((strm (car (select-stream (list *standard-input*) 0.1)))) (if strm (read-line strm nil nil)))) + 17: at (do-until-key-with-check t (print 0) (ros::sleep) (ros::spin-onec)) + 18: at (do-until-key (print 0) (ros::sleep) (ros::spin-onec)) + 19: at (progn (ros::rate 1) (do-until-key (print 0) (ros::sleep) (ros::spin-onec))) + And more... +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: no such package SPEECH_RECOGNITION_MSGS in (apply #'ros::load-org-for-ros ros::fullname args) +44.E11-irteusgl$ load "main.l" +Call Stack (max depth: 20): + 0: at (apply #'ros::load-org-for-ros ros::fullname args) + 1: at (apply #'ros::load-org-for-ros ros::fullname args) + 2: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 3: at (load "main.l") + 4: at euserror + 5: at euserror + 6: at (apply #'ros::load-org-for-ros ros::fullname args) + 7: at (apply #'ros::load-org-for-ros ros::fullname args) + 8: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 9: at (load "main.l") + 10: at sigint-handler + 11: at sigint-handler + 12: at (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (print 0) (ros::sleep) (ros::spin-once)) + 13: at (let ((#:prog110265185 (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (print 0) (ros::sleep) (ros::spin-once)))) (progn (let ((strm (car (select-stream (list *standard-input*) 0.1)))) (if strm (read-line strm nil nil)))) #:prog110265185) + 14: at (prog1 (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (print 0) (ros::sleep) (ros::spin-once)) (let ((strm (car (select-stream (list *standard-input*) 0.1)))) (if strm (read-line strm nil nil)))) + 15: at (do-until-key-with-check t (print 0) (ros::sleep) (ros::spin-once)) + 16: at (do-until-key (print 0) (ros::sleep) (ros::spin-once)) + 17: at (progn (ros::rate 1) (do-until-key (print 0) (ros::sleep) (ros::spin-once))) + 18: at euserror + 19: at euserror + And more... +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: no such package DEBUG in (apply #'ros::load-org-for-ros ros::fullname args) +45.E12-irteusgl$ rest +Call Stack (max depth: 20): + 0: at (rest) + 1: at euserror + 2: at euserror + 3: at (apply #'ros::load-org-for-ros ros::fullname args) + 4: at (apply #'ros::load-org-for-ros ros::fullname args) + 5: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 6: at (load "main.l") + 7: at euserror + 8: at euserror + 9: at (apply #'ros::load-org-for-ros ros::fullname args) + 10: at (apply #'ros::load-org-for-ros ros::fullname args) + 11: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 12: at (load "main.l") + 13: at sigint-handler + 14: at sigint-handler + 15: at (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (print 0) (ros::sleep) (ros::spin-once)) + 16: at (let ((#:prog110265185 (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (print 0) (ros::sleep) (ros::spin-once)))) (progn (let ((strm (car (select-stream (list *standard-input*) 0.1)))) (if strm (read-line strm nil nil)))) #:prog110265185) + 17: at (prog1 (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (print 0) (ros::sleep) (ros::spin-once)) (let ((strm (car (select-stream (list *standard-input*) 0.1)))) (if strm (read-line strm nil nil)))) + 18: at (do-until-key-with-check t (print 0) (ros::sleep) (ros::spin-once)) + 19: at (do-until-key (print 0) (ros::sleep) (ros::spin-once)) + And more... +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: mismatch argument in (rest) +46.E13-irteusgl$ reset +47.irteusgl$ load "main.l" +t +48.irteusgl$ load "main.l" +[ WARN] [1732709608.395697617]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732709608.395736025]: expected goal id 1732709608394766244_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_20 +[ WARN] [1732709608.395750760]: received goal id /battery_warning-106-1732708820.966 +[ WARN] [1732709608.396001806]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732709608.396021331]: expected goal id 1732709608394766244_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_20 +[ WARN] [1732709608.396037091]: received goal id 1732709000431450098_/tweet_client_warning_473265_robotsound_jp_81 +[ WARN] [1732709608.396247113]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732709608.396266271]: expected goal id 1732709608394766244_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_20 +[ WARN] [1732709608.396280866]: received goal id 1732709001436293410_/tweet_client_warning_473265_robotsound_jp_82 +[ WARN] [1732709608.396513672]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732709608.396543390]: expected goal id 1732709608394766244_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_20 +[ WARN] [1732709608.396571323]: received goal id 1732709002504808985_/tweet_client_warning_473265_robotsound_jp_83 +[ WARN] [1732709608.396775196]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732709608.396801440]: expected goal id 1732709608394766244_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_20 +[ WARN] [1732709608.396827918]: received goal id /battery_warning-107-1732709004.966 +[ WARN] [1732709608.397176186]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732709608.397216048]: expected goal id 1732709608394766244_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_20 +[ WARN] [1732709608.397240168]: received goal id /battery_warning-108-1732709188.966 +[ WARN] [1732709608.397598453]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732709608.397632146]: expected goal id 1732709608394766244_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_20 +[ WARN] [1732709608.397661446]: received goal id /battery_warning-109-1732709372.966 +[ WARN] [1732709608.398004679]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732709608.398036392]: expected goal id 1732709608394766244_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_20 +[ WARN] [1732709608.398065102]: received goal id /battery_warning-110-1732709556.966 +[ WARN] [1732709612.297730566]: [/r_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732709612.297768041]: expected goal id 1732709612289473157_/pr2_eus_interface_1732705419350276377_79054_/r_gripper_controller/gripper_action_40 +[ WARN] [1732709612.297783170]: received goal id 1732709524612434376_/pr2_eus_interface_1732705419350276377_79054_/r_gripper_controller/gripper_action_39 +[ WARN] [1732709612.333550357]: [/l_gripper_controller/gripper_action] action-result-cb may received old client's goal +[ WARN] [1732709612.333589392]: expected goal id 1732709612289658379_/pr2_eus_interface_1732705419350276377_79054_/l_gripper_controller/gripper_action_40 +[ WARN] [1732709612.333606489]: received goal id 1732709524613276932_/pr2_eus_interface_1732705419350276377_79054_/l_gripper_controller/gripper_action_39 +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(75.522) violate max-angle(74.2702) +[ WARN] [1732709614.779410462]: continuous joint (r_forearm_roll_joint) moves -399.134 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(75.522) violate max-angle(74.2702) +;; # :joint-angle(75.522) violate max-angle(74.2702) +[ WARN] [1732709614.784115155]: continuous joint (r_forearm_roll_joint) moves -399.134 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732709614.784170478]: original trajectory command : +[ WARN] [1732709614.784193991]: : (#f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (1000) +[ WARN] [1732709614.784218532]: current angle vector : #f(232.41 63.4563 -3.8434 67.1743 -17.1686 95.4859 -95.1324 251.873 -36.1094 28.2229 -93.097 -107.664 379.134 -5.72958 91.7335 3.48553 74.2702) +[ WARN] [1732709614.784231988]: new trajectory command : dvi = 3 +[ WARN] [1732709614.784260615]: : #f(171.607 62.3042 22.1044 68.1162 -51.4457 70.3239 -73.4216 227.915 -44.0729 43.4819 -85.398 -111.776 246.089 -13.8197 121.156 2.32369 49.5135) 333 +[ WARN] [1732709614.784295875]: : #f(110.803 61.1521 48.0522 69.0581 -85.7229 45.162 -51.7108 203.958 -52.0365 58.741 -77.699 -115.888 113.045 -21.9099 150.578 1.16184 24.7567) 333 +[ WARN] [1732709614.784317757]: : #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0) 333 +[ WARN] [1732709614.784329959]: new trajectory command : +[ WARN] [1732709614.784369132]: : (#f(171.607 62.3042 22.1044 68.1162 -51.4457 70.3239 -73.4216 227.915 -44.0729 43.4819 -85.398 -111.776 246.089 -13.8197 121.156 2.32369 49.5135) #f(110.803 61.1521 48.0522 69.0581 -85.7229 45.162 -51.7108 203.958 -52.0365 58.741 -77.699 -115.888 113.045 -21.9099 150.578 1.16184 24.7567) #f(50.0 60.0 74.0 70.0 -120.0 20.0 -30.0 180.0 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 0.0)) (333 333 333) +;; # :joint-angle(75.522) violate max-angle(74.2702) +[ INFO] [1732709614.787916373]: wait-interpolation debug: start +[ERROR] [1732709628.939797122]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732709628.939881528]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732709628.958207633]: wait-interpolation debug: end +[ INFO] [1732709632.087251757]: wait-interpolation debug: start +[ERROR] [1732709633.680580195]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732709633.680703117]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732709633.688502076]: wait-interpolation debug: end +[ INFO] [1732709639.706363547]: wait-interpolation debug: start +[ INFO] [1732709639.714336584]: wait-interpolation debug: end +[ INFO] [1732709639.716076931]: start waiting for call + +Call Stack (max depth: 20): + 0: at (while (not (eq *start-flag* 1)) (ros::spin-once) (ros::sleep) (ros::info "wait for voice command ...")) + 1: at (detect-voice) + 2: at (apply #'ros::load-org-for-ros ros::fullname args) + 3: at (apply #'ros::load-org-for-ros ros::fullname args) + 4: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 5: at (load "main.l") + 6: at # +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: undefined function ros::info in (while (not (eq *start-flag* 1)) (ros::spin-once) (ros::sleep) (ros::info "wait for voice command ...")) +49.E1-irteusgl$ (ros::ros-info "wait for voice command ...") +[ INFO] [1732709655.168823212]: wait for voice command ... +t +50.E1-irteusgl$ load "main.l" +[ INFO] [1732709662.986399442]: wait-interpolation debug: start +[ERROR] [1732709664.571288072]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732709664.571331020]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732709664.573954461]: wait-interpolation debug: end +[ INFO] [1732709664.996217260]: wait-interpolation debug: start +[ERROR] [1732709666.582661681]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732709666.582703128]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732709666.583364922]: wait-interpolation debug: end +[ INFO] [1732709672.500047869]: wait-interpolation debug: start +[ INFO] [1732709672.509801844]: wait-interpolation debug: end +[ INFO] [1732709672.514481527]: start waiting for call + +[ INFO] [1732709672.546267389]: wait for voice command ... +[ INFO] [1732709672.556484760]: wait for voice command ... +[ INFO] [1732709672.566384070]: wait for voice command ... +[ INFO] [1732709672.576424180]: wait for voice command ... +[ INFO] [1732709672.586913461]: wait for voice command ... +[ INFO] [1732709672.596418492]: wait for voice command ... +[ INFO] [1732709672.606430484]: wait for voice command ... +[ INFO] [1732709672.616350552]: wait for voice command ... +[ INFO] [1732709672.626372646]: wait for voice command ... +[ INFO] [1732709672.636393732]: wait for voice command ... +[ INFO] [1732709672.646507189]: wait for voice command ... +[ INFO] [1732709672.656438019]: wait for voice command ... +[ INFO] [1732709672.666456480]: wait for voice command ... +[ INFO] [1732709672.676445413]: wait for voice command ... +[ INFO] [1732709672.686411267]: wait for voice command ... +[ INFO] [1732709672.696388368]: wait for voice command ... +[ INFO] [1732709672.706486903]: wait for voice command ... +[ INFO] [1732709672.716380818]: wait for voice command ... +[ INFO] [1732709672.726333372]: wait for voice command ... +[ INFO] [1732709672.736372077]: wait for voice command ... +[ INFO] [1732709672.746349434]: wait for voice command ... +[ INFO] [1732709672.756347826]: wait for voice command ... +[ INFO] [1732709672.766347689]: wait for voice command ... +[ INFO] [1732709672.776428143]: wait for voice command ... +[ INFO] [1732709672.786372663]: wait for voice command ... +[ INFO] [1732709672.796404637]: wait for voice command ... +[ INFO] [1732709672.806446220]: wait for voice command ... +[ INFO] [1732709672.816404617]: wait for voice command ... +[ INFO] [1732709672.826367402]: wait for voice command ... +[ INFO] [1732709672.836347577]: wait for voice command ... +[ INFO] [1732709672.846390825]: wait for voice command ... +[ INFO] [1732709672.856366754]: wait for voice command ... +[ INFO] [1732709672.866375079]: wait for voice command ... +[ INFO] [1732709672.876440924]: wait for voice command ... +[ INFO] [1732709672.886506683]: wait for voice command ... +[ INFO] [1732709672.896436264]: wait for voice command ... +[ INFO] [1732709672.906457854]: wait for voice command ... +[ INFO] [1732709672.916460856]: wait for voice command ... +[ INFO] [1732709672.926385795]: wait for voice command ... +[ INFO] [1732709672.936386118]: wait for voice command ... +[ INFO] [1732709672.946383137]: wait for voice command ... +[ INFO] [1732709672.956422794]: wait for voice command ... +[ INFO] [1732709672.966399829]: wait for voice command ... +[ INFO] [1732709672.976367786]: wait for voice command ... +[ INFO] [1732709672.986440935]: wait for voice command ... +[ INFO] [1732709672.996436138]: wait for voice command ... +[ INFO] [1732709673.006450970]: wait for voice command ... +[ INFO] [1732709673.016452152]: wait for voice command ... +[ INFO] [1732709673.026458682]: wait for voice command ... +[ INFO] [1732709673.036381647]: wait for voice command ... +[ INFO] [1732709673.046383978]: wait for voice command ... +[ INFO] [1732709673.056378415]: wait for voice command ... +[ INFO] [1732709673.066629385]: wait for voice command ... +[ INFO] [1732709673.076379632]: wait for voice command ... +[ INFO] [1732709673.086392976]: wait for voice command ... +[ INFO] [1732709673.096436465]: wait for voice command ... +[ INFO] [1732709673.106348573]: wait for voice command ... +[ INFO] [1732709673.116403234]: wait for voice command ... +[ INFO] [1732709673.126450848]: wait for voice command ... +[ INFO] [1732709673.136362369]: wait for voice command ... +[ INFO] [1732709673.146479155]: wait for voice command ... +[ INFO] [1732709673.156421451]: wait for voice command ... +[ INFO] [1732709673.166432199]: wait for voice command ... +[ INFO] [1732709673.176443842]: wait for voice command ... +[ INFO] [1732709673.186440571]: wait for voice command ... +[ INFO] [1732709673.196404708]: wait for voice command ... +[ INFO] [1732709673.206451192]: wait for voice command ... +[ INFO] [1732709673.216444871]: wait for voice command ... +[ INFO] [1732709673.226347797]: wait for voice command ... +[ INFO] [1732709673.236366599]: wait for voice command ... +[ INFO] [1732709673.246468959]: wait for voice command ... +[ INFO] [1732709673.256461048]: wait for voice command ... +[ INFO] [1732709673.266388587]: wait for voice command ... +[ INFO] [1732709673.276361941]: wait for voice command ... +[ INFO] [1732709673.286359405]: wait for voice command ... +[ INFO] [1732709673.296343173]: wait for voice command ... +[ INFO] [1732709673.306438581]: wait for voice command ... +[ INFO] [1732709673.316438895]: wait for voice command ... +[ INFO] [1732709673.326402272]: wait for voice command ... +[ INFO] [1732709673.336366078]: wait for voice command ... +[ INFO] [1732709673.346413749]: wait for voice command ... +[ INFO] [1732709673.356413706]: wait for voice command ... +[ INFO] [1732709673.366430112]: wait for voice command ... +[ INFO] [1732709673.376366604]: wait for voice command ... +[ INFO] [1732709673.386425638]: wait for voice command ... +[ INFO] [1732709673.396378681]: wait for voice command ... +[ INFO] [1732709673.406441786]: wait for voice command ... +[ INFO] [1732709673.416446532]: wait for voice command ... +[ INFO] [1732709673.426359801]: wait for voice command ... +[ INFO] [1732709673.436355256]: wait for voice command ... +[ INFO] [1732709673.446432227]: wait for voice command ... +[ INFO] [1732709673.456370009]: wait for voice command ... +[ INFO] [1732709673.466436788]: wait for voice command ... +[ INFO] [1732709673.476452055]: wait for voice command ... +[ INFO] [1732709673.486385606]: wait for voice command ... +[ INFO] [1732709673.496434816]: wait for voice command ... +[ INFO] [1732709673.506382433]: wait for voice command ... +[ INFO] [1732709673.516400656]: wait for voice command ... +[ INFO] [1732709673.526440281]: wait for voice command ... +[ INFO] [1732709673.536391546]: wait for voice command ... +[ INFO] [1732709673.546345305]: wait for voice command ... +[ INFO] [1732709673.556400136]: wait for voice command ... +[ INFO] [1732709673.566433799]: wait for voice command ... +[ INFO] [1732709673.576442759]: wait for voice command ... +[ INFO] [1732709673.586451363]: wait for voice command ... +[ INFO] [1732709673.596408928]: wait for voice command ... +[ INFO] [1732709673.606439975]: wait for voice command ... +[ INFO] [1732709673.616453813]: wait for voice command ... +[ INFO] [1732709673.626386484]: wait for voice command ... +[ INFO] [1732709673.636384364]: wait for voice command ... +[ INFO] [1732709673.646384506]: wait for voice command ... +[ INFO] [1732709673.656375340]: wait for voice command ... +[ INFO] [1732709673.666328780]: wait for voice command ... +[ INFO] [1732709673.676482388]: wait for voice command ... +[ INFO] [1732709673.686332556]: wait for voice command ... +[ INFO] [1732709673.696433540]: wait for voice command ... +[ INFO] [1732709673.706493684]: wait for voice command ... +[ INFO] [1732709673.716436901]: wait for voice command ... +[ INFO] [1732709673.726448733]: wait for voice command ... +[ INFO] [1732709673.736456448]: wait for voice command ... +[ INFO] [1732709673.746507441]: wait for voice command ... +[ INFO] [1732709673.756448074]: wait for voice command ... +[ INFO] [1732709673.766433034]: wait for voice command ... +[ INFO] [1732709673.776405151]: wait for voice command ... +[ INFO] [1732709673.786405079]: wait for voice command ... +[ INFO] [1732709673.796411217]: wait for voice command ... +[ INFO] [1732709673.806441733]: wait for voice command ... +[ INFO] [1732709673.816390796]: wait for voice command ... +[ INFO] [1732709673.826446219]: wait for voice command ... +[ INFO] [1732709673.836420176]: wait for voice command ... +[ INFO] [1732709673.846446948]: wait for voice command ... +[ INFO] [1732709673.856390699]: wait for voice command ... +[ INFO] [1732709673.866430639]: wait for voice command ... +[ INFO] [1732709673.876428692]: wait for voice command ... +[ INFO] [1732709673.886452673]: wait for voice command ... +[ INFO] [1732709673.896397501]: wait for voice command ... +[ INFO] [1732709673.906371017]: wait for voice command ... +[ INFO] [1732709673.916364682]: wait for voice command ... +[ INFO] [1732709673.926379165]: wait for voice command ... +[ INFO] [1732709673.936345597]: wait for voice command ... +[ INFO] [1732709673.946368958]: wait for voice command ... +[ INFO] [1732709673.956435297]: wait for voice command ... +[ INFO] [1732709673.966460952]: wait for voice command ... +[ INFO] [1732709673.976470092]: wait for voice command ... +[ INFO] [1732709673.986449537]: wait for voice command ... +[ INFO] [1732709673.996391450]: wait for voice command ... +[ INFO] [1732709674.006398122]: wait for voice command ... +[ INFO] [1732709674.016420885]: wait for voice command ... +[ INFO] [1732709674.026362343]: wait for voice command ... +[ INFO] [1732709674.036391613]: wait for voice command ... +[ INFO] [1732709674.046331594]: wait for voice command ... +[ INFO] [1732709674.056402554]: wait for voice command ... +[ INFO] [1732709674.066438975]: wait for voice command ... +[ INFO] [1732709674.076431295]: wait for voice command ... +[ INFO] [1732709674.086449967]: wait for voice command ... +[ INFO] [1732709674.096390052]: wait for voice command ... +[ INFO] [1732709674.106437770]: wait for voice command ... +[ INFO] [1732709674.116428878]: wait for voice command ... +[ INFO] [1732709674.126421169]: wait for voice command ... +[ INFO] [1732709674.136436459]: wait for voice command ... +[ INFO] [1732709674.146423212]: wait for voice command ... +[ INFO] [1732709674.156461067]: wait for voice command ... +[ INFO] [1732709674.166425573]: wait for voice command ... +[ INFO] [1732709674.176481719]: wait for voice command ... +[ INFO] [1732709674.186353492]: wait for voice command ... +[ INFO] [1732709674.196332963]: wait for voice command ... +[ INFO] [1732709674.206468963]: wait for voice command ... +[ INFO] [1732709674.216375102]: wait for voice command ... +[ INFO] [1732709674.226467146]: wait for voice command ... +[ INFO] [1732709674.236374753]: wait for voice command ... +[ INFO] [1732709674.246455360]: wait for voice command ... +[ INFO] [1732709674.256393167]: wait for voice command ... +[ INFO] [1732709674.266399913]: wait for voice command ... +[ INFO] [1732709674.276386052]: wait for voice command ... +[ INFO] [1732709674.286373352]: wait for voice command ... +[ INFO] [1732709674.296431468]: wait for voice command ... +[ INFO] [1732709674.306430822]: wait for voice command ... +[ INFO] [1732709674.316426774]: wait for voice command ... +[ INFO] [1732709674.326402434]: wait for voice command ... +[ INFO] [1732709674.336425961]: wait for voice command ... +[ INFO] [1732709674.346401082]: wait for voice command ... +[ INFO] [1732709674.356370556]: wait for voice command ... +[ INFO] [1732709674.366364940]: wait for voice command ... +[ INFO] [1732709674.376376621]: wait for voice command ... +[ INFO] [1732709674.386331639]: wait for voice command ... +[ INFO] [1732709674.396337804]: wait for voice command ... +[ INFO] [1732709674.406547559]: wait for voice command ... +[ INFO] [1732709674.416375150]: wait for voice command ... +[ INFO] [1732709674.426322482]: wait for voice command ... +[ INFO] [1732709674.436432183]: wait for voice command ... +[ INFO] [1732709674.446325014]: wait for voice command ... +[ INFO] [1732709674.456528129]: wait for voice command ... +[ INFO] [1732709674.466511580]: wait for voice command ... +[ INFO] [1732709674.476435105]: wait for voice command ... +[ INFO] [1732709674.486426116]: wait for voice command ... +[ INFO] [1732709674.496437840]: wait for voice command ... +[ INFO] [1732709674.506422104]: wait for voice command ... +[ INFO] [1732709674.516441426]: wait for voice command ... +[ INFO] [1732709674.526439408]: wait for voice command ... +[ INFO] [1732709674.536383297]: wait for voice command ... +[ INFO] [1732709674.546553802]: wait for voice command ... +[ INFO] [1732709674.556427823]: wait for voice command ... +[ INFO] [1732709674.566462506]: wait for voice command ... +[ INFO] [1732709674.576426166]: wait for voice command ... +[ INFO] [1732709674.586407408]: wait for voice command ... +[ INFO] [1732709674.596590300]: wait for voice command ... +[ INFO] [1732709674.606430538]: wait for voice command ... +[ INFO] [1732709674.616432075]: wait for voice command ... +[ INFO] [1732709674.626398076]: wait for voice command ... +[ INFO] [1732709674.636407103]: wait for voice command ... +[ INFO] [1732709674.646446714]: wait for voice command ... +[ INFO] [1732709674.656483346]: wait for voice command ... +[ INFO] [1732709674.666440946]: wait for voice command ... +[ INFO] [1732709674.676437557]: wait for voice command ... +[ INFO] [1732709674.686405058]: wait for voice command ... +[ INFO] [1732709674.696463504]: wait for voice command ... +[ INFO] [1732709674.706336957]: wait for voice command ... +[ INFO] [1732709674.716369525]: wait for voice command ... +[ INFO] [1732709674.726346631]: wait for voice command ... +[ INFO] [1732709674.736406701]: wait for voice command ... +[ INFO] [1732709674.746351000]: wait for voice command ... +[ INFO] [1732709674.756393374]: wait for voice command ... +[ INFO] [1732709674.766374165]: wait for voice command ... +[ INFO] [1732709674.776457763]: wait for voice command ... +[ INFO] [1732709674.786393732]: wait for voice command ... +[ INFO] [1732709674.796438353]: wait for voice command ... +[ INFO] [1732709674.806417765]: wait for voice command ... +[ INFO] [1732709674.816385267]: wait for voice command ... +[ INFO] [1732709674.826423032]: wait for voice command ... +[ INFO] [1732709674.836442716]: wait for voice command ... +[ INFO] [1732709674.846381928]: wait for voice command ... +[ INFO] [1732709674.856431697]: wait for voice command ... +[ INFO] [1732709674.866483859]: wait for voice command ... +[ INFO] [1732709674.876368952]: wait for voice command ... +[ INFO] [1732709674.886362564]: wait for voice command ... +[ INFO] [1732709674.896418110]: wait for voice command ... +[ INFO] [1732709674.906410542]: wait for voice command ... +[ INFO] [1732709674.916403308]: wait for voice command ... +[ INFO] [1732709674.926412378]: wait for voice command ... +[ INFO] [1732709674.936416475]: wait for voice command ... +[ INFO] [1732709674.946434260]: wait for voice command ... +[ INFO] [1732709674.956410043]: wait for voice command ... +[ INFO] [1732709674.966424401]: wait for voice command ... +[ INFO] [1732709674.976413323]: wait for voice command ... +[ INFO] [1732709674.986442287]: wait for voice command ... +[ INFO] [1732709674.996417996]: wait for voice command ... +[ INFO] [1732709675.006426002]: wait for voice command ... +[ INFO] [1732709675.016419375]: wait for voice command ... +[ INFO] [1732709675.026411693]: wait for voice command ... +[ INFO] [1732709675.036370636]: wait for voice command ... +[ INFO] [1732709675.046362670]: wait for voice command ... +[ INFO] [1732709675.056385850]: wait for voice command ... +[ INFO] [1732709675.066450717]: wait for voice command ... +[ INFO] [1732709675.076429049]: wait for voice command ... +[ INFO] [1732709675.086408278]: wait for voice command ... +[ INFO] [1732709675.096414109]: wait for voice command ... +[ INFO] [1732709675.106392233]: wait for voice command ... +[ INFO] [1732709675.116364177]: wait for voice command ... +[ INFO] [1732709675.126485569]: wait for voice command ... +[ INFO] [1732709675.136412212]: wait for voice command ... +[ INFO] [1732709675.146368757]: wait for voice command ... +[ INFO] [1732709675.156464507]: wait for voice command ... +[ INFO] [1732709675.166439451]: wait for voice command ... +[ INFO] [1732709675.176368666]: wait for voice command ... +[ INFO] [1732709675.186476118]: wait for voice command ... +[ INFO] [1732709675.196448257]: wait for voice command ... +[ INFO] [1732709675.206446739]: wait for voice command ... +[ INFO] [1732709675.216420733]: wait for voice command ... +[ INFO] [1732709675.226424814]: wait for voice command ... +[ INFO] [1732709675.236390067]: wait for voice command ... +[ INFO] [1732709675.246346831]: wait for voice command ... +[ INFO] [1732709675.256387844]: wait for voice command ... +[ INFO] [1732709675.266450842]: wait for voice command ... +[ INFO] [1732709675.276339502]: wait for voice command ... +[ INFO] [1732709675.286384816]: wait for voice command ... +[ INFO] [1732709675.296336403]: wait for voice command ... +[ INFO] [1732709675.306442631]: wait for voice command ... +[ INFO] [1732709675.316423755]: wait for voice command ... +[ INFO] [1732709675.326430176]: wait for voice command ... +[ INFO] [1732709675.336435258]: wait for voice command ... +[ INFO] [1732709675.346394108]: wait for voice command ... +[ INFO] [1732709675.356455696]: wait for voice command ... +[ INFO] [1732709675.366412791]: wait for voice command ... +[ INFO] [1732709675.376399519]: wait for voice command ... +[ INFO] [1732709675.386435494]: wait for voice command ... +[ INFO] [1732709675.396362524]: wait for voice command ... +[ INFO] [1732709675.406471044]: wait for voice command ... +[ INFO] [1732709675.416384597]: wait for voice command ... +[ INFO] [1732709675.426383128]: wait for voice command ... +[ INFO] [1732709675.436394890]: wait for voice command ... +[ INFO] [1732709675.446352439]: wait for voice command ... +[ INFO] [1732709675.456392861]: wait for voice command ... +[ INFO] [1732709675.466413530]: wait for voice command ... +[ INFO] [1732709675.476469530]: wait for voice command ... +[ INFO] [1732709675.486413545]: wait for voice command ... +[ INFO] [1732709675.496378392]: wait for voice command ... +[ INFO] [1732709675.506492556]: wait for voice command ... +[ INFO] [1732709675.516336696]: wait for voice command ... +[ INFO] [1732709675.526328645]: wait for voice command ... +[ INFO] [1732709675.536345226]: wait for voice command ... +[ INFO] [1732709675.546456403]: wait for voice command ... +[ INFO] [1732709675.556410013]: wait for voice command ... +[ INFO] [1732709675.566456524]: wait for voice command ... +[ INFO] [1732709675.576458620]: wait for voice command ... +[ INFO] [1732709675.586387596]: wait for voice command ... +[ INFO] [1732709675.596444735]: wait for voice command ... +[ INFO] [1732709675.606417539]: wait for voice command ... +[ INFO] [1732709675.616453442]: wait for voice command ... +[ INFO] [1732709675.626439709]: wait for voice command ... +[ INFO] [1732709675.636448038]: wait for voice command ... +[ INFO] [1732709675.646422079]: wait for voice command ... +[ INFO] [1732709675.656435903]: wait for voice command ... +[ INFO] [1732709675.666572934]: wait for voice command ... +[ INFO] [1732709675.676397590]: wait for voice command ... +[ INFO] [1732709675.686441873]: wait for voice command ... +[ INFO] [1732709675.696840479]: wait for voice command ... +[ INFO] [1732709675.706474350]: wait for voice command ... +[ INFO] [1732709675.716411946]: wait for voice command ... +[ INFO] [1732709675.726351286]: wait for voice command ... +[ INFO] [1732709675.736412007]: wait for voice command ... +[ INFO] [1732709675.746352967]: wait for voice command ... +[ INFO] [1732709675.756349960]: wait for voice command ... +[ INFO] [1732709675.766338552]: wait for voice command ... +[ INFO] [1732709675.776329525]: wait for voice command ... +[ INFO] [1732709675.786379035]: wait for voice command ... +[ INFO] [1732709675.796461314]: wait for voice command ... +[ INFO] [1732709675.806511859]: wait for voice command ... +[ INFO] [1732709675.816377162]: wait for voice command ... +[ INFO] [1732709675.826413636]: wait for voice command ... +[ INFO] [1732709675.836335741]: wait for voice command ... +[ INFO] [1732709675.846376194]: wait for voice command ... +[ INFO] [1732709675.856343964]: wait for voice command ... +[ INFO] [1732709675.866503518]: wait for voice command ... +[ INFO] [1732709675.876464378]: wait for voice command ... +[ INFO] [1732709675.886379277]: wait for voice command ... +[ INFO] [1732709675.896367044]: wait for voice command ... +[ INFO] [1732709675.906466503]: wait for voice command ... +[ INFO] [1732709675.916379599]: wait for voice command ... +[ INFO] [1732709675.926348694]: wait for voice command ... +[ INFO] [1732709675.936422633]: wait for voice command ... +[ INFO] [1732709675.946389211]: wait for voice command ... +[ INFO] [1732709675.956411377]: wait for voice command ... +[ INFO] [1732709675.966434703]: wait for voice command ... +[ INFO] [1732709675.976427175]: wait for voice command ... +[ INFO] [1732709675.986367252]: wait for voice command ... +[ INFO] [1732709675.996420540]: wait for voice command ... +[ INFO] [1732709676.006455789]: wait for voice command ... +[ INFO] [1732709676.016447457]: wait for voice command ... +[ INFO] [1732709676.026461225]: wait for voice command ... +[ INFO] [1732709676.036407303]: wait for voice command ... +[ INFO] [1732709676.046422463]: wait for voice command ... +[ INFO] [1732709676.056430006]: wait for voice command ... +[ INFO] [1732709676.066446198]: wait for voice command ... +[ INFO] [1732709676.076427647]: wait for voice command ... +[ INFO] [1732709676.086360812]: wait for voice command ... +[ INFO] [1732709676.096405969]: wait for voice command ... +[ INFO] [1732709676.106353841]: wait for voice command ... +[ INFO] [1732709676.116358824]: wait for voice command ... +[ INFO] [1732709676.126400979]: wait for voice command ... +[ INFO] [1732709676.136385491]: wait for voice command ... +[ INFO] [1732709676.146383962]: wait for voice command ... +[ INFO] [1732709676.156456511]: wait for voice command ... +[ INFO] [1732709676.166451889]: wait for voice command ... +[ INFO] [1732709676.176375336]: wait for voice command ... +[ INFO] [1732709676.186461694]: wait for voice command ... +[ INFO] [1732709676.196423080]: wait for voice command ... +[ INFO] [1732709676.206377856]: wait for voice command ... +[ INFO] [1732709676.216400496]: wait for voice command ... +[ INFO] [1732709676.226362718]: wait for voice command ... +[ INFO] [1732709676.236393501]: wait for voice command ... +[ INFO] [1732709676.246412275]: wait for voice command ... +[ INFO] [1732709676.256405657]: wait for voice command ... +[ INFO] [1732709676.266442796]: wait for voice command ... +[ INFO] [1732709676.276435636]: wait for voice command ... +[ INFO] [1732709676.286432987]: wait for voice command ... +[ INFO] [1732709676.296379636]: wait for voice command ... +[ INFO] [1732709676.306422987]: wait for voice command ... +[ INFO] [1732709676.316451597]: wait for voice command ... +[ INFO] [1732709676.326432660]: wait for voice command ... +[ INFO] [1732709676.336477155]: wait for voice command ... +[ INFO] [1732709676.346444097]: wait for voice command ... +[ INFO] [1732709676.356405595]: wait for voice command ... +[ INFO] [1732709676.366433514]: wait for voice command ... +[ INFO] [1732709676.376360554]: wait for voice command ... +[ INFO] [1732709676.386345441]: wait for voice command ... +[ INFO] [1732709676.396458723]: wait for voice command ... +[ INFO] [1732709676.406415115]: wait for voice command ... +[ INFO] [1732709676.416425431]: wait for voice command ... +[ INFO] [1732709676.426413060]: wait for voice command ... +[ INFO] [1732709676.436359916]: wait for voice command ... +[ INFO] [1732709676.446333661]: wait for voice command ... +[ INFO] [1732709676.456359691]: wait for voice command ... +[ INFO] [1732709676.466362983]: wait for voice command ... +[ INFO] [1732709676.476377083]: wait for voice command ... +[ INFO] [1732709676.486370090]: wait for voice command ... +[ INFO] [1732709676.496398964]: wait for voice command ... +[ INFO] [1732709676.506491097]: wait for voice command ... +[ INFO] [1732709676.516367964]: wait for voice command ... +[ INFO] [1732709676.526329942]: wait for voice command ... +[ INFO] [1732709676.536368927]: wait for voice command ... +[ INFO] [1732709676.546345468]: wait for voice command ... +[ INFO] [1732709676.556511780]: wait for voice command ... +[ INFO] [1732709676.566442616]: wait for voice command ... +[ INFO] [1732709676.576433613]: wait for voice command ... +[ INFO] [1732709676.586435005]: wait for voice command ... +[ INFO] [1732709676.596693672]: wait for voice command ... +[ INFO] [1732709676.606458048]: wait for voice command ... +[ INFO] [1732709676.616380847]: wait for voice command ... +[ INFO] [1732709676.626437483]: wait for voice command ... +[ INFO] [1732709676.636376653]: wait for voice command ... +[ INFO] [1732709676.646408190]: wait for voice command ... +[ INFO] [1732709676.656367396]: wait for voice command ... +[ INFO] [1732709676.666451654]: wait for voice command ... +[ INFO] [1732709676.680023467]: wait for voice command ... +[ INFO] [1732709676.686357967]: wait for voice command ... +[ INFO] [1732709676.696378692]: wait for voice command ... +[ INFO] [1732709676.706439763]: wait for voice command ... +[ INFO] [1732709676.716366682]: wait for voice command ... +[ INFO] [1732709676.726452254]: wait for voice command ... +[ INFO] [1732709676.736343334]: wait for voice command ... +[ INFO] [1732709676.746369651]: wait for voice command ... +[ INFO] [1732709676.756662408]: wait for voice command ... +[ INFO] [1732709676.766773087]: wait for voice command ... +[ INFO] [1732709676.776424325]: wait for voice command ... +[ INFO] [1732709676.786562105]: wait for voice command ... +[ INFO] [1732709676.796409005]: wait for voice command ... +[ INFO] [1732709676.806384037]: wait for voice command ... +[ INFO] [1732709676.816386832]: wait for voice command ... +[ INFO] [1732709676.826468029]: wait for voice command ... +[ INFO] [1732709676.836470018]: wait for voice command ... +[ INFO] [1732709676.846360826]: wait for voice command ... +[ INFO] [1732709676.856376120]: wait for voice command ... +[ INFO] [1732709676.866368585]: wait for voice command ... +[ INFO] [1732709676.876424045]: wait for voice command ... +[ INFO] [1732709676.886377645]: wait for voice command ... +[ INFO] [1732709676.896420975]: wait for voice command ... +[ INFO] [1732709676.906371211]: wait for voice command ... +[ INFO] [1732709676.916393875]: wait for voice command ... +[ INFO] [1732709676.926456066]: wait for voice command ... +[ INFO] [1732709676.936630068]: wait for voice command ... +[ INFO] [1732709676.946448541]: wait for voice command ... +[ INFO] [1732709676.956484791]: wait for voice command ... +[ INFO] [1732709676.966473851]: wait for voice command ... +[ INFO] [1732709676.976392740]: wait for voice command ... +[ INFO] [1732709676.986360860]: wait for voice command ... +[ INFO] [1732709676.996340228]: wait for voice command ... +[ INFO] [1732709677.006377229]: wait for voice command ... +[ INFO] [1732709677.016382036]: wait for voice command ... +[ INFO] [1732709677.026431381]: wait for voice command ... +[ INFO] [1732709677.036349925]: wait for voice command ... +[ INFO] [1732709677.046374969]: wait for voice command ... +[ INFO] [1732709677.056365388]: wait for voice command ... +[ INFO] [1732709677.066350626]: wait for voice command ... +[ INFO] [1732709677.076408634]: wait for voice command ... +[ INFO] [1732709677.086411779]: wait for voice command ... +[ INFO] [1732709677.096332027]: wait for voice command ... +[ INFO] [1732709677.106368534]: wait for voice command ... +[ INFO] [1732709677.116356902]: wait for voice command ... +[ INFO] [1732709677.126363447]: wait for voice command ... +[ INFO] [1732709677.136373122]: wait for voice command ... +[ INFO] [1732709677.146364217]: wait for voice command ... +[ INFO] [1732709677.156396775]: wait for voice command ... +[ INFO] [1732709677.166433303]: wait for voice command ... +[ INFO] [1732709677.176406985]: wait for voice command ... +[ INFO] [1732709677.186373349]: wait for voice command ... +[ INFO] [1732709677.196417368]: wait for voice command ... +[ INFO] [1732709677.206407418]: wait for voice command ... +[ INFO] [1732709677.216356122]: wait for voice command ... +[ INFO] [1732709677.226480063]: wait for voice command ... +[ INFO] [1732709677.236433814]: wait for voice command ... +[ INFO] [1732709677.246397064]: wait for voice command ... +[ INFO] [1732709677.256447164]: wait for voice command ... +[ INFO] [1732709677.266531263]: wait for voice command ... +[ INFO] [1732709677.276457189]: wait for voice command ... +[ INFO] [1732709677.286418248]: wait for voice command ... +[ INFO] [1732709677.296404777]: wait for voice command ... +[ INFO] [1732709677.306379869]: wait for voice command ... +[ INFO] [1732709677.316330963]: wait for voice command ... +[ INFO] [1732709677.326324363]: wait for voice command ... +[ INFO] [1732709677.336353780]: wait for voice command ... +[ INFO] [1732709677.346342468]: wait for voice command ... +[ INFO] [1732709677.356541576]: wait for voice command ... +[ INFO] [1732709677.366544413]: wait for voice command ... +[ INFO] [1732709677.376372582]: wait for voice command ... +[ INFO] [1732709677.386381019]: wait for voice command ... +[ INFO] [1732709677.396368604]: wait for voice command ... +[ INFO] [1732709677.406347506]: wait for voice command ... +[ INFO] [1732709677.416415774]: wait for voice command ... +[ INFO] [1732709677.426448845]: wait for voice command ... +[ INFO] [1732709677.436394888]: wait for voice command ... +[ INFO] [1732709677.446344972]: wait for voice command ... +[ INFO] [1732709677.456385336]: wait for voice command ... +[ INFO] [1732709677.466440859]: wait for voice command ... +[ INFO] [1732709677.476406490]: wait for voice command ... +[ INFO] [1732709677.487525244]: wait for voice command ... +[ INFO] [1732709677.496360724]: wait for voice command ... +[ INFO] [1732709677.506383184]: wait for voice command ... +[ INFO] [1732709677.516403134]: wait for voice command ... +[ INFO] [1732709677.526354025]: wait for voice command ... +[ INFO] [1732709677.536374944]: wait for voice command ... +[ INFO] [1732709677.546428454]: wait for voice command ... +[ INFO] [1732709677.556389012]: wait for voice command ... +[ INFO] [1732709677.566451213]: wait for voice command ... +[ INFO] [1732709677.576339653]: wait for voice command ... +[ INFO] [1732709677.586390630]: wait for voice command ... +[ INFO] [1732709677.596356586]: wait for voice command ... +[ INFO] [1732709677.606402468]: wait for voice command ... +[ INFO] [1732709677.616707762]: wait for voice command ... +[ INFO] [1732709677.626350531]: wait for voice command ... +[ INFO] [1732709677.636405319]: wait for voice command ... +[ INFO] [1732709677.646374839]: wait for voice command ... +[ INFO] [1732709677.656407575]: wait for voice command ... +[ INFO] [1732709677.666358767]: wait for voice command ... +[ INFO] [1732709677.676354362]: wait for voice command ... +[ INFO] [1732709677.686400222]: wait for voice command ... +[ INFO] [1732709677.696492648]: wait for voice command ... +[ INFO] [1732709677.706429358]: wait for voice command ... +[ INFO] [1732709677.716386345]: wait for voice command ... +[ INFO] [1732709677.726424050]: wait for voice command ... +[ INFO] [1732709677.736414081]: wait for voice command ... +[ INFO] [1732709677.746361065]: wait for voice command ... +[ INFO] [1732709677.756405690]: wait for voice command ... +[ INFO] [1732709677.766457385]: wait for voice command ... +[ INFO] [1732709677.776394086]: wait for voice command ... +[ INFO] [1732709677.786445074]: wait for voice command ... +[ INFO] [1732709677.796403047]: wait for voice command ... +[ INFO] [1732709677.806459041]: wait for voice command ... +[ INFO] [1732709677.816450757]: wait for voice command ... +[ INFO] [1732709677.826407343]: wait for voice command ... +[ INFO] [1732709677.836332904]: wait for voice command ... +[ INFO] [1732709677.846363044]: wait for voice command ... +[ INFO] [1732709677.856393291]: wait for voice command ... +[ INFO] [1732709677.866452153]: wait for voice command ... +[ INFO] [1732709677.876471565]: wait for voice command ... +[ INFO] [1732709677.886402097]: wait for voice command ... +[ INFO] [1732709677.896359116]: wait for voice command ... +[ INFO] [1732709677.906450496]: wait for voice command ... +[ INFO] [1732709677.916392789]: wait for voice command ... +[ INFO] [1732709677.926451652]: wait for voice command ... +[ INFO] [1732709677.936354336]: wait for voice command ... +[ INFO] [1732709677.946337264]: wait for voice command ... +[ INFO] [1732709677.956465266]: wait for voice command ... +[ INFO] [1732709677.966449638]: wait for voice command ... +[ INFO] [1732709677.976391224]: wait for voice command ... +[ INFO] [1732709677.986399685]: wait for voice command ... +[ INFO] [1732709677.996410419]: wait for voice command ... +[ INFO] [1732709678.006461972]: wait for voice command ... +[ INFO] [1732709678.016421465]: wait for voice command ... +[ INFO] [1732709678.026466939]: wait for voice command ... +[ INFO] [1732709678.036366703]: wait for voice command ... +[ INFO] [1732709678.046446358]: wait for voice command ... +[ INFO] [1732709678.056441923]: wait for voice command ... +[ INFO] [1732709678.066391550]: wait for voice command ... +[ INFO] [1732709678.076468813]: wait for voice command ... +[ INFO] [1732709678.086377011]: wait for voice command ... +[ INFO] [1732709678.096366424]: wait for voice command ... +[ INFO] [1732709678.106488338]: wait for voice command ... +[ INFO] [1732709678.116432873]: wait for voice command ... +[ INFO] [1732709678.126444195]: wait for voice command ... +[ INFO] [1732709678.136420758]: wait for voice command ... +[ INFO] [1732709678.146552600]: wait for voice command ... +[ INFO] [1732709678.156421334]: wait for voice command ... +[ INFO] [1732709678.166421362]: wait for voice command ... +[ INFO] [1732709678.176615597]: wait for voice command ... +[ INFO] [1732709678.186416360]: wait for voice command ... +[ INFO] [1732709678.196405647]: wait for voice command ... +[ INFO] [1732709678.206375363]: wait for voice command ... +[ INFO] [1732709678.216358944]: wait for voice command ... +[ INFO] [1732709678.226336654]: wait for voice command ... +[ INFO] [1732709678.236381369]: wait for voice command ... +[ INFO] [1732709678.246376951]: wait for voice command ... +[ INFO] [1732709678.256423414]: wait for voice command ... +[ INFO] [1732709678.266433975]: wait for voice command ... +[ INFO] [1732709678.276438876]: wait for voice command ... +[ INFO] [1732709678.286414655]: wait for voice command ... +[ INFO] [1732709678.296333496]: wait for voice command ... +[ INFO] [1732709678.306449220]: wait for voice command ... +[ INFO] [1732709678.316365999]: wait for voice command ... +[ INFO] [1732709678.326331852]: wait for voice command ... +[ INFO] [1732709678.336338129]: wait for voice command ... +[ INFO] [1732709678.346369241]: wait for voice command ... +[ INFO] [1732709678.356354362]: wait for voice command ... +[ INFO] [1732709678.366369264]: wait for voice command ... +[ INFO] [1732709678.376487415]: wait for voice command ... +[ INFO] [1732709678.386373764]: wait for voice command ... +[ INFO] [1732709678.396334432]: wait for voice command ... +[ INFO] [1732709678.406456387]: wait for voice command ... +[ INFO] [1732709678.416345910]: wait for voice command ... +[ INFO] [1732709678.426374290]: wait for voice command ... +[ INFO] [1732709678.436381832]: wait for voice command ... +[ INFO] [1732709678.446378304]: wait for voice command ... +[ INFO] [1732709678.456449816]: wait for voice command ... +[ INFO] [1732709678.466432291]: wait for voice command ... +[ INFO] [1732709678.476446083]: wait for voice command ... +[ INFO] [1732709678.486410280]: wait for voice command ... +[ INFO] [1732709678.496413032]: wait for voice command ... +[ INFO] [1732709678.506393688]: wait for voice command ... +[ INFO] [1732709678.516360417]: wait for voice command ... +[ INFO] [1732709678.526450745]: wait for voice command ... +[ INFO] [1732709678.536347215]: wait for voice command ... +[ INFO] [1732709678.546356993]: wait for voice command ... +[ INFO] [1732709678.556345888]: wait for voice command ... +[ INFO] [1732709678.566441697]: wait for voice command ... +[ INFO] [1732709678.576411599]: wait for voice command ... +[ INFO] [1732709678.586372361]: wait for voice command ... +[ INFO] [1732709678.596385804]: wait for voice command ... +[ INFO] [1732709678.606421736]: wait for voice command ... +[ INFO] [1732709678.616423113]: wait for voice command ... +[ INFO] [1732709678.626427046]: wait for voice command ... +[ INFO] [1732709678.636444397]: wait for voice command ... +[ INFO] [1732709678.646401708]: wait for voice command ... +[ INFO] [1732709678.656550601]: wait for voice command ... +[ INFO] [1732709678.666434115]: wait for voice command ... +[ INFO] [1732709678.676408466]: wait for voice command ... +[ INFO] [1732709678.686477127]: wait for voice command ... +[ INFO] [1732709678.696421703]: wait for voice command ... +[ INFO] [1732709678.706421978]: wait for voice command ... +[ INFO] [1732709678.716376924]: wait for voice command ... +[ INFO] [1732709678.726436897]: wait for voice command ... +[ INFO] [1732709678.736369468]: wait for voice command ... +[ INFO] [1732709678.746457883]: wait for voice command ... +[ INFO] [1732709678.756424914]: wait for voice command ... +[ INFO] [1732709678.766385206]: wait for voice command ... +[ INFO] [1732709678.776427730]: wait for voice command ... +[ INFO] [1732709678.786362827]: wait for voice command ... +[ INFO] [1732709678.796387677]: wait for voice command ... +[ INFO] [1732709678.806438264]: wait for voice command ... +[ INFO] [1732709678.816408398]: wait for voice command ... +[ INFO] [1732709678.826360338]: wait for voice command ... +[ INFO] [1732709678.836416949]: wait for voice command ... +[ INFO] [1732709678.846406573]: wait for voice command ... +[ INFO] [1732709678.856435599]: wait for voice command ... +[ INFO] [1732709678.866823567]: wait for voice command ... +[ INFO] [1732709678.876415558]: wait for voice command ... +[ INFO] [1732709678.886441991]: wait for voice command ... +[ INFO] [1732709678.896444984]: wait for voice command ... +[ INFO] [1732709678.906377487]: wait for voice command ... +[ INFO] [1732709678.916374236]: wait for voice command ... +[ INFO] [1732709678.926488631]: wait for voice command ... +[ INFO] [1732709678.936329818]: wait for voice command ... +[ INFO] [1732709678.946345973]: wait for voice command ... +[ INFO] [1732709678.956329024]: wait for voice command ... +[ INFO] [1732709678.966445589]: wait for voice command ... +[ INFO] [1732709678.976447183]: wait for voice command ... +[ INFO] [1732709678.986415555]: wait for voice command ... +[ INFO] [1732709678.996445735]: wait for voice command ... +[ INFO] [1732709679.006517581]: wait for voice command ... +[ INFO] [1732709679.016580955]: wait for voice command ... +[ INFO] [1732709679.026370669]: wait for voice command ... +[ INFO] [1732709679.036410695]: wait for voice command ... +[ INFO] [1732709679.046343061]: wait for voice command ... +[ INFO] [1732709679.056377333]: wait for voice command ... +[ INFO] [1732709679.066390975]: wait for voice command ... +[ INFO] [1732709679.076366268]: wait for voice command ... +[ INFO] [1732709679.086379728]: wait for voice command ... +[ INFO] [1732709679.096441053]: wait for voice command ... +[ INFO] [1732709679.106407280]: wait for voice command ... +[ INFO] [1732709679.116360762]: wait for voice command ... +[ INFO] [1732709679.126445795]: wait for voice command ... +[ INFO] [1732709679.136409807]: wait for voice command ... +[ INFO] [1732709679.146411598]: wait for voice command ... +[ INFO] [1732709679.156420837]: wait for voice command ... +[ INFO] [1732709679.166418734]: wait for voice command ... +[ INFO] [1732709679.176413796]: wait for voice command ... +[ INFO] [1732709679.186379277]: wait for voice command ... +[ INFO] [1732709679.196392213]: wait for voice command ... +[ INFO] [1732709679.206417845]: wait for voice command ... +[ INFO] [1732709679.216407255]: wait for voice command ... +[ INFO] [1732709679.226370711]: wait for voice command ... +[ INFO] [1732709679.236432409]: wait for voice command ... +[ INFO] [1732709679.246385981]: wait for voice command ... +[ INFO] [1732709679.256392409]: wait for voice command ... +[ INFO] [1732709679.266379314]: wait for voice command ... +[ INFO] [1732709679.276420124]: wait for voice command ... +[ INFO] [1732709679.286403544]: wait for voice command ... +[ INFO] [1732709679.296358017]: wait for voice command ... +[ INFO] [1732709679.306468851]: wait for voice command ... +[ INFO] [1732709679.316433581]: wait for voice command ... +[ INFO] [1732709679.326425709]: wait for voice command ... +[ INFO] [1732709679.336315497]: wait for voice command ... +[ INFO] [1732709679.346352251]: wait for voice command ... +[ INFO] [1732709679.356371322]: wait for voice command ... +[ INFO] [1732709679.366420443]: wait for voice command ... +[ INFO] [1732709679.376409479]: wait for voice command ... +[ INFO] [1732709679.386424257]: wait for voice command ... +[ INFO] [1732709679.396458510]: wait for voice command ... +[ INFO] [1732709679.406451136]: wait for voice command ... +[ INFO] [1732709679.416412440]: wait for voice command ... +[ INFO] [1732709679.426429632]: wait for voice command ... +[ INFO] [1732709679.436452513]: wait for voice command ... +[ INFO] [1732709679.446377594]: wait for voice command ... +[ INFO] [1732709679.456345535]: wait for voice command ... +[ INFO] [1732709679.466356660]: wait for voice command ... +[ INFO] [1732709679.476413300]: wait for voice command ... +[ INFO] [1732709679.486377073]: wait for voice command ... +[ INFO] [1732709679.496392372]: wait for voice command ... +[ INFO] [1732709679.506459869]: wait for voice command ... +[ INFO] [1732709679.516480500]: wait for voice command ... +[ INFO] [1732709679.526390479]: wait for voice command ... +[ INFO] [1732709679.536361925]: wait for voice command ... +[ INFO] [1732709679.546475420]: wait for voice command ... +[ INFO] [1732709679.556409265]: wait for voice command ... +[ INFO] [1732709679.566392443]: wait for voice command ... +[ INFO] [1732709679.576433418]: wait for voice command ... +[ INFO] [1732709679.586445640]: wait for voice command ... +[ INFO] [1732709679.596449641]: wait for voice command ... +[ INFO] [1732709679.606393689]: wait for voice command ... +[ INFO] [1732709679.616436434]: wait for voice command ... +[ INFO] [1732709679.626551322]: wait for voice command ... +[ INFO] [1732709679.636368831]: wait for voice command ... +[ INFO] [1732709679.646546654]: wait for voice command ... +[ INFO] [1732709679.656522332]: wait for voice command ... +[ INFO] [1732709679.666338693]: wait for voice command ... +[ INFO] [1732709679.676535883]: wait for voice command ... +[ INFO] [1732709679.686334967]: wait for voice command ... +[ INFO] [1732709679.696341552]: wait for voice command ... +[ INFO] [1732709679.706516899]: wait for voice command ... +[ INFO] [1732709679.716451146]: wait for voice command ... +[ INFO] [1732709679.726373450]: wait for voice command ... +[ INFO] [1732709679.736412485]: wait for voice command ... +[ INFO] [1732709679.746425092]: wait for voice command ... +[ INFO] [1732709679.756411269]: wait for voice command ... +[ INFO] [1732709679.766463608]: wait for voice command ... +[ INFO] [1732709679.776481757]: wait for voice command ... +[ INFO] [1732709679.786387314]: wait for voice command ... +[ INFO] [1732709679.796439469]: wait for voice command ... +[ INFO] [1732709679.806415822]: wait for voice command ... +[ INFO] [1732709679.816468278]: wait for voice command ... +[ INFO] [1732709679.826377152]: wait for voice command ... +[ INFO] [1732709679.836357511]: wait for voice command ... +[ INFO] [1732709679.846434875]: wait for voice command ... +[ INFO] [1732709679.856419627]: wait for voice command ... +[ INFO] [1732709679.866466558]: wait for voice command ... +[ INFO] [1732709679.876404474]: wait for voice command ... +[ INFO] [1732709679.886452503]: wait for voice command ... +[ INFO] [1732709679.896439812]: wait for voice command ... +[ INFO] [1732709679.906443276]: wait for voice command ... +[ INFO] [1732709679.916390639]: wait for voice command ... +[ INFO] [1732709679.926392126]: wait for voice command ... +[ INFO] [1732709679.936441298]: wait for voice command ... +[ INFO] [1732709679.946492990]: wait for voice command ... +[ INFO] [1732709679.956442329]: wait for voice command ... +[ INFO] [1732709679.966397582]: wait for voice command ... +[ INFO] [1732709679.976351975]: wait for voice command ... +[ INFO] [1732709679.986491132]: wait for voice command ... +[ INFO] [1732709679.996441414]: wait for voice command ... +[ INFO] [1732709680.006394243]: wait for voice command ... +[ INFO] [1732709680.016383756]: wait for voice command ... +[ INFO] [1732709680.026534254]: wait for voice command ... +[ INFO] [1732709680.036360883]: wait for voice command ... +[ INFO] [1732709680.046533105]: wait for voice command ... +[ INFO] [1732709680.056370870]: wait for voice command ... +[ INFO] [1732709680.066472927]: wait for voice command ... +[ INFO] [1732709680.076383799]: wait for voice command ... +[ INFO] [1732709680.086387997]: wait for voice command ... +[ INFO] [1732709680.096447451]: wait for voice command ... +[ INFO] [1732709680.106398281]: wait for voice command ... +[ INFO] [1732709680.116381660]: wait for voice command ... +[ INFO] [1732709680.126458446]: wait for voice command ... +[ INFO] [1732709680.136341711]: wait for voice command ... +[ INFO] [1732709680.146389278]: wait for voice command ... +[ INFO] [1732709680.156441806]: wait for voice command ... +[ INFO] [1732709680.166401299]: wait for voice command ... +[ INFO] [1732709680.176421639]: wait for voice command ... +[ INFO] [1732709680.186460964]: wait for voice command ... +[ INFO] [1732709680.196440743]: wait for voice command ... +[ INFO] [1732709680.206440406]: wait for voice command ... +[ INFO] [1732709680.216458243]: wait for voice command ... +[ INFO] [1732709680.226515739]: wait for voice command ... +[ INFO] [1732709680.236482623]: wait for voice command ... +[ INFO] [1732709680.246444546]: wait for voice command ... +[ INFO] [1732709680.256424963]: wait for voice command ... +[ INFO] [1732709680.266500312]: wait for voice command ... +[ INFO] [1732709680.276433763]: wait for voice command ... +[ INFO] [1732709680.286517341]: wait for voice command ... +[ INFO] [1732709680.296448821]: wait for voice command ... +[ INFO] [1732709680.306568015]: wait for voice command ... +[ INFO] [1732709680.316483463]: wait for voice command ... +[ INFO] [1732709680.326429986]: wait for voice command ... +[ INFO] [1732709680.336435329]: wait for voice command ... +[ INFO] [1732709680.346416069]: wait for voice command ... +[ INFO] [1732709680.356419540]: wait for voice command ... +[ INFO] [1732709680.366348125]: wait for voice command ... +[ INFO] [1732709680.376391543]: wait for voice command ... +[ INFO] [1732709680.386857544]: wait for voice command ... +[ INFO] [1732709680.396346399]: wait for voice command ... +[ INFO] [1732709680.406446624]: wait for voice command ... +[ INFO] [1732709680.416333830]: wait for voice command ... +[ INFO] [1732709680.426444599]: wait for voice command ... +[ INFO] [1732709680.436336864]: wait for voice command ... +[ INFO] [1732709680.446435053]: wait for voice command ... +[ INFO] [1732709680.456440181]: wait for voice command ... +[ INFO] [1732709680.466521648]: wait for voice command ... +[ INFO] [1732709680.476467088]: wait for voice command ... +[ INFO] [1732709680.486454022]: wait for voice command ... +[ INFO] [1732709680.496471444]: wait for voice command ... +[ INFO] [1732709680.506458857]: wait for voice command ... +[ INFO] [1732709680.516408745]: wait for voice command ... +[ INFO] [1732709680.526413812]: wait for voice command ... +[ INFO] [1732709680.536422476]: wait for voice command ... +[ INFO] [1732709680.546408383]: wait for voice command ... +[ INFO] [1732709680.556472411]: wait for voice command ... +[ INFO] [1732709680.566477021]: wait for voice command ... +[ INFO] [1732709680.576444167]: wait for voice command ... +[ INFO] [1732709680.586399088]: wait for voice command ... +[ INFO] [1732709680.596419641]: wait for voice command ... +[ INFO] [1732709680.606425764]: wait for voice command ... +[ INFO] [1732709680.616451312]: wait for voice command ... +[ INFO] [1732709680.626420946]: wait for voice command ... +[ INFO] [1732709680.636556267]: wait for voice command ... +[ INFO] [1732709680.646420775]: wait for voice command ... +[ INFO] [1732709680.656454793]: wait for voice command ... +[ INFO] [1732709680.666406908]: wait for voice command ... +[ INFO] [1732709680.676443822]: wait for voice command ... +[ INFO] [1732709680.686427940]: wait for voice command ... +[ INFO] [1732709680.696534535]: wait for voice command ... +[ INFO] [1732709680.706377906]: wait for voice command ... +[ INFO] [1732709680.716409302]: wait for voice command ... +[ INFO] [1732709680.726530226]: wait for voice command ... +[ INFO] [1732709680.736469807]: wait for voice command ... +[ INFO] [1732709680.746474580]: wait for voice command ... +[ INFO] [1732709680.756412385]: wait for voice command ... +[ INFO] [1732709680.766492397]: wait for voice command ... +[ INFO] [1732709680.776398758]: wait for voice command ... +[ INFO] [1732709680.786514299]: wait for voice command ... +[ INFO] [1732709680.796475313]: wait for voice command ... +[ INFO] [1732709680.806480538]: wait for voice command ... +[ INFO] [1732709680.816472611]: wait for voice command ... +[ INFO] [1732709680.826450647]: wait for voice command ... +[ INFO] [1732709680.836452843]: wait for voice command ... +[ INFO] [1732709680.846430540]: wait for voice command ... +[ INFO] [1732709680.856479821]: wait for voice command ... +[ INFO] [1732709680.866645341]: wait for voice command ... +[ INFO] [1732709680.876925408]: wait for voice command ... +[ INFO] [1732709680.886637761]: wait for voice command ... +[ INFO] [1732709680.896369915]: wait for voice command ... +[ INFO] [1732709680.906424565]: wait for voice command ... +[ INFO] [1732709680.916524018]: wait for voice command ... +[ INFO] [1732709680.926561889]: wait for voice command ... +[ INFO] [1732709680.936463732]: wait for voice command ... +[ INFO] [1732709680.946507139]: wait for voice command ... +[ INFO] [1732709680.956472643]: wait for voice command ... +[ INFO] [1732709680.966462716]: wait for voice command ... +[ INFO] [1732709680.976450926]: wait for voice command ... +[ INFO] [1732709680.986443176]: wait for voice command ... +[ INFO] [1732709680.996443612]: wait for voice command ... +[ INFO] [1732709681.006399182]: wait for voice command ... +[ INFO] [1732709681.016525282]: wait for voice command ... +[ INFO] [1732709681.026481309]: wait for voice command ... +[ INFO] [1732709681.036429719]: wait for voice command ... +[ INFO] [1732709681.046392120]: wait for voice command ... +[ INFO] [1732709681.056357691]: wait for voice command ... +[ INFO] [1732709681.066315419]: wait for voice command ... +[ INFO] [1732709681.076346870]: wait for voice command ... +[ INFO] [1732709681.086452435]: wait for voice command ... +[ INFO] [1732709681.096398341]: wait for voice command ... +[ INFO] [1732709681.106360983]: wait for voice command ... +[ INFO] [1732709681.116478769]: wait for voice command ... +[ INFO] [1732709681.126357083]: wait for voice command ... +[ INFO] [1732709681.136415441]: wait for voice command ... +[ INFO] [1732709681.146405119]: wait for voice command ... +[ INFO] [1732709681.156419171]: wait for voice command ... +[ INFO] [1732709681.166422329]: wait for voice command ... +[ INFO] [1732709681.176434441]: wait for voice command ... +[ INFO] [1732709681.186425234]: wait for voice command ... +[ INFO] [1732709681.196408619]: wait for voice command ... +[ INFO] [1732709681.206388974]: wait for voice command ... +[ INFO] [1732709681.216353763]: wait for voice command ... +[ INFO] [1732709681.226331412]: wait for voice command ... +[ INFO] [1732709681.236322834]: wait for voice command ... +[ INFO] [1732709681.246332442]: wait for voice command ... +[ INFO] [1732709681.256336731]: wait for voice command ... +[ INFO] [1732709681.266343349]: wait for voice command ... +[ INFO] [1732709681.276340733]: wait for voice command ... +[ INFO] [1732709681.286368211]: wait for voice command ... +[ INFO] [1732709681.296347254]: wait for voice command ... +[ INFO] [1732709681.306363982]: wait for voice command ... +[ INFO] [1732709681.316371096]: wait for voice command ... +"め" +Call Stack (max depth: 20): + 0: at (if (equalp *ans* "メス") (setq *start-flag* 1)) + 1: at (ros::spin-once) + 2: at (ros::spin-once) + 3: at (while (not (eq *start-flag* 1)) (ros::spin-once) (ros::sleep) (ros::ros-info "wait for voice command ...")) + 4: at (detect-voice) + 5: at (apply #'ros::load-org-for-ros ros::fullname args) + 6: at (apply #'ros::load-org-for-ros ros::fullname args) + 7: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 8: at (load "main.l") + 9: at euserror + 10: at euserror + 11: at (while (not (eq *start-flag* 1)) (ros::spin-once) (ros::sleep) (ros::info "wait for voice command ...")) + 12: at (detect-voice) + 13: at (apply #'ros::load-org-for-ros ros::fullname args) + 14: at (apply #'ros::load-org-for-ros ros::fullname args) + 15: at (let ((ros::fullname fname)) (when (and (stringp fname) (substringp "package://" fname)) (setq ros::fullname (ros::resolve-ros-path fname)) (when ros::*compile-message* (let* ((ros::urlname (url-pathname fname)) (package-name (send ros::urlname :host)) (ros::path-name (format nil "~A_~A" package-name (substitute 95 47 (concatenate string (subseq (send ros::urlname :directory-string) 1) (send ros::urlname :name))))) (ros::old-module (find ros::path-name *loaded-modules* :key #'lisp::load-module-file-name :test #'equal))) (unless ros::old-module (let* ((ros::ppath (unix:getenv "CMAKE_PREFIX_PATH")) (dir (format nil "~A/share/roseus/ros/~A" (subseq ros::ppath 0 (position 58 ros::ppath)) package-name))) (unless (probe-file dir) (unix:mkdir dir)) (compiler:compile-file-if-src-newer ros::fullname (format nil "~A/~A" dir ros::path-name)) (return-from load (load (format nil "~A/~A.so" dir ros::path-name) :entry (format nil "___~A" ros::path-name)))))))) (if (null ros::fullname) (error "file ~s not found" fname)) (apply #'ros::load-org-for-ros ros::fullname args)) + 16: at (load "main.l") + 17: at # +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: undefined function equalp in (if (equalp *ans* "メス") (setq *start-flag* 1)) +51.E2-irteusgl$ (equal *ans* "メス") +nil +52.E2-irteusgl$ *ans* +"め" +53.E2-irteusgl$ load "main.l" +[ INFO] [1732709717.687552691]: wait-interpolation debug: start +[ERROR] [1732709719.282289648]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732709719.282331428]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732709719.293516732]: wait-interpolation debug: end +[ INFO] [1732709719.669067283]: wait-interpolation debug: start +[ERROR] [1732709721.259596112]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732709721.259641171]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732709721.265064577]: wait-interpolation debug: end +[ INFO] [1732709727.268783485]: wait-interpolation debug: start +[ INFO] [1732709727.269274385]: wait-interpolation debug: end +[ INFO] [1732709727.270715856]: start waiting for call + +[ INFO] [1732709727.387162548]: wait for voice command ... +[ INFO] [1732709727.487130718]: wait for voice command ... +[ INFO] [1732709727.587186703]: wait for voice command ... +[ INFO] [1732709727.687119040]: wait for voice command ... +[ INFO] [1732709727.787174771]: wait for voice command ... +[ INFO] [1732709727.887170218]: wait for voice command ... +[ INFO] [1732709727.987165288]: wait for voice command ... +[ INFO] [1732709728.087129108]: wait for voice command ... +[ INFO] [1732709728.187163005]: wait for voice command ... +[ INFO] [1732709728.287129119]: wait for voice command ... +[ INFO] [1732709728.387126055]: wait for voice command ... +[ INFO] [1732709728.487137924]: wait for voice command ... +[ INFO] [1732709728.587129957]: wait for voice command ... +[ INFO] [1732709728.687232581]: wait for voice command ... +[ INFO] [1732709728.787141997]: wait for voice command ... +[ INFO] [1732709728.887161519]: wait for voice command ... +[ INFO] [1732709728.987163093]: wait for voice command ... +[ INFO] [1732709729.087140686]: wait for voice command ... +[ INFO] [1732709729.187125388]: wait for voice command ... +[ INFO] [1732709729.287172767]: wait for voice command ... +[ INFO] [1732709729.387124179]: wait for voice command ... +[ INFO] [1732709729.487167951]: wait for voice command ... +[ INFO] [1732709729.587166220]: wait for voice command ... +[ INFO] [1732709729.687160167]: wait for voice command ... +[ INFO] [1732709729.787160427]: wait for voice command ... +[ INFO] [1732709729.887128513]: wait for voice command ... +[ INFO] [1732709729.987124633]: wait for voice command ... +[ INFO] [1732709730.087169719]: wait for voice command ... +[ INFO] [1732709730.187122769]: wait for voice command ... +[ INFO] [1732709730.287166400]: wait for voice command ... +[ INFO] [1732709730.387169849]: wait for voice command ... +[ INFO] [1732709730.487790741]: wait for voice command ... +[ INFO] [1732709730.587161872]: wait for voice command ... +[ INFO] [1732709730.687118244]: wait for voice command ... +[ INFO] [1732709730.787160039]: wait for voice command ... +[ INFO] [1732709730.887201930]: wait for voice command ... +[ INFO] [1732709730.987129016]: wait for voice command ... +[ INFO] [1732709731.087170786]: wait for voice command ... +[ INFO] [1732709731.187154235]: wait for voice command ... +[ INFO] [1732709731.287156824]: wait for voice command ... +[ INFO] [1732709731.387117069]: wait for voice command ... +[ INFO] [1732709731.487125724]: wait for voice command ... +[ INFO] [1732709731.587122267]: wait for voice command ... +[ INFO] [1732709731.687232318]: wait for voice command ... +[ INFO] [1732709731.787229204]: wait for voice command ... +[ INFO] [1732709731.887214315]: wait for voice command ... +[ INFO] [1732709731.987260809]: wait for voice command ... +[ INFO] [1732709732.087229211]: wait for voice command ... +[ INFO] [1732709732.187272553]: wait for voice command ... +[ INFO] [1732709732.287233465]: wait for voice command ... +[ INFO] [1732709732.387240947]: wait for voice command ... +[ INFO] [1732709732.487160945]: wait for voice command ... +[ INFO] [1732709732.587184589]: wait for voice command ... +[ INFO] [1732709732.687200405]: wait for voice command ... +[ INFO] [1732709732.787262488]: wait for voice command ... +[ INFO] [1732709732.887244060]: wait for voice command ... +[ INFO] [1732709732.987298321]: wait for voice command ... +[ INFO] [1732709733.087162412]: wait for voice command ... +[ INFO] [1732709733.187160127]: wait for voice command ... +[ INFO] [1732709733.287144363]: wait for voice command ... +[ INFO] [1732709733.387219813]: wait for voice command ... +[ INFO] [1732709733.487233258]: wait for voice command ... +[ INFO] [1732709733.587162934]: wait for voice command ... +[ INFO] [1732709733.687159190]: wait for voice command ... +[ INFO] [1732709733.787165335]: wait for voice command ... +[ INFO] [1732709733.887224735]: wait for voice command ... +[ INFO] [1732709733.987128958]: wait for voice command ... +[ INFO] [1732709734.087201563]: wait for voice command ... +[ INFO] [1732709734.187248678]: wait for voice command ... +[ INFO] [1732709734.287144331]: wait for voice command ... +[ INFO] [1732709734.387205285]: wait for voice command ... +[ INFO] [1732709734.487204564]: wait for voice command ... +[ INFO] [1732709734.587264678]: wait for voice command ... +"メス" +[ INFO] [1732709734.687258981]: wait for voice command ... +[ WARN] [1732709736.979166222]: [robotsound_jp] :wait-for-result finished with preempted status +[ INFO] [1732709738.948193756]: wait-interpolation debug: start +[ INFO] [1732709738.949282342]: wait-interpolation debug: end +[ WARN] [1732709738.985574025]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732709738.985621716]: expected goal id 1732709738954957023_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_27 +[ WARN] [1732709738.985657497]: received goal id /battery_warning-111-1732709736.966 +[ INFO] [1732709745.684573046]: wait-interpolation debug: start +[ INFO] [1732709746.696656437]: wait-interpolation debug: end +[ WARN] [1732709746.757792814]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732709746.762948335]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732709746.763109893]: original trajectory command : +[ WARN] [1732709746.763150405]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (1000) +[ WARN] [1732709746.763193069]: current angle vector : #f(50.0 17.8275 14.7726 46.824 -78.4543 6.11414 -34.739 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732709746.763219079]: new trajectory command : dvi = 2 +[ WARN] [1732709746.763279850]: : #f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732709746.763306396]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732709746.763322744]: new trajectory command : +[ WARN] [1732709746.763355729]: : (#f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (500 500) +[ INFO] [1732709746.765759038]: wait-interpolation debug: start +[ INFO] [1732709747.933510366]: wait-interpolation debug: end + + + C-c C-cinterrupt54.B3-irteusgl$ reset +55.irteusgl$ load "main.l" +[ INFO] [1732709917.486424977]: wait-interpolation debug: start +[ERROR] [1732709919.071798239]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732709919.071936522]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732709919.075313965]: wait-interpolation debug: end +[ INFO] [1732709919.165666102]: wait-interpolation debug: start +[ERROR] [1732709920.749807038]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732709920.749864765]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732709920.751558756]: wait-interpolation debug: end +[ WARN] [1732709921.155455268]: [robotsound_jp] :wait-for-result finished with preempted status +[ INFO] [1732709922.993574474]: wait-interpolation debug: start +[ INFO] [1732709922.995633849]: wait-interpolation debug: end +[ INFO] [1732709922.997115843]: start waiting for call + +[ INFO] [1732709923.108015589]: wait for voice command ... +[ INFO] [1732709923.208025424]: wait for voice command ... +[ INFO] [1732709923.308018263]: wait for voice command ... +[ INFO] [1732709923.408026811]: wait for voice command ... +[ INFO] [1732709923.508031428]: wait for voice command ... +[ INFO] [1732709923.607990257]: wait for voice command ... +[ INFO] [1732709923.707985103]: wait for voice command ... +[ INFO] [1732709923.807985302]: wait for voice command ... +[ INFO] [1732709923.907983745]: wait for voice command ... +[ INFO] [1732709924.007986719]: wait for voice command ... +[ INFO] [1732709924.108026079]: wait for voice command ... +[ INFO] [1732709924.208022143]: wait for voice command ... +[ INFO] [1732709924.308025915]: wait for voice command ... +[ INFO] [1732709924.408103716]: wait for voice command ... +[ INFO] [1732709924.508045556]: wait for voice command ... +[ INFO] [1732709924.608032814]: wait for voice command ... +[ INFO] [1732709924.708025412]: wait for voice command ... +[ INFO] [1732709924.807979832]: wait for voice command ... +[ INFO] [1732709924.907992549]: wait for voice command ... +[ INFO] [1732709925.008022566]: wait for voice command ... +[ INFO] [1732709925.108079122]: wait for voice command ... +[ INFO] [1732709925.208146675]: wait for voice command ... +[ INFO] [1732709925.308060794]: wait for voice command ... +[ INFO] [1732709925.408053173]: wait for voice command ... +[ INFO] [1732709925.508017133]: wait for voice command ... +[ INFO] [1732709925.608023398]: wait for voice command ... +[ INFO] [1732709925.708014081]: wait for voice command ... +[ INFO] [1732709925.807997599]: wait for voice command ... +[ INFO] [1732709925.908002528]: wait for voice command ... +[ INFO] [1732709926.008042690]: wait for voice command ... +[ INFO] [1732709926.108001309]: wait for voice command ... +[ INFO] [1732709926.207980733]: wait for voice command ... +[ INFO] [1732709926.307980144]: wait for voice command ... +[ INFO] [1732709926.407978182]: wait for voice command ... +[ INFO] [1732709926.508021154]: wait for voice command ... +[ INFO] [1732709926.608024117]: wait for voice command ... +[ INFO] [1732709926.707991922]: wait for voice command ... +[ INFO] [1732709926.808093835]: wait for voice command ... +[ INFO] [1732709926.907990163]: wait for voice command ... +[ INFO] [1732709927.007999738]: wait for voice command ... +[ INFO] [1732709927.107992816]: wait for voice command ... +[ INFO] [1732709927.207985790]: wait for voice command ... +[ INFO] [1732709927.307987876]: wait for voice command ... +[ INFO] [1732709927.407988219]: wait for voice command ... +[ INFO] [1732709927.508028163]: wait for voice command ... +[ INFO] [1732709927.608067327]: wait for voice command ... +[ INFO] [1732709927.708142510]: wait for voice command ... +[ INFO] [1732709927.807998719]: wait for voice command ... +[ INFO] [1732709927.907979887]: wait for voice command ... +[ INFO] [1732709928.008034992]: wait for voice command ... +[ INFO] [1732709928.107979787]: wait for voice command ... +[ INFO] [1732709928.207985511]: wait for voice command ... +[ INFO] [1732709928.307984617]: wait for voice command ... +[ INFO] [1732709928.408527024]: wait for voice command ... +[ INFO] [1732709928.508055859]: wait for voice command ... +[ INFO] [1732709928.607983767]: wait for voice command ... +[ INFO] [1732709928.708033869]: wait for voice command ... +[ INFO] [1732709928.808022784]: wait for voice command ... +[ INFO] [1732709928.907983115]: wait for voice command ... +[ INFO] [1732709929.008030373]: wait for voice command ... +[ INFO] [1732709929.107988665]: wait for voice command ... +[ INFO] [1732709929.207985631]: wait for voice command ... +[ INFO] [1732709929.308031544]: wait for voice command ... +[ INFO] [1732709929.407981307]: wait for voice command ... +[ INFO] [1732709929.507988964]: wait for voice command ... +[ INFO] [1732709929.608021640]: wait for voice command ... +[ INFO] [1732709929.708002169]: wait for voice command ... +[ INFO] [1732709929.808012620]: wait for voice command ... +[ INFO] [1732709929.908195130]: wait for voice command ... +[ INFO] [1732709930.008039694]: wait for voice command ... +[ INFO] [1732709930.108037718]: wait for voice command ... +[ INFO] [1732709930.208034089]: wait for voice command ... +[ INFO] [1732709930.308028901]: wait for voice command ... +[ INFO] [1732709930.407990287]: wait for voice command ... +[ INFO] [1732709930.507987239]: wait for voice command ... +[ INFO] [1732709930.608024307]: wait for voice command ... +[ INFO] [1732709930.707984442]: wait for voice command ... +[ INFO] [1732709930.808029011]: wait for voice command ... +[ INFO] [1732709930.908031537]: wait for voice command ... +[ INFO] [1732709931.008029094]: wait for voice command ... +[ INFO] [1732709931.108025219]: wait for voice command ... +[ INFO] [1732709931.208018458]: wait for voice command ... +[ INFO] [1732709931.308023674]: wait for voice command ... +[ INFO] [1732709931.408035098]: wait for voice command ... +[ INFO] [1732709931.508113227]: wait for voice command ... +[ INFO] [1732709931.608032650]: wait for voice command ... +[ INFO] [1732709931.707991229]: wait for voice command ... +[ INFO] [1732709931.807996551]: wait for voice command ... +"メス" +[ INFO] [1732709931.907984122]: wait for voice command ... +[ WARN] [1732709931.909251055]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732709931.909285250]: expected goal id 1732709931908138387_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_30 +[ WARN] [1732709931.909313950]: received goal id /battery_warning-112-1732709920.966 +[ INFO] [1732709938.615931393]: wait-interpolation debug: start +[ INFO] [1732709938.616083131]: wait-interpolation debug: end +[ INFO] [1732709945.193733611]: wait-interpolation debug: start +[ INFO] [1732709946.186207348]: wait-interpolation debug: end +[ WARN] [1732709946.230563892]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732709946.234871016]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732709946.234946457]: original trajectory command : +[ WARN] [1732709946.234970459]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (1000) +[ WARN] [1732709946.234990663]: current angle vector : #f(50.0 17.8275 14.7726 46.824 -78.4543 6.11414 -34.739 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732709946.235001706]: new trajectory command : dvi = 2 +[ WARN] [1732709946.235027232]: : #f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732709946.235048603]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732709946.235061808]: new trajectory command : +[ WARN] [1732709946.235089982]: : (#f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (500 500) +[ INFO] [1732709946.237263159]: wait-interpolation debug: start +[ INFO] [1732709947.403340732]: wait-interpolation debug: end + C-c C-cinterrupt56.B1-irteusgl$ reset +57.irteusgl$ load "main.l" +[ WARN] [1732710006.644651109]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732710006.644688802]: expected goal id 1732710006642575365_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_32 +[ WARN] [1732710006.644712852]: received goal id 1732710000422741052_/tweet_client_warning_473265_robotsound_jp_84 +[ WARN] [1732710006.645076472]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732710006.645100321]: expected goal id 1732710006642575365_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_32 +[ WARN] [1732710006.645136379]: received goal id 1732710001426727258_/tweet_client_warning_473265_robotsound_jp_85 +[ WARN] [1732710006.645381842]: [robotsound_jp] action-result-cb may received old client's goal +[ WARN] [1732710006.645401891]: expected goal id 1732710006642575365_/pr2_eus_interface_1732705419350276377_79054_robotsound_jp_32 +[ WARN] [1732710006.645415108]: received goal id 1732710002485701605_/tweet_client_warning_473265_robotsound_jp_86 +[ INFO] [1732710010.568157308]: wait-interpolation debug: start +[ERROR] [1732710012.154050507]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732710012.154104321]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732710012.155431413]: wait-interpolation debug: end +[ INFO] [1732710012.713784408]: wait-interpolation debug: start +[ERROR] [1732710014.301916779]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732710014.301990863]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732710014.306154133]: wait-interpolation debug: end +[ INFO] [1732710020.198412296]: wait-interpolation debug: start +[ INFO] [1732710020.201739058]: wait-interpolation debug: end +[ INFO] [1732710020.203337494]: start waiting for call + +[ INFO] [1732710020.311882236]: wait for voice command ... +[ INFO] [1732710020.411896264]: wait for voice command ... +[ INFO] [1732710020.511851396]: wait for voice command ... +[ INFO] [1732710020.611885565]: wait for voice command ... +[ INFO] [1732710020.711795135]: wait for voice command ... +[ INFO] [1732710020.811873225]: wait for voice command ... +[ INFO] [1732710020.911852066]: wait for voice command ... +[ INFO] [1732710021.011815412]: wait for voice command ... +[ INFO] [1732710021.111945749]: wait for voice command ... +[ INFO] [1732710021.211909108]: wait for voice command ... +[ INFO] [1732710021.311817090]: wait for voice command ... +[ INFO] [1732710021.411874783]: wait for voice command ... +[ INFO] [1732710021.511935439]: wait for voice command ... +[ INFO] [1732710021.611895765]: wait for voice command ... +[ INFO] [1732710021.711905012]: wait for voice command ... +[ INFO] [1732710021.811954401]: wait for voice command ... +[ INFO] [1732710021.911910795]: wait for voice command ... +[ INFO] [1732710022.011839251]: wait for voice command ... +[ INFO] [1732710022.111834026]: wait for voice command ... +[ INFO] [1732710022.211841893]: wait for voice command ... +[ INFO] [1732710022.311857547]: wait for voice command ... +[ INFO] [1732710022.411882414]: wait for voice command ... +[ INFO] [1732710022.511843562]: wait for voice command ... +[ INFO] [1732710022.611897759]: wait for voice command ... +[ INFO] [1732710022.711934473]: wait for voice command ... +[ INFO] [1732710022.811846717]: wait for voice command ... +[ INFO] [1732710022.911895201]: wait for voice command ... +[ INFO] [1732710023.011849308]: wait for voice command ... +[ INFO] [1732710023.111831853]: wait for voice command ... +[ INFO] [1732710023.211900839]: wait for voice command ... +[ INFO] [1732710023.311816052]: wait for voice command ... +[ INFO] [1732710023.411915304]: wait for voice command ... +[ INFO] [1732710023.511901192]: wait for voice command ... +[ INFO] [1732710023.611911719]: wait for voice command ... +[ INFO] [1732710023.711797709]: wait for voice command ... +[ INFO] [1732710023.811802524]: wait for voice command ... +[ INFO] [1732710023.911915447]: wait for voice command ... +[ INFO] [1732710024.011877091]: wait for voice command ... +[ INFO] [1732710024.111916392]: wait for voice command ... +[ INFO] [1732710024.211905466]: wait for voice command ... +[ INFO] [1732710024.311955041]: wait for voice command ... +[ INFO] [1732710024.411798256]: wait for voice command ... +[ INFO] [1732710024.511873878]: wait for voice command ... +[ INFO] [1732710024.611832415]: wait for voice command ... +[ INFO] [1732710024.711898913]: wait for voice command ... +[ INFO] [1732710024.811876366]: wait for voice command ... +[ INFO] [1732710024.911951984]: wait for voice command ... +[ INFO] [1732710025.011829707]: wait for voice command ... +[ INFO] [1732710025.111934208]: wait for voice command ... +[ INFO] [1732710025.211842321]: wait for voice command ... +[ INFO] [1732710025.311911199]: wait for voice command ... +[ INFO] [1732710025.411890613]: wait for voice command ... +[ INFO] [1732710025.511924776]: wait for voice command ... +[ INFO] [1732710025.611979667]: wait for voice command ... +[ INFO] [1732710025.711864745]: wait for voice command ... +[ INFO] [1732710025.811839436]: wait for voice command ... +[ INFO] [1732710025.911785154]: wait for voice command ... +[ INFO] [1732710026.011878788]: wait for voice command ... +[ INFO] [1732710026.111895148]: wait for voice command ... +[ INFO] [1732710026.211957521]: wait for voice command ... +[ INFO] [1732710026.311838861]: wait for voice command ... +[ INFO] [1732710026.411855350]: wait for voice command ... +[ INFO] [1732710026.511872628]: wait for voice command ... +"メス" +[ INFO] [1732710026.611854986]: wait for voice command ... +[ INFO] [1732710033.358865797]: wait-interpolation debug: start +[ INFO] [1732710033.359011721]: wait-interpolation debug: end +[ INFO] [1732710039.915391946]: wait-interpolation debug: start +[ INFO] [1732710040.905437631]: wait-interpolation debug: end +[ WARN] [1732710041.006930272]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732710041.013098709]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732710041.013189815]: original trajectory command : +[ WARN] [1732710041.013225441]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (1000) +[ WARN] [1732710041.013254001]: current angle vector : #f(50.0 17.8275 14.7726 46.824 -78.4543 6.11414 -34.739 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732710041.013270564]: new trajectory command : dvi = 2 +[ WARN] [1732710041.013309176]: : #f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732710041.013340863]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732710041.013371414]: new trajectory command : +[ WARN] [1732710041.013433109]: : (#f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (500 500) +[ INFO] [1732710041.016686444]: wait-interpolation debug: start +[ INFO] [1732710042.194967201]: wait-interpolation debug: end +[ INFO] [1732710042.197602154]: wait for target... +[ INFO] [1732710042.205053804]: wait for target... +[ INFO] [1732710042.215031164]: wait for target... +[ INFO] [1732710042.225055825]: wait for target... +[ INFO] [1732710042.235016150]: wait for target... +[ INFO] [1732710042.245054300]: wait for target... +[ INFO] [1732710042.255046636]: wait for target... +[ INFO] [1732710042.265029200]: wait for target... +[ INFO] [1732710042.275072987]: wait for target... +[ INFO] [1732710042.285057977]: wait for target... +[ INFO] [1732710042.295013693]: wait for target... +[ INFO] [1732710042.305086666]: wait for target... +[ INFO] [1732710042.315075916]: wait for target... +[ INFO] [1732710042.325052334]: wait for target... +[ INFO] [1732710042.335016246]: wait for target... +[ INFO] [1732710042.345016565]: wait for target... +[ INFO] [1732710042.355062798]: wait for target... +[ INFO] [1732710042.365073545]: wait for target... +[ INFO] [1732710042.387257066]: wait for target... +[ INFO] [1732710042.387346667]: wait for target... +[ INFO] [1732710042.395028698]: wait for target... +[ INFO] [1732710042.405038458]: wait for target... +[ INFO] [1732710042.415067405]: wait for target... +[ INFO] [1732710042.425044968]: wait for target... +[ INFO] [1732710042.435085411]: wait for target... +[ INFO] [1732710042.445020646]: wait for target... +[ INFO] [1732710042.455058454]: wait for target... +[ INFO] [1732710042.465068128]: wait for target... +[ INFO] [1732710042.475064966]: wait for target... +[ INFO] [1732710042.485061156]: wait for target... +[ INFO] [1732710042.495064736]: wait for target... +[ INFO] [1732710042.505063611]: wait for target... +[ INFO] [1732710042.515052539]: wait for target... +[ INFO] [1732710042.525058594]: wait for target... +[ INFO] [1732710042.535023874]: wait for target... +[ INFO] [1732710042.545054788]: wait for target... +[ INFO] [1732710042.555059366]: wait for target... +[ INFO] [1732710042.565058622]: wait for target... +[ INFO] [1732710042.575070878]: wait for target... +[ INFO] [1732710042.585054848]: wait for target... +[ INFO] [1732710042.595099654]: wait for target... +[ INFO] [1732710042.605061209]: wait for target... +[ INFO] [1732710042.615060231]: wait for target... +[ INFO] [1732710042.625088404]: wait for target... +[ INFO] [1732710042.635057297]: wait for target... +[ INFO] [1732710042.645068340]: wait for target... +[ INFO] [1732710042.655048227]: wait for target... +[ INFO] [1732710042.665064112]: wait for target... +[ INFO] [1732710042.675063933]: wait for target... +[ INFO] [1732710042.685062072]: wait for target... +[ INFO] [1732710042.695068592]: wait for target... +[ INFO] [1732710042.705060262]: wait for target... +[ INFO] [1732710042.715059159]: wait for target... +[ INFO] [1732710042.725060923]: wait for target... +[ INFO] [1732710042.735038206]: wait for target... +[ INFO] [1732710042.745059219]: wait for target... +[ INFO] [1732710042.755063863]: wait for target... +[ INFO] [1732710042.765050532]: wait for target... +[ INFO] [1732710042.775024068]: wait for target... +[ INFO] [1732710042.785071553]: wait for target... +[ INFO] [1732710042.795058080]: wait for target... +[ INFO] [1732710042.805018126]: wait for target... +[ INFO] [1732710042.815013412]: wait for target... +[ INFO] [1732710042.825051794]: wait for target... +[ INFO] [1732710042.835017045]: wait for target... +[ INFO] [1732710042.845048103]: wait for target... +[ INFO] [1732710042.855018910]: wait for target... +[ INFO] [1732710042.865015053]: wait for target... +[ INFO] [1732710042.875052189]: wait for target... +[ INFO] [1732710042.885017417]: wait for target... +[ INFO] [1732710042.895019431]: wait for target... +[ INFO] [1732710042.905017760]: wait for target... +[ INFO] [1732710042.915051372]: wait for target... +[ INFO] [1732710042.925015686]: wait for target... +[ INFO] [1732710042.935048727]: wait for target... +[ INFO] [1732710042.945167042]: wait for target... +[ INFO] [1732710042.955018751]: wait for target... +[ INFO] [1732710042.965097895]: wait for target... +[ INFO] [1732710042.975056424]: wait for target... +[ INFO] [1732710042.985017414]: wait for target... +[ INFO] [1732710042.995020518]: wait for target... +[ INFO] [1732710043.005056037]: wait for target... +[ INFO] [1732710043.015053541]: wait for target... +[ INFO] [1732710043.025054883]: wait for target... +[ INFO] [1732710043.035026091]: wait for target... +[ INFO] [1732710043.045059866]: wait for target... +[ INFO] [1732710043.055061236]: wait for target... +[ INFO] [1732710043.065053261]: wait for target... +[ INFO] [1732710043.075023919]: wait for target... +[ INFO] [1732710043.085015140]: wait for target... +[ INFO] [1732710043.095008800]: wait for target... +[ INFO] [1732710043.105064231]: wait for target... +[ INFO] [1732710043.115023048]: wait for target... +[ INFO] [1732710043.125047685]: wait for target... +[ INFO] [1732710043.135016095]: wait for target... +[ INFO] [1732710043.145062205]: wait for target... +[ INFO] [1732710043.155079692]: wait for target... +[ INFO] [1732710043.165034301]: wait for target... +[ INFO] [1732710043.175060849]: wait for target... +[ INFO] [1732710043.185018542]: wait for target... +[ INFO] [1732710043.195008999]: wait for target... +[ INFO] [1732710043.205028311]: wait for target... +[ INFO] [1732710043.215061976]: wait for target... +[ INFO] [1732710043.225055909]: wait for target... +[ INFO] [1732710043.235024954]: wait for target... +[ INFO] [1732710043.245055672]: wait for target... +[ INFO] [1732710043.255056129]: wait for target... +[ INFO] [1732710043.265049335]: wait for target... +[ INFO] [1732710043.275080590]: wait for target... +[ INFO] [1732710043.285046927]: wait for target... +[ INFO] [1732710043.295017552]: wait for target... +[ INFO] [1732710043.305024301]: wait for target... +[ INFO] [1732710043.315022406]: wait for target... +[ INFO] [1732710043.325052299]: wait for target... +[ INFO] [1732710043.335168054]: wait for target... +[ INFO] [1732710043.345017844]: wait for target... +[ INFO] [1732710043.355066977]: wait for target... +[ INFO] [1732710043.365033300]: wait for target... +[ INFO] [1732710043.375068702]: wait for target... +[ INFO] [1732710043.385016836]: wait for target... +[ INFO] [1732710043.395071482]: wait for target... +[ INFO] [1732710043.405053840]: wait for target... +[ INFO] [1732710043.415032929]: wait for target... +[ INFO] [1732710043.425076168]: wait for target... +[ INFO] [1732710043.435020185]: wait for target... +[ INFO] [1732710043.445043982]: wait for target... +[ INFO] [1732710043.455060995]: wait for target... +[ INFO] [1732710043.465062393]: wait for target... +[ INFO] [1732710043.475059742]: wait for target... +[ INFO] [1732710043.485054407]: wait for target... +[ INFO] [1732710043.495063530]: wait for target... +[ INFO] [1732710043.505065118]: wait for target... +[ INFO] [1732710043.515055222]: wait for target... +[ INFO] [1732710043.525024825]: wait for target... +[ INFO] [1732710043.535058375]: wait for target... +[ INFO] [1732710043.545057639]: wait for target... +[ INFO] [1732710043.555061980]: wait for target... +[ INFO] [1732710043.565027562]: wait for target... +[ INFO] [1732710043.575081407]: wait for target... +[ INFO] [1732710043.585069075]: wait for target... +[ INFO] [1732710043.595052108]: wait for target... +[ INFO] [1732710043.605018070]: wait for target... +[ INFO] [1732710043.615050437]: wait for target... +[ INFO] [1732710043.625062665]: wait for target... +[ INFO] [1732710043.635056545]: wait for target... +[ INFO] [1732710043.645066272]: wait for target... +[ INFO] [1732710043.655062799]: wait for target... +[ INFO] [1732710043.665079261]: wait for target... +[ INFO] [1732710043.675068612]: wait for target... +[ INFO] [1732710043.685027514]: wait for target... +[ INFO] [1732710043.695053515]: wait for target... +[ INFO] [1732710043.705065240]: wait for target... +[ INFO] [1732710043.715024308]: wait for target... +[ INFO] [1732710043.725048745]: wait for target... +[ INFO] [1732710043.735034516]: wait for target... +[ INFO] [1732710043.745041694]: wait for target... +[ INFO] [1732710043.755059641]: wait for target... +[ INFO] [1732710043.765060402]: wait for target... +[ INFO] [1732710043.775022860]: wait for target... +[ INFO] [1732710043.785024488]: wait for target... +[ INFO] [1732710043.795019160]: wait for target... +[ INFO] [1732710043.805017045]: wait for target... +[ INFO] [1732710043.815051519]: wait for target... +[ INFO] [1732710043.825016456]: wait for target... +[ INFO] [1732710043.835073433]: wait for target... +[ INFO] [1732710043.845051080]: wait for target... +[ INFO] [1732710043.855059884]: wait for target... +[ INFO] [1732710043.865055172]: wait for target... +[ INFO] [1732710043.875061348]: wait for target... +[ INFO] [1732710043.885043071]: wait for target... +[ INFO] [1732710043.895030019]: wait for target... +[ INFO] [1732710043.905089433]: wait for target... +[ INFO] [1732710043.915052197]: wait for target... +[ INFO] [1732710043.925037079]: wait for target... +[ INFO] [1732710043.935034511]: wait for target... +[ INFO] [1732710043.945018059]: wait for target... +[ INFO] [1732710043.955061399]: wait for target... +[ INFO] [1732710043.965050723]: wait for target... +[ INFO] [1732710043.975019704]: wait for target... +[ INFO] [1732710043.985051418]: wait for target... +[ INFO] [1732710043.995051968]: wait for target... +[ INFO] [1732710044.005056602]: wait for target... +[ INFO] [1732710044.015026747]: wait for target... +[ INFO] [1732710044.025055560]: wait for target... +[ INFO] [1732710044.035055072]: wait for target... +[ INFO] [1732710044.045054702]: wait for target... +[ INFO] [1732710044.055030381]: wait for target... +[ INFO] [1732710044.065051734]: wait for target... +[ INFO] [1732710044.075015513]: wait for target... +[ INFO] [1732710044.085057724]: wait for target... +[ INFO] [1732710044.095017486]: wait for target... +[ INFO] [1732710044.105020738]: wait for target... +[ INFO] [1732710044.115058637]: wait for target... +[ INFO] [1732710044.125058162]: wait for target... +[ INFO] [1732710044.135055015]: wait for target... +[ INFO] [1732710044.145059288]: wait for target... +[ INFO] [1732710044.155026928]: wait for target... +[ INFO] [1732710044.165096605]: wait for target... +[ INFO] [1732710044.175059572]: wait for target... +[ INFO] [1732710044.185057871]: wait for target... +[ INFO] [1732710044.195066089]: wait for target... +[ INFO] [1732710044.205019734]: wait for target... +[ INFO] [1732710044.215072535]: wait for target... +[ INFO] [1732710044.225075858]: wait for target... +[ INFO] [1732710044.235007242]: wait for target... +[ INFO] [1732710044.245050659]: wait for target... +[ INFO] [1732710044.255050508]: wait for target... +[ INFO] [1732710044.265017627]: wait for target... +[ INFO] [1732710044.275058468]: wait for target... +[ INFO] [1732710044.285045565]: wait for target... +[ INFO] [1732710044.295058669]: wait for target... +[ INFO] [1732710044.305052564]: wait for target... +[ INFO] [1732710044.315052731]: wait for target... +[ INFO] [1732710044.325072871]: wait for target... +[ INFO] [1732710044.335068192]: wait for target... +[ INFO] [1732710044.345015273]: wait for target... +[ INFO] [1732710044.355065747]: wait for target... +[ INFO] [1732710044.365066610]: wait for target... +[ INFO] [1732710044.375065404]: wait for target... +[ INFO] [1732710044.385060520]: wait for target... +[ INFO] [1732710044.395048634]: wait for target... +[ INFO] [1732710044.405015677]: wait for target... +[ INFO] [1732710044.415023681]: wait for target... +[ INFO] [1732710044.425024175]: wait for target... +[ INFO] [1732710044.435027502]: wait for target... +[ INFO] [1732710044.445054279]: wait for target... +[ INFO] [1732710044.455048983]: wait for target... +[ INFO] [1732710044.465057543]: wait for target... +[ INFO] [1732710044.475055626]: wait for target... +[ INFO] [1732710044.485048664]: wait for target... +[ INFO] [1732710044.495058735]: wait for target... +[ INFO] [1732710044.505026764]: wait for target... +[ INFO] [1732710044.515024214]: wait for target... +[ INFO] [1732710044.525017593]: wait for target... +[ INFO] [1732710044.535031009]: wait for target... +[ INFO] [1732710044.545042418]: wait for target... +[ INFO] [1732710044.555023903]: wait for target... +[ INFO] [1732710044.565057514]: wait for target... +[ INFO] [1732710044.575128725]: wait for target... +[ INFO] [1732710044.585137340]: wait for target... +[ INFO] [1732710044.595140699]: wait for target... +[ INFO] [1732710044.605135476]: wait for target... +[ INFO] [1732710044.615135687]: wait for target... +[ INFO] [1732710044.625166406]: wait for target... +[ INFO] [1732710044.635125668]: wait for target... +[ INFO] [1732710044.645137528]: wait for target... +[ INFO] [1732710044.655145682]: wait for target... +[ INFO] [1732710044.665100728]: wait for target... +[ INFO] [1732710044.675130202]: wait for target... +[ INFO] [1732710044.685094525]: wait for target... +[ INFO] [1732710044.695064007]: wait for target... +[ INFO] [1732710044.705071412]: wait for target... +[ INFO] [1732710044.715082293]: wait for target... +[ INFO] [1732710044.725055510]: wait for target... +[ INFO] [1732710044.735050977]: wait for target... +[ INFO] [1732710044.745057839]: wait for target... +[ INFO] [1732710044.755010952]: wait for target... +[ INFO] [1732710044.765096204]: wait for target... +[ INFO] [1732710044.775052365]: wait for target... +[ INFO] [1732710044.785019693]: wait for target... +[ INFO] [1732710044.795054175]: wait for target... +[ INFO] [1732710044.805026877]: wait for target... +[ INFO] [1732710044.815027331]: wait for target... +[ INFO] [1732710044.825058925]: wait for target... +[ INFO] [1732710044.835065973]: wait for target... +[ INFO] [1732710044.845017634]: wait for target... +[ INFO] [1732710044.855065893]: wait for target... +[ INFO] [1732710044.865128840]: wait for target... +[ INFO] [1732710044.875067721]: wait for target... +[ INFO] [1732710044.885065396]: wait for target... +[ INFO] [1732710044.895028520]: wait for target... +[ INFO] [1732710044.905063752]: wait for target... +[ INFO] [1732710044.915055534]: wait for target... +[ INFO] [1732710044.925059225]: wait for target... +[ INFO] [1732710044.935025096]: wait for target... +[ INFO] [1732710044.945050699]: wait for target... +[ INFO] [1732710044.955062684]: wait for target... +[ INFO] [1732710044.965059369]: wait for target... +[ INFO] [1732710044.975031333]: wait for target... +[ INFO] [1732710044.985016792]: wait for target... +[ INFO] [1732710044.995064572]: wait for target... +[ INFO] [1732710045.005058648]: wait for target... +[ INFO] [1732710045.015074253]: wait for target... +[ INFO] [1732710045.025088135]: wait for target... +[ INFO] [1732710045.035056589]: wait for target... +[ INFO] [1732710045.045052943]: wait for target... +[ INFO] [1732710045.055060585]: wait for target... +[ INFO] [1732710045.065020348]: wait for target... +[ INFO] [1732710045.075057998]: wait for target... +[ INFO] [1732710045.085048444]: wait for target... +[ INFO] [1732710045.095050357]: wait for target... +[ INFO] [1732710045.105064790]: wait for target... +[ INFO] [1732710045.115076517]: wait for target... +[ INFO] [1732710045.125016248]: wait for target... +[ INFO] [1732710045.135053455]: wait for target... +[ INFO] [1732710045.145088342]: wait for target... +[ INFO] [1732710045.155072391]: wait for target... +[ INFO] [1732710045.165057503]: wait for target... +[ INFO] [1732710045.175058568]: wait for target... +[ INFO] [1732710045.185069034]: wait for target... +[ INFO] [1732710045.195053674]: wait for target... +[ INFO] [1732710045.205017542]: wait for target... +[ INFO] [1732710045.215063027]: wait for target... +[ INFO] [1732710045.225055652]: wait for target... +[ INFO] [1732710045.235060176]: wait for target... +[ INFO] [1732710045.245018484]: wait for target... +[ INFO] [1732710045.255037384]: wait for target... +[ INFO] [1732710045.265015624]: wait for target... +[ INFO] [1732710045.275030254]: wait for target... +[ INFO] [1732710045.285020329]: wait for target... +[ INFO] [1732710045.295026286]: wait for target... +[ INFO] [1732710045.305078843]: wait for target... +[ INFO] [1732710045.315024648]: wait for target... +[ INFO] [1732710045.325010877]: wait for target... +[ INFO] [1732710045.335018274]: wait for target... +[ INFO] [1732710045.345028377]: wait for target... +[ INFO] [1732710045.355062953]: wait for target... +[ INFO] [1732710045.365060271]: wait for target... +[ INFO] [1732710045.375239457]: wait for target... +[ INFO] [1732710045.385028495]: wait for target... +[ INFO] [1732710045.395325610]: wait for target... +[ INFO] [1732710045.405213411]: wait for target... +[ INFO] [1732710045.415255641]: wait for target... +[ INFO] [1732710045.425047136]: wait for target... +[ INFO] [1732710045.435048053]: wait for target... +[ INFO] [1732710045.445075925]: wait for target... +[ INFO] [1732710045.455081905]: wait for target... +[ INFO] [1732710045.465182784]: wait for target... +[ INFO] [1732710045.475046660]: wait for target... +[ INFO] [1732710045.485053093]: wait for target... +[ INFO] [1732710045.495072081]: wait for target... +[ INFO] [1732710045.505091380]: wait for target... +[ INFO] [1732710045.515087350]: wait for target... +[ INFO] [1732710045.525033705]: wait for target... +[ INFO] [1732710045.535028230]: wait for target... +[ INFO] [1732710045.545023959]: wait for target... +[ INFO] [1732710045.555018889]: wait for target... +[ INFO] [1732710045.565036376]: wait for target... +[ INFO] [1732710045.575031764]: wait for target... +[ INFO] [1732710045.585025827]: wait for target... +[ INFO] [1732710045.595063002]: wait for target... +[ INFO] [1732710045.605051241]: wait for target... +[ INFO] [1732710045.615088879]: wait for target... +[ INFO] [1732710045.625048656]: wait for target... +[ INFO] [1732710045.635056960]: wait for target... +[ INFO] [1732710045.645058147]: wait for target... +[ INFO] [1732710045.655010258]: wait for target... +[ INFO] [1732710045.665143593]: wait for target... +[ INFO] [1732710045.675051969]: wait for target... +[ INFO] [1732710045.685027627]: wait for target... +[ INFO] [1732710045.695054966]: wait for target... +[ INFO] [1732710045.705023787]: wait for target... +[ INFO] [1732710045.715062647]: wait for target... +[ INFO] [1732710045.725060427]: wait for target... +[ INFO] [1732710045.735016115]: wait for target... +[ INFO] [1732710045.745059713]: wait for target... +[ INFO] [1732710045.755067138]: wait for target... +[ INFO] [1732710045.765056060]: wait for target... +[ INFO] [1732710045.775025881]: wait for target... +[ INFO] [1732710045.785015440]: wait for target... +[ INFO] [1732710045.795017446]: wait for target... +[ INFO] [1732710045.805065272]: wait for target... +[ INFO] [1732710045.815051456]: wait for target... +[ INFO] [1732710045.825096916]: wait for target... +[ INFO] [1732710045.835020009]: wait for target... +[ INFO] [1732710045.845066649]: wait for target... +[ INFO] [1732710045.855061526]: wait for target... +[ INFO] [1732710045.865059554]: wait for target... +[ INFO] [1732710045.875053327]: wait for target... +[ INFO] [1732710045.885116064]: wait for target... +[ INFO] [1732710045.895057603]: wait for target... +[ INFO] [1732710045.905060255]: wait for target... +[ INFO] [1732710045.915056751]: wait for target... +[ INFO] [1732710045.925060431]: wait for target... +[ INFO] [1732710045.935055942]: wait for target... +[ INFO] [1732710045.945020413]: wait for target... +[ INFO] [1732710045.955064274]: wait for target... +[ INFO] [1732710045.965068248]: wait for target... +[ INFO] [1732710045.975059500]: wait for target... +[ INFO] [1732710045.985076038]: wait for target... +[ INFO] [1732710045.995052955]: wait for target... +[ INFO] [1732710046.005021377]: wait for target... +[ INFO] [1732710046.015073837]: wait for target... +[ INFO] [1732710046.025057428]: wait for target... +[ INFO] [1732710046.035019988]: wait for target... +[ INFO] [1732710046.045020454]: wait for target... +[ INFO] [1732710046.055064767]: wait for target... +[ INFO] [1732710046.065019816]: wait for target... +[ INFO] [1732710046.075062353]: wait for target... +[ INFO] [1732710046.085018109]: wait for target... +[ INFO] [1732710046.095023847]: wait for target... +[ INFO] [1732710046.105047138]: wait for target... +[ INFO] [1732710046.115069737]: wait for target... +[ INFO] [1732710046.125062520]: wait for target... +[ INFO] [1732710046.135056965]: wait for target... +[ INFO] [1732710046.145028341]: wait for target... +[ INFO] [1732710046.155054052]: wait for target... +[ INFO] [1732710046.165052971]: wait for target... +[ INFO] [1732710046.175058565]: wait for target... +[ INFO] [1732710046.185057334]: wait for target... +[ INFO] [1732710046.195060939]: wait for target... +[ INFO] [1732710046.205086938]: wait for target... +[ INFO] [1732710046.215056541]: wait for target... +[ INFO] [1732710046.225054978]: wait for target... +[ INFO] [1732710046.235018170]: wait for target... +[ INFO] [1732710046.245060420]: wait for target... +[ INFO] [1732710046.255062347]: wait for target... +[ INFO] [1732710046.265064990]: wait for target... +[ INFO] [1732710046.275024313]: wait for target... +[ INFO] [1732710046.285062914]: wait for target... +[ INFO] [1732710046.295062861]: wait for target... +[ INFO] [1732710046.305130568]: wait for target... +[ INFO] [1732710046.315089080]: wait for target... +[ INFO] [1732710046.325054898]: wait for target... +[ INFO] [1732710046.335028892]: wait for target... +[ INFO] [1732710046.345058253]: wait for target... +[ INFO] [1732710046.355062081]: wait for target... +[ INFO] [1732710046.365055906]: wait for target... +[ INFO] [1732710046.375058614]: wait for target... +[ INFO] [1732710046.385016559]: wait for target... +[ INFO] [1732710046.395064389]: wait for target... +[ INFO] [1732710046.405018623]: wait for target... +[ INFO] [1732710046.415057640]: wait for target... +[ INFO] [1732710046.425048797]: wait for target... +[ INFO] [1732710046.435061688]: wait for target... +[ INFO] [1732710046.445090196]: wait for target... +[ INFO] [1732710046.455063139]: wait for target... +[ INFO] [1732710046.465072228]: wait for target... +[ INFO] [1732710046.475060309]: wait for target... +[ INFO] [1732710046.485009954]: wait for target... +[ INFO] [1732710046.495070189]: wait for target... +[ INFO] [1732710046.505016876]: wait for target... +[ INFO] [1732710046.515013197]: wait for target... +[ INFO] [1732710046.525053527]: wait for target... +[ INFO] [1732710046.535016580]: wait for target... +[ INFO] [1732710046.545013577]: wait for target... +[ INFO] [1732710046.555019965]: wait for target... +[ INFO] [1732710046.565053898]: wait for target... +[ INFO] [1732710046.575065426]: wait for target... +[ INFO] [1732710046.585014927]: wait for target... +[ INFO] [1732710046.595062129]: wait for target... +[ INFO] [1732710046.605070740]: wait for target... +[ INFO] [1732710046.615072092]: wait for target... +[ INFO] [1732710046.625029466]: wait for target... +[ INFO] [1732710046.635017600]: wait for target... +[ INFO] [1732710046.645048743]: wait for target... +[ INFO] [1732710046.655055911]: wait for target... +[ INFO] [1732710046.665062971]: wait for target... +[ INFO] [1732710046.675064434]: wait for target... +[ INFO] [1732710046.685012555]: wait for target... +[ INFO] [1732710046.695060603]: wait for target... +[ INFO] [1732710046.705058357]: wait for target... +[ INFO] [1732710046.715020954]: wait for target... +[ INFO] [1732710046.725060452]: wait for target... +[ INFO] [1732710046.735067270]: wait for target... +[ INFO] [1732710046.745055682]: wait for target... +[ INFO] [1732710046.755066288]: wait for target... +[ INFO] [1732710046.765104217]: wait for target... +[ INFO] [1732710046.775065150]: wait for target... +[ INFO] [1732710046.785038363]: wait for target... +[ INFO] [1732710046.795059754]: wait for target... +[ INFO] [1732710046.805024312]: wait for target... +[ INFO] [1732710046.815020131]: wait for target... +[ INFO] [1732710046.825026432]: wait for target... +[ INFO] [1732710046.835024283]: wait for target... +[ INFO] [1732710046.845017315]: wait for target... +[ INFO] [1732710046.855025933]: wait for target... +[ INFO] [1732710046.865057954]: wait for target... +[ INFO] [1732710046.875063896]: wait for target... +[ INFO] [1732710046.885025505]: wait for target... +[ INFO] [1732710046.895061655]: wait for target... +[ INFO] [1732710046.905027012]: wait for target... +[ INFO] [1732710046.915063392]: wait for target... +[ INFO] [1732710046.925049922]: wait for target... +[ INFO] [1732710046.935063912]: wait for target... +[ INFO] [1732710046.945031439]: wait for target... +[ INFO] [1732710046.955019006]: wait for target... +[ INFO] [1732710046.965005428]: wait for target... +[ INFO] [1732710046.975031978]: wait for target... +[ INFO] [1732710046.985050030]: wait for target... +[ INFO] [1732710046.995023438]: wait for target... +[ INFO] [1732710047.005059503]: wait for target... +[ INFO] [1732710047.015060184]: wait for target... +[ INFO] [1732710047.025058682]: wait for target... +[ INFO] [1732710047.035050010]: wait for target... +[ INFO] [1732710047.045061948]: wait for target... +[ INFO] [1732710047.055059895]: wait for target... +[ INFO] [1732710047.065048988]: wait for target... +[ INFO] [1732710047.075063554]: wait for target... +[ INFO] [1732710047.085017810]: wait for target... +[ INFO] [1732710047.095063539]: wait for target... +[ INFO] [1732710047.105069560]: wait for target... +[ INFO] [1732710047.115060545]: wait for target... +[ INFO] [1732710047.125061917]: wait for target... +[ INFO] [1732710047.135088839]: wait for target... +[ INFO] [1732710047.145060849]: wait for target... +[ INFO] [1732710047.155032443]: wait for target... +[ INFO] [1732710047.165059017]: wait for target... +[ INFO] [1732710047.175091498]: wait for target... +[ INFO] [1732710047.185024109]: wait for target... +[ INFO] [1732710047.195062223]: wait for target... +[ INFO] [1732710047.205061643]: wait for target... +[ INFO] [1732710047.215016564]: wait for target... +[ INFO] [1732710047.225087950]: wait for target... +[ INFO] [1732710047.235017249]: wait for target... +[ INFO] [1732710047.245061234]: wait for target... +[ INFO] [1732710047.255061352]: wait for target... +[ INFO] [1732710047.265053677]: wait for target... +[ INFO] [1732710047.275086849]: wait for target... +[ INFO] [1732710047.285061367]: wait for target... +[ INFO] [1732710047.295063435]: wait for target... +[ INFO] [1732710047.305017299]: wait for target... +[ INFO] [1732710047.315058614]: wait for target... +[ INFO] [1732710047.325090117]: wait for target... +[ INFO] [1732710047.335019797]: wait for target... +[ INFO] [1732710047.345075286]: wait for target... +[ INFO] [1732710047.355064483]: wait for target... +[ INFO] [1732710047.365023282]: wait for target... +[ INFO] [1732710047.375074432]: wait for target... +[ INFO] [1732710047.385057894]: wait for target... +[ INFO] [1732710047.395066068]: wait for target... +[ INFO] [1732710047.405054004]: wait for target... +[ INFO] [1732710047.415059601]: wait for target... +[ INFO] [1732710047.425058255]: wait for target... +[ INFO] [1732710047.435018918]: wait for target... +[ INFO] [1732710047.445045635]: wait for target... +[ INFO] [1732710047.455049892]: wait for target... +[ INFO] [1732710047.465060478]: wait for target... +[ INFO] [1732710047.475065279]: wait for target... +[ INFO] [1732710047.485058317]: wait for target... +[ INFO] [1732710047.495060588]: wait for target... +[ INFO] [1732710047.505064681]: wait for target... +[ INFO] [1732710047.515062354]: wait for target... +[ INFO] [1732710047.525068666]: wait for target... +[ INFO] [1732710047.535048824]: wait for target... +[ INFO] [1732710047.545053749]: wait for target... +[ INFO] [1732710047.555025256]: wait for target... +[ INFO] [1732710047.565027810]: wait for target... +[ INFO] [1732710047.575064136]: wait for target... +[ INFO] [1732710047.585104517]: wait for target... +[ INFO] [1732710047.595059622]: wait for target... +[ INFO] [1732710047.605051902]: wait for target... +[ INFO] [1732710047.615055233]: wait for target... +[ INFO] [1732710047.625041708]: wait for target... +[ INFO] [1732710047.635020178]: wait for target... +[ INFO] [1732710047.645264380]: wait for target... +[ INFO] [1732710047.655160251]: wait for target... +[ INFO] [1732710047.665126925]: wait for target... +[ INFO] [1732710047.675151533]: wait for target... +[ INFO] [1732710047.685102837]: wait for target... +[ INFO] [1732710047.695123126]: wait for target... +[ INFO] [1732710047.705100612]: wait for target... +[ INFO] [1732710047.715085112]: wait for target... +[ INFO] [1732710047.725070659]: wait for target... +[ INFO] [1732710047.735014329]: wait for target... +[ INFO] [1732710047.745077781]: wait for target... +[ INFO] [1732710047.755067994]: wait for target... +[ INFO] [1732710047.765024222]: wait for target... +[ INFO] [1732710047.775063578]: wait for target... +[ INFO] [1732710047.785046282]: wait for target... +[ INFO] [1732710047.795058856]: wait for target... +[ INFO] [1732710047.805053946]: wait for target... +[ INFO] [1732710047.815053270]: wait for target... +[ INFO] [1732710047.825031786]: wait for target... +[ INFO] [1732710047.835061441]: wait for target... +[ INFO] [1732710047.845063834]: wait for target... +[ INFO] [1732710047.855057788]: wait for target... +[ INFO] [1732710047.865081145]: wait for target... +[ INFO] [1732710047.875033524]: wait for target... +[ INFO] [1732710047.885020205]: wait for target... +[ INFO] [1732710047.895014970]: wait for target... +[ INFO] [1732710047.905034273]: wait for target... +[ INFO] [1732710047.915057161]: wait for target... +[ INFO] [1732710047.925017111]: wait for target... +[ INFO] [1732710047.935072220]: wait for target... +[ INFO] [1732710047.945053767]: wait for target... +[ INFO] [1732710047.955069284]: wait for target... +[ INFO] [1732710047.965052036]: wait for target... +[ INFO] [1732710047.975018449]: wait for target... +[ INFO] [1732710047.985076246]: wait for target... +[ INFO] [1732710047.995060212]: wait for target... +[ INFO] [1732710048.005016779]: wait for target... +[ INFO] [1732710048.015062169]: wait for target... +[ INFO] [1732710048.025052767]: wait for target... +[ INFO] [1732710048.035072789]: wait for target... +[ INFO] [1732710048.045020411]: wait for target... +[ INFO] [1732710048.055051136]: wait for target... +[ INFO] [1732710048.065092917]: wait for target... +[ INFO] [1732710048.075060150]: wait for target... +[ INFO] [1732710048.085056886]: wait for target... +[ INFO] [1732710048.095021529]: wait for target... +[ INFO] [1732710048.105022326]: wait for target... +[ INFO] [1732710048.115062044]: wait for target... +[ INFO] [1732710048.125045118]: wait for target... +[ INFO] [1732710048.135057285]: wait for target... +[ INFO] [1732710048.145058648]: wait for target... +[ INFO] [1732710048.155018118]: wait for target... +[ INFO] [1732710048.165061313]: wait for target... +[ INFO] [1732710048.175059374]: wait for target... +[ INFO] [1732710048.185025312]: wait for target... +[ INFO] [1732710048.195061180]: wait for target... +[ INFO] [1732710048.205059771]: wait for target... +[ INFO] [1732710048.215024164]: wait for target... +[ INFO] [1732710048.225058618]: wait for target... +[ INFO] [1732710048.235034262]: wait for target... +[ INFO] [1732710048.245025624]: wait for target... +[ INFO] [1732710048.255028108]: wait for target... +[ INFO] [1732710048.265023305]: wait for target... +[ INFO] [1732710048.275021007]: wait for target... +[ INFO] [1732710048.285017802]: wait for target... +[ INFO] [1732710048.295051577]: wait for target... +[ INFO] [1732710048.305021433]: wait for target... +[ INFO] [1732710048.315055270]: wait for target... +[ INFO] [1732710048.325023899]: wait for target... +[ INFO] [1732710048.335021426]: wait for target... +[ INFO] [1732710048.345025350]: wait for target... +[ INFO] [1732710048.355049391]: wait for target... +[ INFO] [1732710048.365040457]: wait for target... +[ INFO] [1732710048.375020011]: wait for target... +[ INFO] [1732710048.385025376]: wait for target... +[ INFO] [1732710048.395024889]: wait for target... +[ INFO] [1732710048.405054596]: wait for target... +[ INFO] [1732710048.415051988]: wait for target... +[ INFO] [1732710048.425016486]: wait for target... +[ INFO] [1732710048.435062158]: wait for target... +[ INFO] [1732710048.445048024]: wait for target... +[ INFO] [1732710048.455017269]: wait for target... +[ INFO] [1732710048.465056008]: wait for target... +[ INFO] [1732710048.475061694]: wait for target... +[ INFO] [1732710048.485051786]: wait for target... +[ INFO] [1732710048.495058981]: wait for target... +[ INFO] [1732710048.505058096]: wait for target... +[ INFO] [1732710048.515063172]: wait for target... +[ INFO] [1732710048.525015312]: wait for target... +[ INFO] [1732710048.535094348]: wait for target... +[ INFO] [1732710048.545028962]: wait for target... +[ INFO] [1732710048.555027024]: wait for target... +[ INFO] [1732710048.565011385]: wait for target... +[ INFO] [1732710048.575124665]: wait for target... +[ INFO] [1732710048.585047712]: wait for target... +[ INFO] [1732710048.595200637]: wait for target... +[ INFO] [1732710048.605095447]: wait for target... +[ INFO] [1732710048.615514038]: wait for target... +[ INFO] [1732710048.625175157]: wait for target... +[ INFO] [1732710048.635132808]: wait for target... +[ INFO] [1732710048.645108839]: wait for target... +[ INFO] [1732710048.655166357]: wait for target... +[ INFO] [1732710048.665136512]: wait for target... +[ INFO] [1732710048.675266207]: wait for target... +[ INFO] [1732710048.685074983]: wait for target... +[ INFO] [1732710048.695040151]: wait for target... +[ INFO] [1732710048.705094935]: wait for target... +[ INFO] [1732710048.715067110]: wait for target... +[ INFO] [1732710048.725020102]: wait for target... +[ INFO] [1732710048.735057217]: wait for target... +[ INFO] [1732710048.745062107]: wait for target... +[ INFO] [1732710048.755061909]: wait for target... +[ INFO] [1732710048.765066842]: wait for target... +[ INFO] [1732710048.775060073]: wait for target... +[ INFO] [1732710048.785026233]: wait for target... +[ INFO] [1732710048.795048928]: wait for target... +[ INFO] [1732710048.805060601]: wait for target... +[ INFO] [1732710048.815028499]: wait for target... +[ INFO] [1732710048.825020837]: wait for target... +[ INFO] [1732710048.835063037]: wait for target... +[ INFO] [1732710048.845112728]: wait for target... +[ INFO] [1732710048.855056853]: wait for target... +[ INFO] [1732710048.865086323]: wait for target... +[ INFO] [1732710048.875060447]: wait for target... +[ INFO] [1732710048.885015788]: wait for target... +[ INFO] [1732710048.895068417]: wait for target... +[ INFO] [1732710048.905017811]: wait for target... +[ INFO] [1732710048.915060647]: wait for target... +[ INFO] [1732710048.925050222]: wait for target... +[ INFO] [1732710048.935017859]: wait for target... +[ INFO] [1732710048.945011354]: wait for target... +[ INFO] [1732710048.955053582]: wait for target... +[ INFO] [1732710048.965060696]: wait for target... +[ INFO] [1732710048.975058369]: wait for target... +[ INFO] [1732710048.985095374]: wait for target... +[ INFO] [1732710048.995031486]: wait for target... +[ INFO] [1732710049.005034307]: wait for target... +[ INFO] [1732710049.015059287]: wait for target... +[ INFO] [1732710049.025058395]: wait for target... +[ INFO] [1732710049.035023466]: wait for target... +[ INFO] [1732710049.045015518]: wait for target... +[ INFO] [1732710049.055074899]: wait for target... +[ INFO] [1732710049.065105026]: wait for target... +[ INFO] [1732710049.075063045]: wait for target... +[ INFO] [1732710049.085016963]: wait for target... +[ INFO] [1732710049.095022281]: wait for target... +[ INFO] [1732710049.105029055]: wait for target... +[ INFO] [1732710049.115025472]: wait for target... +[ INFO] [1732710049.125054422]: wait for target... +[ INFO] [1732710049.135063216]: wait for target... +[ INFO] [1732710049.145111521]: wait for target... +[ INFO] [1732710049.155022661]: wait for target... +[ INFO] [1732710049.165063385]: wait for target... +[ INFO] [1732710049.175043930]: wait for target... +[ INFO] [1732710049.185098320]: wait for target... +[ INFO] [1732710049.195020761]: wait for target... +[ INFO] [1732710049.205020786]: wait for target... +[ INFO] [1732710049.215063786]: wait for target... +[ INFO] [1732710049.225067829]: wait for target... +[ INFO] [1732710049.235023001]: wait for target... +[ INFO] [1732710049.245019350]: wait for target... +[ INFO] [1732710049.255025471]: wait for target... +[ INFO] [1732710049.265069029]: wait for target... +[ INFO] [1732710049.275025431]: wait for target... +[ INFO] [1732710049.285058535]: wait for target... +[ INFO] [1732710049.295058584]: wait for target... +[ INFO] [1732710049.305027306]: wait for target... +[ INFO] [1732710049.315067473]: wait for target... +[ INFO] [1732710049.325089406]: wait for target... +[ INFO] [1732710049.335022307]: wait for target... +[ INFO] [1732710049.345065127]: wait for target... +[ INFO] [1732710049.355009244]: wait for target... +[ INFO] [1732710049.365065422]: wait for target... +[ INFO] [1732710049.375018610]: wait for target... +[ INFO] [1732710049.385051107]: wait for target... +[ INFO] [1732710049.395057455]: wait for target... +[ INFO] [1732710049.405020260]: wait for target... +[ INFO] [1732710049.415050484]: wait for target... +[ INFO] [1732710049.425018043]: wait for target... +[ INFO] [1732710049.435021986]: wait for target... +[ INFO] [1732710049.445062443]: wait for target... +[ INFO] [1732710049.455019682]: wait for target... +[ INFO] [1732710049.465116738]: wait for target... +[ INFO] [1732710049.475034721]: wait for target... +[ INFO] [1732710049.485021205]: wait for target... +[ INFO] [1732710049.495055271]: wait for target... +[ INFO] [1732710049.505028866]: wait for target... +[ INFO] [1732710049.515020742]: wait for target... +[ INFO] [1732710049.525144314]: wait for target... +[ INFO] [1732710049.535191324]: wait for target... +[ INFO] [1732710049.545115628]: wait for target... +[ INFO] [1732710049.555065489]: wait for target... +[ INFO] [1732710049.565097231]: wait for target... +[ INFO] [1732710049.575037589]: wait for target... +[ INFO] [1732710049.585062965]: wait for target... +[ INFO] [1732710049.595058415]: wait for target... +[ INFO] [1732710049.605060153]: wait for target... +[ INFO] [1732710049.615053602]: wait for target... +[ INFO] [1732710049.625022271]: wait for target... +[ INFO] [1732710049.635059727]: wait for target... +[ INFO] [1732710049.645025990]: wait for target... +[ INFO] [1732710049.655030928]: wait for target... +[ INFO] [1732710049.665045424]: wait for target... +[ INFO] [1732710049.675062971]: wait for target... +[ INFO] [1732710049.685021322]: wait for target... +[ INFO] [1732710049.695021175]: wait for target... +[ INFO] [1732710049.705053734]: wait for target... +[ INFO] [1732710049.715030933]: wait for target... +[ INFO] [1732710049.725063347]: wait for target... +[ INFO] [1732710049.735024938]: wait for target... +[ INFO] [1732710049.745067115]: wait for target... +[ INFO] [1732710049.755065584]: wait for target... +[ INFO] [1732710049.765035984]: wait for target... +[ INFO] [1732710049.775021901]: wait for target... +[ INFO] [1732710049.785032470]: wait for target... +[ INFO] [1732710049.795054054]: wait for target... +[ INFO] [1732710049.805027699]: wait for target... +[ INFO] [1732710049.815053490]: wait for target... +[ INFO] [1732710049.825079163]: wait for target... +[ INFO] [1732710049.835032721]: wait for target... +[ INFO] [1732710049.845063222]: wait for target... +[ INFO] [1732710049.855055220]: wait for target... +[ INFO] [1732710049.865028524]: wait for target... +[ INFO] [1732710049.875024692]: wait for target... +[ INFO] [1732710049.885030077]: wait for target... +[ INFO] [1732710049.895026564]: wait for target... +[ INFO] [1732710049.905037449]: wait for target... +[ INFO] [1732710049.915035249]: wait for target... +[ INFO] [1732710049.925025974]: wait for target... +[ INFO] [1732710049.935049675]: wait for target... +[ INFO] [1732710049.945059754]: wait for target... +[ INFO] [1732710049.955048820]: wait for target... +[ INFO] [1732710049.965057604]: wait for target... +[ INFO] [1732710049.975026464]: wait for target... +[ INFO] [1732710049.985085688]: wait for target... +[ INFO] [1732710049.995059847]: wait for target... +[ INFO] [1732710050.005020221]: wait for target... +[ INFO] [1732710050.015064123]: wait for target... +[ INFO] [1732710050.025021277]: wait for target... +[ INFO] [1732710050.035024691]: wait for target... +[ INFO] [1732710050.045052247]: wait for target... +[ INFO] [1732710050.055026210]: wait for target... +[ INFO] [1732710050.065076019]: wait for target... +[ INFO] [1732710050.075023099]: wait for target... +[ INFO] [1732710050.085066338]: wait for target... +[ INFO] [1732710050.095030507]: wait for target... +[ INFO] [1732710050.105059275]: wait for target... +[ INFO] [1732710050.115050039]: wait for target... +[ INFO] [1732710050.125021869]: wait for target... +[ INFO] [1732710050.135026023]: wait for target... +[ INFO] [1732710050.145071230]: wait for target... +[ INFO] [1732710050.155022444]: wait for target... +[ INFO] [1732710050.165051729]: wait for target... +[ INFO] [1732710050.175022328]: wait for target... +[ INFO] [1732710050.185062881]: wait for target... +[ INFO] [1732710050.195082355]: wait for target... +[ INFO] [1732710050.205051197]: wait for target... +[ INFO] [1732710050.215066909]: wait for target... +[ INFO] [1732710050.225017491]: wait for target... +[ INFO] [1732710050.235033104]: wait for target... +[ INFO] [1732710050.245028727]: wait for target... +[ INFO] [1732710050.255021356]: wait for target... +[ INFO] [1732710050.265098142]: wait for target... +[ INFO] [1732710050.275070316]: wait for target... +[ INFO] [1732710050.285069465]: wait for target... +[ INFO] [1732710050.295067134]: wait for target... +[ INFO] [1732710050.305040919]: wait for target... +[ INFO] [1732710050.315033395]: wait for target... +[ INFO] [1732710050.325020231]: wait for target... +[ INFO] [1732710050.335094478]: wait for target... +[ INFO] [1732710050.345056171]: wait for target... +[ INFO] [1732710050.355225322]: wait for target... +[ INFO] [1732710050.365264938]: wait for target... +[ INFO] [1732710050.375028871]: wait for target... +[ INFO] [1732710050.385053596]: wait for target... +[ INFO] [1732710050.395071414]: wait for target... +[ INFO] [1732710050.405069052]: wait for target... +[ INFO] [1732710050.415045463]: wait for target... +[ INFO] [1732710050.425063324]: wait for target... +[ INFO] [1732710050.435060583]: wait for target... +[ INFO] [1732710050.445156644]: wait for target... +[ INFO] [1732710050.455028088]: wait for target... +[ INFO] [1732710050.465024528]: wait for target... +[ INFO] [1732710050.475030005]: wait for target... +[ INFO] [1732710050.485054487]: wait for target... +[ INFO] [1732710050.495023243]: wait for target... +[ INFO] [1732710050.505060738]: wait for target... +[ INFO] [1732710050.515025372]: wait for target... +[ INFO] [1732710050.525024668]: wait for target... +[ INFO] [1732710050.535063059]: wait for target... +[ INFO] [1732710050.545044092]: wait for target... +[ INFO] [1732710050.555021032]: wait for target... +[ INFO] [1732710050.565054716]: wait for target... +[ INFO] [1732710050.575035903]: wait for target... +[ INFO] [1732710050.585071391]: wait for target... +[ INFO] [1732710050.595029948]: wait for target... +[ INFO] [1732710050.605056811]: wait for target... +[ INFO] [1732710050.615020970]: wait for target... +[ INFO] [1732710050.625072786]: wait for target... +[ INFO] [1732710050.635074237]: wait for target... +[ INFO] [1732710050.645019848]: wait for target... +[ INFO] [1732710050.655060897]: wait for target... +[ INFO] [1732710050.665061165]: wait for target... +[ INFO] [1732710050.675053576]: wait for target... +[ INFO] [1732710050.685060454]: wait for target... +[ INFO] [1732710050.695064519]: wait for target... +[ INFO] [1732710050.705054658]: wait for target... +[ INFO] [1732710050.715061251]: wait for target... +[ INFO] [1732710050.725049639]: wait for target... +[ INFO] [1732710050.735020130]: wait for target... +[ INFO] [1732710050.745043341]: wait for target... +[ INFO] [1732710050.755065466]: wait for target... +[ INFO] [1732710050.765066819]: wait for target... +[ INFO] [1732710050.775054413]: wait for target... +[ INFO] [1732710050.785040225]: wait for target... +[ INFO] [1732710050.795023937]: wait for target... +[ INFO] [1732710050.805062175]: wait for target... +[ INFO] [1732710050.815084107]: wait for target... +[ INFO] [1732710050.825052213]: wait for target... +[ INFO] [1732710050.835023605]: wait for target... +[ INFO] [1732710050.845027669]: wait for target... +[ INFO] [1732710050.855066087]: wait for target... +[ INFO] [1732710050.865063381]: wait for target... +[ INFO] [1732710050.875060007]: wait for target... +[ INFO] [1732710050.885062692]: wait for target... +[ INFO] [1732710050.894992938]: wait for target... +[ INFO] [1732710050.905037185]: wait for target... +[ INFO] [1732710050.915100174]: wait for target... +[ INFO] [1732710050.925058378]: wait for target... +[ INFO] [1732710050.935020438]: wait for target... +[ INFO] [1732710050.945077100]: wait for target... +[ INFO] [1732710050.955026837]: wait for target... +[ INFO] [1732710050.965062770]: wait for target... +[ INFO] [1732710050.975057931]: wait for target... +[ INFO] [1732710050.985059548]: wait for target... +[ INFO] [1732710050.995078909]: wait for target... +[ INFO] [1732710051.005064167]: wait for target... +[ INFO] [1732710051.015064737]: wait for target... +[ INFO] [1732710051.025062757]: wait for target... +[ INFO] [1732710051.035051844]: wait for target... +[ INFO] [1732710051.045055199]: wait for target... +[ INFO] [1732710051.055061752]: wait for target... +[ INFO] [1732710051.065021009]: wait for target... +[ INFO] [1732710051.075060350]: wait for target... +[ INFO] [1732710051.085019635]: wait for target... +[ INFO] [1732710051.095019404]: wait for target... +[ INFO] [1732710051.105082996]: wait for target... +[ INFO] [1732710051.115064365]: wait for target... +[ INFO] [1732710051.125043119]: wait for target... +[ INFO] [1732710051.135026569]: wait for target... +[ INFO] [1732710051.145046286]: wait for target... +[ INFO] [1732710050.655060897]: wait for target... +[ INFO] [1732710051.155074242]: wait for target... +[ INFO] [1732710051.165065458]: wait for target... +[ INFO] [1732710051.175061403]: wait for target... +[ INFO] [1732710051.185059402]: wait for target... +[ INFO] [1732710051.195057208]: wait for target... +[ INFO] [1732710051.205051397]: wait for target... +[ INFO] [1732710051.215060488]: wait for target... +[ INFO] [1732710051.225056052]: wait for target... +[ INFO] [1732710051.235021963]: wait for target... +[ INFO] [1732710051.245063458]: wait for target... +[ INFO] [1732710051.255066438]: wait for target... +[ INFO] [1732710051.265022304]: wait for target... +[ INFO] [1732710051.275054659]: wait for target... +[ INFO] [1732710051.285020864]: wait for target... +[ INFO] [1732710051.295088013]: wait for target... +[ INFO] [1732710051.305149433]: wait for target... +[ INFO] [1732710051.315156535]: wait for target... +[ INFO] [1732710051.325101198]: wait for target... +[ INFO] [1732710051.335124911]: wait for target... +[ INFO] [1732710051.345121646]: wait for target... +[ INFO] [1732710051.355056949]: wait for target... +[ INFO] [1732710051.365113032]: wait for target... +[ INFO] [1732710051.375089375]: wait for target... +[ INFO] [1732710051.385028249]: wait for target... +[ INFO] [1732710051.395037327]: wait for target... +[ INFO] [1732710051.405066364]: wait for target... +[ INFO] [1732710051.415062145]: wait for target... +[ INFO] [1732710051.425091065]: wait for target... +[ INFO] [1732710051.435062507]: wait for target... +[ INFO] [1732710051.445016947]: wait for target... +[ INFO] [1732710051.455062655]: wait for target... +[ INFO] [1732710051.465060491]: wait for target... +[ INFO] [1732710051.475059649]: wait for target... +[ INFO] [1732710051.485027455]: wait for target... +[ INFO] [1732710051.495048153]: wait for target... +[ INFO] [1732710051.505050567]: wait for target... +[ INFO] [1732710051.515025159]: wait for target... +[ INFO] [1732710051.525022581]: wait for target... +[ INFO] [1732710051.535046882]: wait for target... +[ INFO] [1732710051.545061813]: wait for target... +[ INFO] [1732710051.555064494]: wait for target... +[ INFO] [1732710051.565026819]: wait for target... +[ INFO] [1732710051.575018050]: wait for target... +[ INFO] [1732710051.585077450]: wait for target... +[ INFO] [1732710051.595062954]: wait for target... +[ INFO] [1732710051.605049586]: wait for target... +[ INFO] [1732710051.615064873]: wait for target... +[ INFO] [1732710051.625061709]: wait for target... +[ INFO] [1732710051.635083697]: wait for target... +[ INFO] [1732710051.645120175]: wait for target... +[ INFO] [1732710051.655047286]: wait for target... +[ INFO] [1732710051.665048360]: wait for target... +[ INFO] [1732710051.675022005]: wait for target... +[ INFO] [1732710051.685054503]: wait for target... +[ INFO] [1732710051.695018937]: wait for target... +[ INFO] [1732710051.705062013]: wait for target... +[ INFO] [1732710051.715034179]: wait for target... +[ INFO] [1732710051.725049118]: wait for target... +[ INFO] [1732710051.735018507]: wait for target... +[ INFO] [1732710051.745029927]: wait for target... +[ INFO] [1732710051.755022221]: wait for target... +[ INFO] [1732710051.765047449]: wait for target... +[ INFO] [1732710051.775061895]: wait for target... +[ INFO] [1732710051.785020975]: wait for target... +[ INFO] [1732710051.795055498]: wait for target... +[ INFO] [1732710051.805015790]: wait for target... +[ INFO] [1732710051.815057373]: wait for target... +[ INFO] [1732710051.825047684]: wait for target... +[ INFO] [1732710051.835057893]: wait for target... +[ INFO] [1732710051.845058356]: wait for target... +[ INFO] [1732710051.855063313]: wait for target... +[ INFO] [1732710051.865054610]: wait for target... +[ INFO] [1732710051.875064051]: wait for target... +[ INFO] [1732710051.885020987]: wait for target... +[ INFO] [1732710051.895027360]: wait for target... +[ INFO] [1732710051.905103255]: wait for target... +[ INFO] [1732710051.915050678]: wait for target... +[ INFO] [1732710051.925053752]: wait for target... +[ INFO] [1732710051.935061848]: wait for target... +[ INFO] [1732710051.945028562]: wait for target... +[ INFO] [1732710051.955023616]: wait for target... +[ INFO] [1732710051.965015412]: wait for target... +[ INFO] [1732710051.975023143]: wait for target... +[ INFO] [1732710051.985019104]: wait for target... +[ INFO] [1732710051.995035862]: wait for target... +[ INFO] [1732710052.005040346]: wait for target... +[ INFO] [1732710052.015022850]: wait for target... +[ INFO] [1732710052.025032465]: wait for target... +[ INFO] [1732710052.035030083]: wait for target... +[ INFO] [1732710052.045055519]: wait for target... +[ INFO] [1732710052.055018035]: wait for target... +[ INFO] [1732710052.065135063]: wait for target... +[ INFO] [1732710052.075025442]: wait for target... +[ INFO] [1732710052.085090160]: wait for target... +[ INFO] [1732710052.095262478]: wait for target... +[ INFO] [1732710052.105152484]: wait for target... +[ INFO] [1732710052.115195296]: wait for target... +[ INFO] [1732710052.125076017]: wait for target... +[ INFO] [1732710052.135063069]: wait for target... +[ INFO] [1732710052.145141629]: wait for target... +[ INFO] [1732710052.155039188]: wait for target... +[ INFO] [1732710052.165151569]: wait for target... +[ INFO] [1732710052.175158167]: wait for target... +[ INFO] [1732710052.185159493]: wait for target... + C-c C-c[ INFO] [1732710052.195387800]: wait for target... +[ INFO] [1732710052.205145699]: wait for target... +interrupt58.B1-irteusgl$ load "main.l" +[ INFO] [1732710077.957344647]: wait-interpolation debug: start +[ERROR] [1732710079.549673383]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732710079.549710607]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732710079.551151063]: wait-interpolation debug: end +[ INFO] [1732710080.283121047]: wait-interpolation debug: start +[ERROR] [1732710081.886300130]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732710081.886338000]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732710081.891692924]: wait-interpolation debug: end +[ INFO] [1732710087.935873434]: wait-interpolation debug: start +[ INFO] [1732710087.937816708]: wait-interpolation debug: end +[ INFO] [1732710087.940043162]: start waiting for call + +[ INFO] [1732710088.055433662]: wait for voice command ... +[ INFO] [1732710088.155439014]: wait for voice command ... +[ INFO] [1732710088.255471922]: wait for voice command ... +[ INFO] [1732710088.355435608]: wait for voice command ... +[ INFO] [1732710088.455466810]: wait for voice command ... +[ INFO] [1732710088.555461508]: wait for voice command ... +[ INFO] [1732710088.655456191]: wait for voice command ... +[ INFO] [1732710088.755420904]: wait for voice command ... +[ INFO] [1732710088.855418076]: wait for voice command ... +[ INFO] [1732710088.955456842]: wait for voice command ... +[ INFO] [1732710089.055439653]: wait for voice command ... +[ INFO] [1732710089.155416381]: wait for voice command ... +[ INFO] [1732710089.255460242]: wait for voice command ... +[ INFO] [1732710089.355457108]: wait for voice command ... +[ INFO] [1732710089.455544201]: wait for voice command ... +[ INFO] [1732710089.555501519]: wait for voice command ... +[ INFO] [1732710089.655459623]: wait for voice command ... +[ INFO] [1732710089.755458459]: wait for voice command ... +[ INFO] [1732710089.855427044]: wait for voice command ... +[ INFO] [1732710089.955459450]: wait for voice command ... +[ INFO] [1732710090.055433568]: wait for voice command ... +[ INFO] [1732710090.155455207]: wait for voice command ... +[ INFO] [1732710090.255460665]: wait for voice command ... +[ INFO] [1732710090.355612316]: wait for voice command ... +[ INFO] [1732710090.455456790]: wait for voice command ... +[ INFO] [1732710090.555465835]: wait for voice command ... +[ INFO] [1732710090.655421949]: wait for voice command ... +[ INFO] [1732710090.755422108]: wait for voice command ... +[ INFO] [1732710090.855457537]: wait for voice command ... +[ INFO] [1732710090.955459806]: wait for voice command ... +[ INFO] [1732710091.055399352]: wait for voice command ... +[ INFO] [1732710091.155420139]: wait for voice command ... +[ INFO] [1732710091.255440997]: wait for voice command ... +[ INFO] [1732710091.355464307]: wait for voice command ... +[ INFO] [1732710091.455463271]: wait for voice command ... +[ INFO] [1732710091.555433513]: wait for voice command ... +[ INFO] [1732710091.655426660]: wait for voice command ... +[ INFO] [1732710091.755457243]: wait for voice command ... +[ INFO] [1732710091.855528649]: wait for voice command ... +[ INFO] [1732710091.955473599]: wait for voice command ... +[ INFO] [1732710092.055470503]: wait for voice command ... +[ INFO] [1732710092.155467832]: wait for voice command ... +[ INFO] [1732710092.255471199]: wait for voice command ... +[ INFO] [1732710092.355463710]: wait for voice command ... +[ INFO] [1732710092.455420306]: wait for voice command ... +[ INFO] [1732710092.555414812]: wait for voice command ... +[ INFO] [1732710092.655435161]: wait for voice command ... +[ INFO] [1732710092.755416719]: wait for voice command ... +[ INFO] [1732710092.855434491]: wait for voice command ... +[ INFO] [1732710092.955454800]: wait for voice command ... +[ INFO] [1732710093.055442249]: wait for voice command ... +[ INFO] [1732710093.155476061]: wait for voice command ... +[ INFO] [1732710093.255455352]: wait for voice command ... +[ INFO] [1732710093.355431856]: wait for voice command ... +[ INFO] [1732710093.455459392]: wait for voice command ... +[ INFO] [1732710093.555418430]: wait for voice command ... +[ INFO] [1732710093.655490642]: wait for voice command ... +[ INFO] [1732710093.755420206]: wait for voice command ... +[ INFO] [1732710093.855510940]: wait for voice command ... +[ INFO] [1732710093.955425809]: wait for voice command ... +[ INFO] [1732710094.055431281]: wait for voice command ... +[ INFO] [1732710094.155635621]: wait for voice command ... +[ INFO] [1732710094.255453702]: wait for voice command ... +[ INFO] [1732710094.355440726]: wait for voice command ... +[ INFO] [1732710094.455436616]: wait for voice command ... +[ INFO] [1732710094.555438439]: wait for voice command ... +[ INFO] [1732710094.655425480]: wait for voice command ... +[ INFO] [1732710094.755454486]: wait for voice command ... +[ INFO] [1732710094.855416520]: wait for voice command ... +[ INFO] [1732710094.955453325]: wait for voice command ... +[ INFO] [1732710095.055537945]: wait for voice command ... +[ INFO] [1732710095.155455730]: wait for voice command ... +[ INFO] [1732710095.255476561]: wait for voice command ... +[ INFO] [1732710095.355451586]: wait for voice command ... +[ INFO] [1732710095.455477638]: wait for voice command ... +[ INFO] [1732710095.555456067]: wait for voice command ... +[ INFO] [1732710095.655461403]: wait for voice command ... +[ INFO] [1732710095.755452434]: wait for voice command ... +[ INFO] [1732710095.855414776]: wait for voice command ... +[ INFO] [1732710095.955455264]: wait for voice command ... +[ INFO] [1732710096.055414911]: wait for voice command ... +[ INFO] [1732710096.155427932]: wait for voice command ... +[ INFO] [1732710096.255429844]: wait for voice command ... +[ INFO] [1732710096.355427200]: wait for voice command ... +[ INFO] [1732710096.455425206]: wait for voice command ... +[ INFO] [1732710096.555495278]: wait for voice command ... +[ INFO] [1732710096.655457709]: wait for voice command ... +[ INFO] [1732710096.755467503]: wait for voice command ... +[ INFO] [1732710096.855463651]: wait for voice command ... +[ INFO] [1732710096.955456896]: wait for voice command ... +[ INFO] [1732710097.055470111]: wait for voice command ... +[ INFO] [1732710097.155457435]: wait for voice command ... +[ INFO] [1732710097.255466782]: wait for voice command ... +[ INFO] [1732710097.355458193]: wait for voice command ... +[ INFO] [1732710097.455459936]: wait for voice command ... +[ INFO] [1732710097.555431695]: wait for voice command ... +[ INFO] [1732710097.655421303]: wait for voice command ... +[ INFO] [1732710097.755418506]: wait for voice command ... +[ INFO] [1732710097.855463496]: wait for voice command ... +[ INFO] [1732710097.955456037]: wait for voice command ... +[ INFO] [1732710098.055535403]: wait for voice command ... +[ INFO] [1732710098.155451155]: wait for voice command ... +[ INFO] [1732710098.255452080]: wait for voice command ... +[ INFO] [1732710098.355453727]: wait for voice command ... +[ INFO] [1732710098.455416927]: wait for voice command ... +[ INFO] [1732710098.555421072]: wait for voice command ... +[ INFO] [1732710098.655487473]: wait for voice command ... +[ INFO] [1732710098.755435399]: wait for voice command ... +[ INFO] [1732710098.855566604]: wait for voice command ... +[ INFO] [1732710098.955414298]: wait for voice command ... +[ INFO] [1732710099.055442361]: wait for voice command ... +[ INFO] [1732710099.155469515]: wait for voice command ... +[ INFO] [1732710099.255464753]: wait for voice command ... +[ INFO] [1732710099.355457112]: wait for voice command ... +[ INFO] [1732710099.455476628]: wait for voice command ... +[ INFO] [1732710099.555469985]: wait for voice command ... +[ INFO] [1732710099.655458797]: wait for voice command ... +[ INFO] [1732710099.755427484]: wait for voice command ... +[ INFO] [1732710099.855420359]: wait for voice command ... +[ INFO] [1732710099.955458763]: wait for voice command ... +[ INFO] [1732710100.055427310]: wait for voice command ... +[ INFO] [1732710100.155424947]: wait for voice command ... +[ INFO] [1732710100.255470493]: wait for voice command ... +[ INFO] [1732710100.355420042]: wait for voice command ... +[ INFO] [1732710100.455453396]: wait for voice command ... +[ INFO] [1732710100.555461869]: wait for voice command ... +[ INFO] [1732710100.655412775]: wait for voice command ... +[ INFO] [1732710100.755458284]: wait for voice command ... +[ INFO] [1732710100.855452331]: wait for voice command ... +[ INFO] [1732710100.955456688]: wait for voice command ... +[ INFO] [1732710101.055465097]: wait for voice command ... +[ INFO] [1732710101.155434477]: wait for voice command ... +[ INFO] [1732710101.255454930]: wait for voice command ... +[ INFO] [1732710101.355460263]: wait for voice command ... +[ INFO] [1732710101.455471074]: wait for voice command ... +[ INFO] [1732710101.555468704]: wait for voice command ... +[ INFO] [1732710101.655535766]: wait for voice command ... +[ INFO] [1732710101.755459445]: wait for voice command ... +[ INFO] [1732710101.855504131]: wait for voice command ... +[ INFO] [1732710101.955455439]: wait for voice command ... +[ INFO] [1732710102.055456176]: wait for voice command ... +[ INFO] [1732710102.155456116]: wait for voice command ... +[ INFO] [1732710102.255458618]: wait for voice command ... +[ INFO] [1732710102.355462668]: wait for voice command ... +[ INFO] [1732710102.455466930]: wait for voice command ... +[ INFO] [1732710102.555469710]: wait for voice command ... +[ INFO] [1732710102.655437314]: wait for voice command ... +[ INFO] [1732710102.755471592]: wait for voice command ... +[ INFO] [1732710102.855472870]: wait for voice command ... +[ INFO] [1732710102.955435912]: wait for voice command ... +[ INFO] [1732710103.055453352]: wait for voice command ... +[ INFO] [1732710103.155464623]: wait for voice command ... +[ INFO] [1732710103.255456634]: wait for voice command ... +[ INFO] [1732710103.355467574]: wait for voice command ... +[ INFO] [1732710103.455450995]: wait for voice command ... +[ INFO] [1732710103.555498584]: wait for voice command ... +[ INFO] [1732710103.655424693]: wait for voice command ... +[ INFO] [1732710103.755455675]: wait for voice command ... +[ INFO] [1732710103.855478053]: wait for voice command ... +[ INFO] [1732710103.955464121]: wait for voice command ... +[ INFO] [1732710104.055467754]: wait for voice command ... +[ INFO] [1732710104.155454544]: wait for voice command ... +[ INFO] [1732710104.255428900]: wait for voice command ... +[ INFO] [1732710104.355468582]: wait for voice command ... +[ INFO] [1732710104.455422428]: wait for voice command ... +[ INFO] [1732710104.555460446]: wait for voice command ... +[ INFO] [1732710104.655453236]: wait for voice command ... +[ INFO] [1732710104.755432677]: wait for voice command ... +[ INFO] [1732710104.855471919]: wait for voice command ... +[ INFO] [1732710104.955462598]: wait for voice command ... +[ INFO] [1732710105.055459830]: wait for voice command ... +[ INFO] [1732710105.155436274]: wait for voice command ... +[ INFO] [1732710105.255459815]: wait for voice command ... +[ INFO] [1732710105.355460911]: wait for voice command ... +[ INFO] [1732710105.455441277]: wait for voice command ... +[ INFO] [1732710105.555447911]: wait for voice command ... +[ INFO] [1732710105.655438216]: wait for voice command ... +[ INFO] [1732710105.755436700]: wait for voice command ... +[ INFO] [1732710105.855429763]: wait for voice command ... +[ INFO] [1732710105.955442970]: wait for voice command ... +[ INFO] [1732710106.055502275]: wait for voice command ... +[ INFO] [1732710106.155433320]: wait for voice command ... +[ INFO] [1732710106.255437662]: wait for voice command ... +[ INFO] [1732710106.355480371]: wait for voice command ... +[ INFO] [1732710106.455483511]: wait for voice command ... +[ INFO] [1732710106.555475643]: wait for voice command ... +[ INFO] [1732710106.655425606]: wait for voice command ... +[ INFO] [1732710106.755449338]: wait for voice command ... +[ INFO] [1732710106.855456261]: wait for voice command ... +[ INFO] [1732710106.955425703]: wait for voice command ... +[ INFO] [1732710107.055425851]: wait for voice command ... +[ INFO] [1732710107.155446181]: wait for voice command ... +[ INFO] [1732710107.255470888]: wait for voice command ... +[ INFO] [1732710107.355465414]: wait for voice command ... +[ INFO] [1732710107.455463685]: wait for voice command ... +[ INFO] [1732710107.555426477]: wait for voice command ... +[ INFO] [1732710107.655459854]: wait for voice command ... +[ INFO] [1732710107.755470056]: wait for voice command ... +[ INFO] [1732710107.855469029]: wait for voice command ... +[ INFO] [1732710107.955469184]: wait for voice command ... +[ INFO] [1732710108.055426480]: wait for voice command ... +[ INFO] [1732710108.155418218]: wait for voice command ... +[ INFO] [1732710108.255472338]: wait for voice command ... +[ INFO] [1732710108.355427053]: wait for voice command ... +[ INFO] [1732710108.455457403]: wait for voice command ... +[ INFO] [1732710108.555538121]: wait for voice command ... +[ INFO] [1732710108.655480381]: wait for voice command ... +[ INFO] [1732710108.755490425]: wait for voice command ... +[ INFO] [1732710108.855452629]: wait for voice command ... +[ INFO] [1732710108.955428027]: wait for voice command ... +[ INFO] [1732710109.055556250]: wait for voice command ... +[ INFO] [1732710109.155500120]: wait for voice command ... +[ INFO] [1732710109.255558721]: wait for voice command ... +[ INFO] [1732710109.355534218]: wait for voice command ... +[ INFO] [1732710109.455544850]: wait for voice command ... +[ INFO] [1732710109.555470364]: wait for voice command ... +[ INFO] [1732710109.655543005]: wait for voice command ... +[ INFO] [1732710109.755510224]: wait for voice command ... +[ INFO] [1732710109.855539809]: wait for voice command ... +[ INFO] [1732710109.955636841]: wait for voice command ... +[ INFO] [1732710110.055546580]: wait for voice command ... +[ INFO] [1732710110.155554515]: wait for voice command ... +[ INFO] [1732710110.255495686]: wait for voice command ... +[ INFO] [1732710110.355520819]: wait for voice command ... +[ INFO] [1732710110.455493768]: wait for voice command ... +[ INFO] [1732710110.555517957]: wait for voice command ... +[ INFO] [1732710110.655511176]: wait for voice command ... +[ INFO] [1732710110.755519301]: wait for voice command ... +[ INFO] [1732710110.855490613]: wait for voice command ... +[ INFO] [1732710110.955546695]: wait for voice command ... +[ INFO] [1732710111.055541884]: wait for voice command ... +[ INFO] [1732710111.155660633]: wait for voice command ... +[ INFO] [1732710111.255508415]: wait for voice command ... +[ INFO] [1732710111.355521502]: wait for voice command ... +[ INFO] [1732710111.455523574]: wait for voice command ... +[ INFO] [1732710111.555576437]: wait for voice command ... +[ INFO] [1732710111.655560235]: wait for voice command ... +[ INFO] [1732710111.755579453]: wait for voice command ... +[ INFO] [1732710111.855597344]: wait for voice command ... +[ INFO] [1732710111.955521924]: wait for voice command ... +[ INFO] [1732710112.055551066]: wait for voice command ... +[ INFO] [1732710112.155569964]: wait for voice command ... +[ INFO] [1732710112.255509648]: wait for voice command ... +[ INFO] [1732710112.355496819]: wait for voice command ... +[ INFO] [1732710112.455803607]: wait for voice command ... +[ INFO] [1732710112.555554449]: wait for voice command ... +[ INFO] [1732710112.655509094]: wait for voice command ... +[ INFO] [1732710112.755584139]: wait for voice command ... +[ INFO] [1732710112.855577918]: wait for voice command ... +[ INFO] [1732710112.955509147]: wait for voice command ... +[ INFO] [1732710113.055520113]: wait for voice command ... +[ INFO] [1732710113.155512556]: wait for voice command ... +[ INFO] [1732710113.255531089]: wait for voice command ... +[ INFO] [1732710113.355481473]: wait for voice command ... +[ INFO] [1732710113.455540015]: wait for voice command ... +[ INFO] [1732710113.555556020]: wait for voice command ... +[ INFO] [1732710113.655474902]: wait for voice command ... +[ INFO] [1732710113.755546434]: wait for voice command ... +[ INFO] [1732710113.855647023]: wait for voice command ... +[ INFO] [1732710113.955551595]: wait for voice command ... +[ INFO] [1732710114.055497023]: wait for voice command ... +[ INFO] [1732710114.155507326]: wait for voice command ... +[ INFO] [1732710114.255476095]: wait for voice command ... +[ INFO] [1732710114.355544493]: wait for voice command ... +[ INFO] [1732710114.455550332]: wait for voice command ... +[ INFO] [1732710114.555495470]: wait for voice command ... +[ INFO] [1732710114.655452262]: wait for voice command ... +[ INFO] [1732710114.755524016]: wait for voice command ... +[ INFO] [1732710114.855647705]: wait for voice command ... +[ INFO] [1732710114.955564254]: wait for voice command ... +[ INFO] [1732710115.055528227]: wait for voice command ... +[ INFO] [1732710115.155576226]: wait for voice command ... +[ INFO] [1732710115.255495107]: wait for voice command ... +[ INFO] [1732710115.355536597]: wait for voice command ... +[ INFO] [1732710115.455480200]: wait for voice command ... +[ INFO] [1732710115.555595470]: wait for voice command ... +[ INFO] [1732710115.655515394]: wait for voice command ... +[ INFO] [1732710115.755494417]: wait for voice command ... +[ INFO] [1732710115.855595187]: wait for voice command ... +[ INFO] [1732710115.955559047]: wait for voice command ... +[ INFO] [1732710116.055551453]: wait for voice command ... +[ INFO] [1732710116.155566787]: wait for voice command ... +[ INFO] [1732710116.255530433]: wait for voice command ... +[ INFO] [1732710116.355544123]: wait for voice command ... +[ INFO] [1732710116.455549022]: wait for voice command ... +[ INFO] [1732710116.555491493]: wait for voice command ... +[ INFO] [1732710116.655551461]: wait for voice command ... +[ INFO] [1732710116.755867308]: wait for voice command ... +[ INFO] [1732710116.855650168]: wait for voice command ... +[ INFO] [1732710116.955549168]: wait for voice command ... +[ INFO] [1732710117.055511462]: wait for voice command ... +[ INFO] [1732710117.155543701]: wait for voice command ... +[ INFO] [1732710117.255541068]: wait for voice command ... +[ INFO] [1732710117.355493590]: wait for voice command ... +[ INFO] [1732710117.455523296]: wait for voice command ... +[ INFO] [1732710117.555493972]: wait for voice command ... +[ INFO] [1732710117.655450522]: wait for voice command ... +[ INFO] [1732710117.755436635]: wait for voice command ... +[ INFO] [1732710117.855417888]: wait for voice command ... +[ INFO] [1732710117.955449292]: wait for voice command ... +[ INFO] [1732710118.055414412]: wait for voice command ... +[ INFO] [1732710118.155433685]: wait for voice command ... +[ INFO] [1732710118.255458414]: wait for voice command ... +[ INFO] [1732710118.355416710]: wait for voice command ... +[ INFO] [1732710118.455459706]: wait for voice command ... +[ INFO] [1732710118.555459819]: wait for voice command ... +[ INFO] [1732710118.655456797]: wait for voice command ... +[ INFO] [1732710118.755425735]: wait for voice command ... +[ INFO] [1732710118.855501043]: wait for voice command ... +[ INFO] [1732710118.955423645]: wait for voice command ... +[ INFO] [1732710119.055455255]: wait for voice command ... +[ INFO] [1732710119.155423291]: wait for voice command ... +[ INFO] [1732710119.255426173]: wait for voice command ... +[ INFO] [1732710119.355454331]: wait for voice command ... +[ INFO] [1732710119.455456999]: wait for voice command ... +[ INFO] [1732710119.555427955]: wait for voice command ... +[ INFO] [1732710119.655462259]: wait for voice command ... +[ INFO] [1732710119.755487407]: wait for voice command ... +[ INFO] [1732710119.855451927]: wait for voice command ... +[ INFO] [1732710119.955461064]: wait for voice command ... +[ INFO] [1732710120.055473996]: wait for voice command ... +[ INFO] [1732710120.155454366]: wait for voice command ... +[ INFO] [1732710120.255452549]: wait for voice command ... +[ INFO] [1732710120.355443034]: wait for voice command ... +[ INFO] [1732710120.455457771]: wait for voice command ... +[ INFO] [1732710120.555454932]: wait for voice command ... +[ INFO] [1732710120.655432212]: wait for voice command ... +[ INFO] [1732710120.755423848]: wait for voice command ... +[ INFO] [1732710120.855423147]: wait for voice command ... +"め" +[ INFO] [1732710120.955439336]: wait for voice command ... +[ INFO] [1732710121.055424779]: wait for voice command ... +[ INFO] [1732710121.155462864]: wait for voice command ... +[ INFO] [1732710121.255415456]: wait for voice command ... +[ INFO] [1732710121.355422550]: wait for voice command ... +[ INFO] [1732710121.455419314]: wait for voice command ... +[ INFO] [1732710121.555422052]: wait for voice command ... +[ INFO] [1732710121.655425992]: wait for voice command ... +[ INFO] [1732710121.755420706]: wait for voice command ... +[ INFO] [1732710121.855497584]: wait for voice command ... +[ INFO] [1732710121.955456886]: wait for voice command ... +[ INFO] [1732710122.055470847]: wait for voice command ... +[ INFO] [1732710122.155459468]: wait for voice command ... +[ INFO] [1732710122.255476077]: wait for voice command ... +[ INFO] [1732710122.355464542]: wait for voice command ... +[ INFO] [1732710122.455457629]: wait for voice command ... +[ INFO] [1732710122.555477188]: wait for voice command ... +[ INFO] [1732710122.655468867]: wait for voice command ... +[ INFO] [1732710122.755386197]: wait for voice command ... +[ INFO] [1732710122.855386820]: wait for voice command ... +[ INFO] [1732710122.955431952]: wait for voice command ... +[ INFO] [1732710123.055429688]: wait for voice command ... +[ INFO] [1732710123.155430322]: wait for voice command ... +[ INFO] [1732710123.255432009]: wait for voice command ... +[ INFO] [1732710123.355422572]: wait for voice command ... +[ INFO] [1732710123.455611201]: wait for voice command ... +[ INFO] [1732710123.555487667]: wait for voice command ... +[ INFO] [1732710123.655553429]: wait for voice command ... +[ INFO] [1732710123.755530120]: wait for voice command ... +[ INFO] [1732710123.855527602]: wait for voice command ... +[ INFO] [1732710123.955515567]: wait for voice command ... +[ INFO] [1732710124.055532400]: wait for voice command ... +[ INFO] [1732710124.155553731]: wait for voice command ... +[ INFO] [1732710124.255595417]: wait for voice command ... +[ INFO] [1732710124.355617840]: wait for voice command ... +[ INFO] [1732710124.455657851]: wait for voice command ... +[ INFO] [1732710124.555534071]: wait for voice command ... +[ INFO] [1732710124.655421748]: wait for voice command ... +[ INFO] [1732710124.755596153]: wait for voice command ... +[ INFO] [1732710124.855534975]: wait for voice command ... +[ INFO] [1732710124.955532940]: wait for voice command ... +[ INFO] [1732710125.055530879]: wait for voice command ... +[ INFO] [1732710125.155516303]: wait for voice command ... +[ INFO] [1732710125.255524795]: wait for voice command ... +[ INFO] [1732710125.355474715]: wait for voice command ... +[ INFO] [1732710125.455548335]: wait for voice command ... +[ INFO] [1732710125.555534293]: wait for voice command ... +[ INFO] [1732710125.655576461]: wait for voice command ... +[ INFO] [1732710125.755537357]: wait for voice command ... +[ INFO] [1732710125.855522161]: wait for voice command ... +[ INFO] [1732710125.955521044]: wait for voice command ... +[ INFO] [1732710126.055524695]: wait for voice command ... +[ INFO] [1732710126.155507594]: wait for voice command ... +[ INFO] [1732710126.255510099]: wait for voice command ... +[ INFO] [1732710126.355555342]: wait for voice command ... +[ INFO] [1732710126.455523644]: wait for voice command ... +[ INFO] [1732710126.555487451]: wait for voice command ... +[ INFO] [1732710126.655494182]: wait for voice command ... +[ INFO] [1732710126.755449196]: wait for voice command ... +[ INFO] [1732710126.855525460]: wait for voice command ... +[ INFO] [1732710126.955517971]: wait for voice command ... +[ INFO] [1732710127.055515466]: wait for voice command ... +[ INFO] [1732710127.155485859]: wait for voice command ... +[ INFO] [1732710127.255504899]: wait for voice command ... +[ INFO] [1732710127.355525500]: wait for voice command ... +[ INFO] [1732710127.455553448]: wait for voice command ... +"め" +[ INFO] [1732710127.555500692]: wait for voice command ... +[ INFO] [1732710127.655507787]: wait for voice command ... +[ INFO] [1732710127.755501348]: wait for voice command ... +[ INFO] [1732710127.855567685]: wait for voice command ... +[ INFO] [1732710127.955559198]: wait for voice command ... +[ INFO] [1732710128.055554605]: wait for voice command ... +[ INFO] [1732710128.155511800]: wait for voice command ... +[ INFO] [1732710128.255446414]: wait for voice command ... +[ INFO] [1732710128.355489886]: wait for voice command ... +[ INFO] [1732710128.455456598]: wait for voice command ... +[ INFO] [1732710128.555520840]: wait for voice command ... +[ INFO] [1732710128.655479898]: wait for voice command ... +[ INFO] [1732710128.755521499]: wait for voice command ... +[ INFO] [1732710128.855514179]: wait for voice command ... +[ INFO] [1732710128.955512663]: wait for voice command ... +[ INFO] [1732710129.055679649]: wait for voice command ... +[ INFO] [1732710129.155498220]: wait for voice command ... +[ INFO] [1732710129.255552682]: wait for voice command ... +[ INFO] [1732710129.355434314]: wait for voice command ... +[ INFO] [1732710129.455622416]: wait for voice command ... +[ INFO] [1732710129.555502691]: wait for voice command ... +[ INFO] [1732710129.655555224]: wait for voice command ... +[ INFO] [1732710129.755448294]: wait for voice command ... +[ INFO] [1732710129.855480960]: wait for voice command ... +[ INFO] [1732710129.955495323]: wait for voice command ... +[ INFO] [1732710130.055498244]: wait for voice command ... +[ INFO] [1732710130.155457279]: wait for voice command ... +[ INFO] [1732710130.255515916]: wait for voice command ... +[ INFO] [1732710130.355489048]: wait for voice command ... +[ INFO] [1732710130.455516887]: wait for voice command ... +[ INFO] [1732710130.555500163]: wait for voice command ... +[ INFO] [1732710130.655570468]: wait for voice command ... +[ INFO] [1732710130.755590992]: wait for voice command ... +[ INFO] [1732710130.855602927]: wait for voice command ... +[ INFO] [1732710130.955549106]: wait for voice command ... +[ INFO] [1732710131.055565864]: wait for voice command ... +[ INFO] [1732710131.155499016]: wait for voice command ... +[ INFO] [1732710131.255522925]: wait for voice command ... +[ INFO] [1732710131.355540280]: wait for voice command ... +[ INFO] [1732710131.455437516]: wait for voice command ... +[ INFO] [1732710131.555493158]: wait for voice command ... +[ INFO] [1732710131.655466485]: wait for voice command ... +[ INFO] [1732710131.755484290]: wait for voice command ... +[ INFO] [1732710131.855516598]: wait for voice command ... +[ INFO] [1732710131.955483321]: wait for voice command ... +[ INFO] [1732710132.055473860]: wait for voice command ... +[ INFO] [1732710132.155545513]: wait for voice command ... +[ INFO] [1732710132.255452649]: wait for voice command ... +[ INFO] [1732710132.355497768]: wait for voice command ... +[ INFO] [1732710132.455518944]: wait for voice command ... +[ INFO] [1732710132.555532520]: wait for voice command ... +[ INFO] [1732710132.655560242]: wait for voice command ... +[ INFO] [1732710132.755499731]: wait for voice command ... +[ INFO] [1732710132.855517232]: wait for voice command ... +[ INFO] [1732710132.955476172]: wait for voice command ... +[ INFO] [1732710133.055495915]: wait for voice command ... +[ INFO] [1732710133.155548285]: wait for voice command ... +[ INFO] [1732710133.255517830]: wait for voice command ... +[ INFO] [1732710133.355514340]: wait for voice command ... +[ INFO] [1732710133.455539150]: wait for voice command ... +[ INFO] [1732710133.555553961]: wait for voice command ... +[ INFO] [1732710133.655546590]: wait for voice command ... +[ INFO] [1732710133.755504957]: wait for voice command ... +[ INFO] [1732710133.855589652]: wait for voice command ... +[ INFO] [1732710133.955477179]: wait for voice command ... +[ INFO] [1732710134.055449964]: wait for voice command ... +[ INFO] [1732710134.155537053]: wait for voice command ... +[ INFO] [1732710134.255540419]: wait for voice command ... +[ INFO] [1732710134.355493899]: wait for voice command ... +[ INFO] [1732710134.455448386]: wait for voice command ... +[ INFO] [1732710134.555584786]: wait for voice command ... +[ INFO] [1732710134.655443955]: wait for voice command ... +[ INFO] [1732710134.755496104]: wait for voice command ... +[ INFO] [1732710134.855558070]: wait for voice command ... +[ INFO] [1732710134.955490961]: wait for voice command ... +[ INFO] [1732710135.055456736]: wait for voice command ... +[ INFO] [1732710135.155527977]: wait for voice command ... +[ INFO] [1732710135.255588049]: wait for voice command ... +[ INFO] [1732710135.355574558]: wait for voice command ... +[ INFO] [1732710135.455541084]: wait for voice command ... +[ INFO] [1732710135.555605464]: wait for voice command ... +[ INFO] [1732710135.655473738]: wait for voice command ... +[ INFO] [1732710135.755514245]: wait for voice command ... +[ INFO] [1732710135.855527999]: wait for voice command ... +[ INFO] [1732710135.955518291]: wait for voice command ... +[ INFO] [1732710136.055513276]: wait for voice command ... +[ INFO] [1732710136.155470980]: wait for voice command ... +[ INFO] [1732710136.255432250]: wait for voice command ... +[ INFO] [1732710136.355519895]: wait for voice command ... +[ INFO] [1732710136.455501936]: wait for voice command ... +[ INFO] [1732710136.555574204]: wait for voice command ... +[ INFO] [1732710136.655554686]: wait for voice command ... +[ INFO] [1732710136.755541674]: wait for voice command ... +[ INFO] [1732710136.855496480]: wait for voice command ... +[ INFO] [1732710136.955442064]: wait for voice command ... +[ INFO] [1732710137.055552107]: wait for voice command ... +[ INFO] [1732710137.155433780]: wait for voice command ... +[ INFO] [1732710137.255427431]: wait for voice command ... +[ INFO] [1732710137.355415574]: wait for voice command ... +[ INFO] [1732710137.455426212]: wait for voice command ... +[ INFO] [1732710137.555551198]: wait for voice command ... +[ INFO] [1732710137.655489809]: wait for voice command ... +[ INFO] [1732710137.755535265]: wait for voice command ... +[ INFO] [1732710137.855536341]: wait for voice command ... +[ INFO] [1732710137.955505314]: wait for voice command ... +[ INFO] [1732710138.055528443]: wait for voice command ... +[ INFO] [1732710138.155455603]: wait for voice command ... +[ INFO] [1732710138.255514980]: wait for voice command ... +[ INFO] [1732710138.355523939]: wait for voice command ... +[ INFO] [1732710138.455418182]: wait for voice command ... +[ INFO] [1732710138.555415304]: wait for voice command ... +[ INFO] [1732710138.655495461]: wait for voice command ... +[ INFO] [1732710138.755452779]: wait for voice command ... +[ INFO] [1732710138.855430974]: wait for voice command ... +[ INFO] [1732710138.955458207]: wait for voice command ... +[ INFO] [1732710139.055458862]: wait for voice command ... +[ INFO] [1732710139.155468951]: wait for voice command ... +[ INFO] [1732710139.255427603]: wait for voice command ... +[ INFO] [1732710139.355439081]: wait for voice command ... +[ INFO] [1732710139.455423737]: wait for voice command ... +[ INFO] [1732710139.555428299]: wait for voice command ... +[ INFO] [1732710139.655423187]: wait for voice command ... +[ INFO] [1732710139.755423796]: wait for voice command ... +[ INFO] [1732710139.855460551]: wait for voice command ... +[ INFO] [1732710139.955433134]: wait for voice command ... +[ INFO] [1732710140.055464646]: wait for voice command ... +[ INFO] [1732710140.155460431]: wait for voice command ... +[ INFO] [1732710140.255434566]: wait for voice command ... +[ INFO] [1732710140.355461526]: wait for voice command ... +[ INFO] [1732710140.455454673]: wait for voice command ... +[ INFO] [1732710140.555459002]: wait for voice command ... +[ INFO] [1732710140.655457446]: wait for voice command ... +[ INFO] [1732710140.755427940]: wait for voice command ... +[ INFO] [1732710140.855471200]: wait for voice command ... +[ INFO] [1732710140.955458481]: wait for voice command ... +[ INFO] [1732710141.055454411]: wait for voice command ... +[ INFO] [1732710141.155432191]: wait for voice command ... +[ INFO] [1732710141.255462527]: wait for voice command ... +[ INFO] [1732710141.355515817]: wait for voice command ... +[ INFO] [1732710141.455421504]: wait for voice command ... +[ INFO] [1732710141.555427508]: wait for voice command ... +[ INFO] [1732710141.655438835]: wait for voice command ... +[ INFO] [1732710141.755443318]: wait for voice command ... +[ INFO] [1732710141.855431300]: wait for voice command ... +[ INFO] [1732710141.955422476]: wait for voice command ... +[ INFO] [1732710142.055428846]: wait for voice command ... +[ INFO] [1732710142.155499166]: wait for voice command ... +[ INFO] [1732710142.255427779]: wait for voice command ... +[ INFO] [1732710142.355433033]: wait for voice command ... +[ INFO] [1732710142.455419182]: wait for voice command ... +[ INFO] [1732710142.555438701]: wait for voice command ... +[ INFO] [1732710142.655432414]: wait for voice command ... +[ INFO] [1732710142.755460010]: wait for voice command ... +[ INFO] [1732710142.855450942]: wait for voice command ... +[ INFO] [1732710142.955431662]: wait for voice command ... +[ INFO] [1732710143.055435398]: wait for voice command ... +[ INFO] [1732710143.155420732]: wait for voice command ... +[ INFO] [1732710143.255496917]: wait for voice command ... +[ INFO] [1732710143.355454027]: wait for voice command ... +[ INFO] [1732710143.455456292]: wait for voice command ... +[ INFO] [1732710143.555422370]: wait for voice command ... +[ INFO] [1732710143.655457358]: wait for voice command ... +[ INFO] [1732710143.755636244]: wait for voice command ... +[ INFO] [1732710143.855477623]: wait for voice command ... +[ INFO] [1732710143.955421715]: wait for voice command ... +[ INFO] [1732710144.055493975]: wait for voice command ... +[ INFO] [1732710144.155462749]: wait for voice command ... +[ INFO] [1732710144.255454239]: wait for voice command ... +[ INFO] [1732710144.355464108]: wait for voice command ... +[ INFO] [1732710144.455457338]: wait for voice command ... +[ INFO] [1732710144.555458230]: wait for voice command ... +[ INFO] [1732710144.655491953]: wait for voice command ... +[ INFO] [1732710144.755424223]: wait for voice command ... +[ INFO] [1732710144.855459803]: wait for voice command ... +[ INFO] [1732710144.955502554]: wait for voice command ... +[ INFO] [1732710145.055468223]: wait for voice command ... +[ INFO] [1732710145.155459039]: wait for voice command ... +[ INFO] [1732710145.255427066]: wait for voice command ... +[ INFO] [1732710145.355433092]: wait for voice command ... +[ INFO] [1732710145.455575812]: wait for voice command ... +[ INFO] [1732710145.555462695]: wait for voice command ... +[ INFO] [1732710145.655462316]: wait for voice command ... +[ INFO] [1732710145.755410339]: wait for voice command ... +[ INFO] [1732710145.855422153]: wait for voice command ... +[ INFO] [1732710145.955455025]: wait for voice command ... +[ INFO] [1732710146.055418173]: wait for voice command ... +[ INFO] [1732710146.155462732]: wait for voice command ... +[ INFO] [1732710146.255657891]: wait for voice command ... +[ INFO] [1732710146.355501596]: wait for voice command ... +[ INFO] [1732710146.455461427]: wait for voice command ... +[ INFO] [1732710146.555453129]: wait for voice command ... +[ INFO] [1732710146.655430300]: wait for voice command ... +[ INFO] [1732710146.755435316]: wait for voice command ... +[ INFO] [1732710146.855462046]: wait for voice command ... +[ INFO] [1732710146.955424703]: wait for voice command ... +[ INFO] [1732710147.055419151]: wait for voice command ... +[ INFO] [1732710147.155431187]: wait for voice command ... +[ INFO] [1732710147.255425373]: wait for voice command ... +[ INFO] [1732710147.355421192]: wait for voice command ... +[ INFO] [1732710147.455421554]: wait for voice command ... +[ INFO] [1732710147.555458987]: wait for voice command ... +[ INFO] [1732710147.655419552]: wait for voice command ... +[ INFO] [1732710147.755463784]: wait for voice command ... +[ INFO] [1732710147.855448106]: wait for voice command ... +[ INFO] [1732710147.955584420]: wait for voice command ... +[ INFO] [1732710148.055462115]: wait for voice command ... +[ INFO] [1732710148.155426588]: wait for voice command ... +[ INFO] [1732710148.255464785]: wait for voice command ... +[ INFO] [1732710148.355423272]: wait for voice command ... +[ INFO] [1732710148.455457798]: wait for voice command ... +[ INFO] [1732710148.555457494]: wait for voice command ... +[ INFO] [1732710148.655462691]: wait for voice command ... +[ INFO] [1732710148.755573562]: wait for voice command ... +[ INFO] [1732710148.855462720]: wait for voice command ... +[ INFO] [1732710148.955454595]: wait for voice command ... +[ INFO] [1732710149.055423499]: wait for voice command ... +[ INFO] [1732710149.155428456]: wait for voice command ... +[ INFO] [1732710149.255425716]: wait for voice command ... +[ INFO] [1732710149.355424165]: wait for voice command ... +[ INFO] [1732710149.455422125]: wait for voice command ... +[ INFO] [1732710149.555429677]: wait for voice command ... +[ INFO] [1732710149.655422589]: wait for voice command ... +[ INFO] [1732710149.755432060]: wait for voice command ... +[ INFO] [1732710149.855421243]: wait for voice command ... +[ INFO] [1732710149.955428716]: wait for voice command ... +[ INFO] [1732710150.055437966]: wait for voice command ... +[ INFO] [1732710150.155455646]: wait for voice command ... +[ INFO] [1732710150.255553650]: wait for voice command ... +[ INFO] [1732710150.355455671]: wait for voice command ... +[ INFO] [1732710150.455426144]: wait for voice command ... +[ INFO] [1732710150.555457657]: wait for voice command ... +[ INFO] [1732710150.655476452]: wait for voice command ... +[ INFO] [1732710150.755488192]: wait for voice command ... +[ INFO] [1732710150.855429820]: wait for voice command ... +[ INFO] [1732710150.955455336]: wait for voice command ... +[ INFO] [1732710151.055550663]: wait for voice command ... +[ INFO] [1732710151.155444846]: wait for voice command ... +[ INFO] [1732710151.255438125]: wait for voice command ... +[ INFO] [1732710151.355449603]: wait for voice command ... +[ INFO] [1732710151.455460394]: wait for voice command ... +[ INFO] [1732710151.555467001]: wait for voice command ... +[ INFO] [1732710151.655433330]: wait for voice command ... +[ INFO] [1732710151.755419186]: wait for voice command ... +[ INFO] [1732710151.855436548]: wait for voice command ... +[ INFO] [1732710151.955509790]: wait for voice command ... +[ INFO] [1732710152.055462099]: wait for voice command ... +[ INFO] [1732710152.155455325]: wait for voice command ... +[ INFO] [1732710152.255424121]: wait for voice command ... +[ INFO] [1732710152.355462059]: wait for voice command ... +[ INFO] [1732710152.455416286]: wait for voice command ... +[ INFO] [1732710152.555459969]: wait for voice command ... +[ INFO] [1732710152.655465085]: wait for voice command ... +[ INFO] [1732710152.755502190]: wait for voice command ... +[ INFO] [1732710152.855464146]: wait for voice command ... +[ INFO] [1732710152.955431287]: wait for voice command ... +[ INFO] [1732710153.055458373]: wait for voice command ... +[ INFO] [1732710153.155426742]: wait for voice command ... +[ INFO] [1732710153.255461359]: wait for voice command ... +[ INFO] [1732710153.355418997]: wait for voice command ... +[ INFO] [1732710153.455450691]: wait for voice command ... +[ INFO] [1732710153.555453723]: wait for voice command ... +[ INFO] [1732710153.655423913]: wait for voice command ... +[ INFO] [1732710153.755460468]: wait for voice command ... +[ INFO] [1732710153.855456140]: wait for voice command ... +[ INFO] [1732710153.955465764]: wait for voice command ... +[ INFO] [1732710154.055420026]: wait for voice command ... +[ INFO] [1732710154.155420735]: wait for voice command ... +[ INFO] [1732710154.255546885]: wait for voice command ... +[ INFO] [1732710154.355462570]: wait for voice command ... +[ INFO] [1732710154.455454995]: wait for voice command ... +[ INFO] [1732710154.555455886]: wait for voice command ... +[ INFO] [1732710154.655420360]: wait for voice command ... +[ INFO] [1732710154.755418099]: wait for voice command ... +[ INFO] [1732710154.855445100]: wait for voice command ... +[ INFO] [1732710154.955423331]: wait for voice command ... +[ INFO] [1732710155.055469602]: wait for voice command ... +[ INFO] [1732710155.155500052]: wait for voice command ... +[ INFO] [1732710155.255428374]: wait for voice command ... +[ INFO] [1732710155.355423522]: wait for voice command ... +[ INFO] [1732710155.455459982]: wait for voice command ... +[ INFO] [1732710155.555422613]: wait for voice command ... +[ INFO] [1732710155.655424736]: wait for voice command ... +[ INFO] [1732710155.755431108]: wait for voice command ... +[ INFO] [1732710155.855694567]: wait for voice command ... +[ INFO] [1732710155.955548744]: wait for voice command ... +[ INFO] [1732710156.055456897]: wait for voice command ... +[ INFO] [1732710156.155456851]: wait for voice command ... +[ INFO] [1732710156.255462911]: wait for voice command ... +[ INFO] [1732710156.355413170]: wait for voice command ... +[ INFO] [1732710156.455425215]: wait for voice command ... +[ INFO] [1732710156.555419708]: wait for voice command ... +[ INFO] [1732710156.655429921]: wait for voice command ... +[ INFO] [1732710156.755463821]: wait for voice command ... +[ INFO] [1732710156.855457973]: wait for voice command ... +[ INFO] [1732710156.955426468]: wait for voice command ... +[ INFO] [1732710157.055430777]: wait for voice command ... +[ INFO] [1732710157.155431422]: wait for voice command ... +[ INFO] [1732710157.255459564]: wait for voice command ... +[ INFO] [1732710157.355458790]: wait for voice command ... +[ INFO] [1732710157.455510497]: wait for voice command ... +[ INFO] [1732710157.555424485]: wait for voice command ... +[ INFO] [1732710157.655488660]: wait for voice command ... +[ INFO] [1732710157.755423967]: wait for voice command ... +[ INFO] [1732710157.855424087]: wait for voice command ... +[ INFO] [1732710157.955419249]: wait for voice command ... +[ INFO] [1732710158.055455073]: wait for voice command ... +[ INFO] [1732710158.155459015]: wait for voice command ... +[ INFO] [1732710158.255547683]: wait for voice command ... +[ INFO] [1732710158.355465412]: wait for voice command ... +[ INFO] [1732710158.455461156]: wait for voice command ... +[ INFO] [1732710158.555457934]: wait for voice command ... +[ INFO] [1732710158.655436115]: wait for voice command ... +[ INFO] [1732710158.755434550]: wait for voice command ... +[ INFO] [1732710158.855457145]: wait for voice command ... +[ INFO] [1732710158.955456445]: wait for voice command ... +[ INFO] [1732710159.055487843]: wait for voice command ... +[ INFO] [1732710159.155538398]: wait for voice command ... +[ INFO] [1732710159.255461004]: wait for voice command ... +[ INFO] [1732710159.355460742]: wait for voice command ... +[ INFO] [1732710159.455426316]: wait for voice command ... +[ INFO] [1732710159.555464836]: wait for voice command ... +[ INFO] [1732710159.655490394]: wait for voice command ... +[ INFO] [1732710159.755466448]: wait for voice command ... +[ INFO] [1732710159.855641561]: wait for voice command ... +[ INFO] [1732710159.955522045]: wait for voice command ... +[ INFO] [1732710160.055467992]: wait for voice command ... +[ INFO] [1732710160.155458296]: wait for voice command ... +[ INFO] [1732710160.255463426]: wait for voice command ... +[ INFO] [1732710160.355459929]: wait for voice command ... +[ INFO] [1732710160.455460018]: wait for voice command ... +[ INFO] [1732710160.555447049]: wait for voice command ... +[ INFO] [1732710160.655417348]: wait for voice command ... +[ INFO] [1732710160.755451313]: wait for voice command ... +[ INFO] [1732710160.855461167]: wait for voice command ... +[ INFO] [1732710160.955456985]: wait for voice command ... +[ INFO] [1732710161.055456256]: wait for voice command ... +[ INFO] [1732710161.155437938]: wait for voice command ... +[ INFO] [1732710161.255462001]: wait for voice command ... +[ INFO] [1732710161.355454813]: wait for voice command ... +[ INFO] [1732710161.455454715]: wait for voice command ... +[ INFO] [1732710161.555470109]: wait for voice command ... +[ INFO] [1732710161.655421000]: wait for voice command ... +[ INFO] [1732710161.755417575]: wait for voice command ... +[ INFO] [1732710161.855443437]: wait for voice command ... +[ INFO] [1732710161.955483438]: wait for voice command ... +[ INFO] [1732710162.055466755]: wait for voice command ... +[ INFO] [1732710162.155456639]: wait for voice command ... +[ INFO] [1732710162.255457768]: wait for voice command ... +[ INFO] [1732710162.355456953]: wait for voice command ... +[ INFO] [1732710162.455464406]: wait for voice command ... +[ INFO] [1732710162.555459662]: wait for voice command ... +[ INFO] [1732710162.655430181]: wait for voice command ... +[ INFO] [1732710162.755422428]: wait for voice command ... +[ INFO] [1732710162.855417888]: wait for voice command ... +[ INFO] [1732710162.955457254]: wait for voice command ... +[ INFO] [1732710163.055413673]: wait for voice command ... +[ INFO] [1732710163.155455973]: wait for voice command ... +[ INFO] [1732710163.255461917]: wait for voice command ... +[ INFO] [1732710163.355469521]: wait for voice command ... +"め" +[ INFO] [1732710163.455427997]: wait for voice command ... +[ INFO] [1732710163.555465385]: wait for voice command ... +[ INFO] [1732710163.655428929]: wait for voice command ... +[ INFO] [1732710163.755466329]: wait for voice command ... +[ INFO] [1732710163.855455405]: wait for voice command ... +[ INFO] [1732710163.955418765]: wait for voice command ... +[ INFO] [1732710164.055460886]: wait for voice command ... +[ INFO] [1732710164.155462178]: wait for voice command ... +[ INFO] [1732710164.255486396]: wait for voice command ... +[ INFO] [1732710164.355463568]: wait for voice command ... +[ INFO] [1732710164.455451643]: wait for voice command ... +[ INFO] [1732710164.555458361]: wait for voice command ... +[ INFO] [1732710164.655433999]: wait for voice command ... +[ INFO] [1732710164.755488697]: wait for voice command ... +[ INFO] [1732710164.855459367]: wait for voice command ... +[ INFO] [1732710164.955455233]: wait for voice command ... +[ INFO] [1732710165.055484224]: wait for voice command ... +[ INFO] [1732710165.155430102]: wait for voice command ... +[ INFO] [1732710165.255462049]: wait for voice command ... +[ INFO] [1732710165.355422045]: wait for voice command ... +[ INFO] [1732710165.455480877]: wait for voice command ... +[ INFO] [1732710165.555423157]: wait for voice command ... +[ INFO] [1732710165.655485114]: wait for voice command ... +[ INFO] [1732710165.755470166]: wait for voice command ... +[ INFO] [1732710165.855422472]: wait for voice command ... +[ INFO] [1732710165.955456830]: wait for voice command ... +[ INFO] [1732710166.055461302]: wait for voice command ... +[ INFO] [1732710166.155464815]: wait for voice command ... +[ INFO] [1732710166.255457658]: wait for voice command ... +[ INFO] [1732710166.355415251]: wait for voice command ... +[ INFO] [1732710166.455456479]: wait for voice command ... +[ INFO] [1732710166.555665137]: wait for voice command ... +[ INFO] [1732710166.655466339]: wait for voice command ... +[ INFO] [1732710166.755435925]: wait for voice command ... +[ INFO] [1732710166.855459278]: wait for voice command ... +[ INFO] [1732710166.955458054]: wait for voice command ... +[ INFO] [1732710167.055458097]: wait for voice command ... +[ INFO] [1732710167.155432860]: wait for voice command ... +[ INFO] [1732710167.255459656]: wait for voice command ... +[ INFO] [1732710167.355452394]: wait for voice command ... +[ INFO] [1732710167.455475081]: wait for voice command ... +[ INFO] [1732710167.555418600]: wait for voice command ... +[ INFO] [1732710167.655419679]: wait for voice command ... +[ INFO] [1732710167.755464554]: wait for voice command ... +[ INFO] [1732710167.855392851]: wait for voice command ... +[ INFO] [1732710167.955419739]: wait for voice command ... +[ INFO] [1732710168.055457536]: wait for voice command ... +[ INFO] [1732710168.155479263]: wait for voice command ... +[ INFO] [1732710168.255424508]: wait for voice command ... +[ INFO] [1732710168.355458529]: wait for voice command ... +[ INFO] [1732710168.455455278]: wait for voice command ... +[ INFO] [1732710168.555454881]: wait for voice command ... +[ INFO] [1732710168.655456926]: wait for voice command ... +[ INFO] [1732710168.755417930]: wait for voice command ... +[ INFO] [1732710168.855435193]: wait for voice command ... +[ INFO] [1732710168.955593553]: wait for voice command ... +[ INFO] [1732710169.055515419]: wait for voice command ... +[ INFO] [1732710169.155467786]: wait for voice command ... +[ INFO] [1732710169.255428884]: wait for voice command ... +[ INFO] [1732710169.355457227]: wait for voice command ... +[ INFO] [1732710169.455440570]: wait for voice command ... +[ INFO] [1732710169.555441020]: wait for voice command ... +[ INFO] [1732710169.655457527]: wait for voice command ... +[ INFO] [1732710169.755454048]: wait for voice command ... +[ INFO] [1732710169.855438669]: wait for voice command ... +[ INFO] [1732710169.955434993]: wait for voice command ... +[ INFO] [1732710170.055428130]: wait for voice command ... +[ INFO] [1732710170.155422574]: wait for voice command ... +[ INFO] [1732710170.255430856]: wait for voice command ... +[ INFO] [1732710170.355422131]: wait for voice command ... +[ INFO] [1732710170.455429226]: wait for voice command ... +[ INFO] [1732710170.555498313]: wait for voice command ... +[ INFO] [1732710170.655448394]: wait for voice command ... +[ INFO] [1732710170.755457935]: wait for voice command ... +[ INFO] [1732710170.855413870]: wait for voice command ... +[ INFO] [1732710170.955462670]: wait for voice command ... +[ INFO] [1732710171.055448655]: wait for voice command ... +[ INFO] [1732710171.155459564]: wait for voice command ... +[ INFO] [1732710171.255476574]: wait for voice command ... +[ INFO] [1732710171.355542151]: wait for voice command ... +[ INFO] [1732710171.455468004]: wait for voice command ... +[ INFO] [1732710171.555532011]: wait for voice command ... +[ INFO] [1732710171.655469746]: wait for voice command ... +[ INFO] [1732710171.755564937]: wait for voice command ... +[ INFO] [1732710171.855551080]: wait for voice command ... +[ INFO] [1732710171.955491244]: wait for voice command ... +[ INFO] [1732710172.055516082]: wait for voice command ... +[ INFO] [1732710172.155463815]: wait for voice command ... +[ INFO] [1732710172.255503417]: wait for voice command ... +[ INFO] [1732710172.355533296]: wait for voice command ... +[ INFO] [1732710172.455538713]: wait for voice command ... +[ INFO] [1732710172.555477407]: wait for voice command ... +[ INFO] [1732710172.655542189]: wait for voice command ... +[ INFO] [1732710172.755515629]: wait for voice command ... +[ INFO] [1732710172.855511033]: wait for voice command ... +[ INFO] [1732710172.955609765]: wait for voice command ... +[ INFO] [1732710173.055539162]: wait for voice command ... +[ INFO] [1732710173.155485966]: wait for voice command ... +[ INFO] [1732710173.255515761]: wait for voice command ... +[ INFO] [1732710173.355479447]: wait for voice command ... +[ INFO] [1732710173.455511489]: wait for voice command ... +[ INFO] [1732710173.555468872]: wait for voice command ... +[ INFO] [1732710173.655514088]: wait for voice command ... +[ INFO] [1732710173.755518456]: wait for voice command ... +[ INFO] [1732710173.855510726]: wait for voice command ... +[ INFO] [1732710173.955526933]: wait for voice command ... +[ INFO] [1732710174.055502366]: wait for voice command ... +[ INFO] [1732710174.155548148]: wait for voice command ... +[ INFO] [1732710174.255545903]: wait for voice command ... +[ INFO] [1732710174.355479737]: wait for voice command ... +[ INFO] [1732710174.455537841]: wait for voice command ... +[ INFO] [1732710174.555542115]: wait for voice command ... +[ INFO] [1732710174.655493729]: wait for voice command ... +[ INFO] [1732710174.755493216]: wait for voice command ... +[ INFO] [1732710174.855549864]: wait for voice command ... +[ INFO] [1732710174.955492823]: wait for voice command ... +[ INFO] [1732710175.055547585]: wait for voice command ... +[ INFO] [1732710175.155529854]: wait for voice command ... +[ INFO] [1732710175.255494178]: wait for voice command ... +[ INFO] [1732710175.355485471]: wait for voice command ... +[ INFO] [1732710175.455583385]: wait for voice command ... +[ INFO] [1732710175.555566309]: wait for voice command ... +[ INFO] [1732710175.655492761]: wait for voice command ... +[ INFO] [1732710175.755532726]: wait for voice command ... +[ INFO] [1732710175.855551741]: wait for voice command ... +[ INFO] [1732710175.955513790]: wait for voice command ... +[ INFO] [1732710176.055570320]: wait for voice command ... +[ INFO] [1732710176.155566073]: wait for voice command ... +[ INFO] [1732710176.255511565]: wait for voice command ... +[ INFO] [1732710176.355496495]: wait for voice command ... +[ INFO] [1732710176.455540358]: wait for voice command ... +[ INFO] [1732710176.555552651]: wait for voice command ... +"メス" +[ INFO] [1732710176.655495013]: wait for voice command ... +[ INFO] [1732710183.397132368]: wait-interpolation debug: start +[ INFO] [1732710183.402449650]: wait-interpolation debug: end +[ INFO] [1732710189.992139282]: wait-interpolation debug: start +[ INFO] [1732710190.983221843]: wait-interpolation debug: end +[ WARN] [1732710191.043127569]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732710191.046374324]: continuous joint (l_forearm_roll_joint) moves 183.91 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732710191.046593123]: original trajectory command : +[ WARN] [1732710191.046666443]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (1000) +[ WARN] [1732710191.046719305]: current angle vector : #f(50.0 17.8275 14.7726 46.824 -78.4543 6.11414 -34.739 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732710191.046755132]: new trajectory command : dvi = 2 +[ WARN] [1732710191.046825547]: : #f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732710191.046885171]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) 500 +[ WARN] [1732710191.046927196]: new trajectory command : +[ WARN] [1732710191.046995142]: : (#f(50.0 2.04043 22.7617 18.9068 -87.3797 98.0693 -49.5448 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986)) (500 500) +[ INFO] [1732710191.052694913]: wait-interpolation debug: start +[ INFO] [1732710192.226215946]: wait-interpolation debug: end +[ INFO] [1732710192.240794253]: wait for target... +[ INFO] [1732710192.340816955]: wait for target... +[ INFO] [1732710192.440846790]: wait for target... +[ INFO] [1732710192.540837042]: wait for target... +[ INFO] [1732710192.640869256]: wait for target... +[ INFO] [1732710192.740819194]: wait for target... +[ INFO] [1732710192.840852675]: wait for target... +[ INFO] [1732710192.940848445]: wait for target... +[ INFO] [1732710193.040844673]: wait for target... +[ INFO] [1732710193.140812761]: wait for target... +[ INFO] [1732710193.240827969]: wait for target... +[ INFO] [1732710193.340938922]: wait for target... +[ INFO] [1732710193.440871646]: wait for target... +[ INFO] [1732710193.540848597]: wait for target... +[ INFO] [1732710193.640817792]: wait for target... +[ INFO] [1732710193.740825387]: wait for target... +[ INFO] [1732710193.840825410]: wait for target... +[ INFO] [1732710193.940815702]: wait for target... +[ INFO] [1732710194.040840113]: wait for target... +[ INFO] [1732710194.140888759]: wait for target... +[ INFO] [1732710194.240868787]: wait for target... +[ INFO] [1732710194.340825692]: wait for target... +[ INFO] [1732710194.440819849]: wait for target... +[ INFO] [1732710194.540822810]: wait for target... +[ INFO] [1732710194.640825504]: wait for target... +[ INFO] [1732710194.740851643]: wait for target... +[ INFO] [1732710194.840820969]: wait for target... +[ INFO] [1732710194.940831688]: wait for target... +[ INFO] [1732710195.040887120]: wait for target... +[ INFO] [1732710195.140850252]: wait for target... +[ INFO] [1732710195.240853024]: wait for target... +[ INFO] [1732710195.340858864]: wait for target... +[ INFO] [1732710195.440815281]: wait for target... +[ INFO] [1732710195.540843414]: wait for target... +[ INFO] [1732710195.640892716]: wait for target... +[ INFO] [1732710195.740837926]: wait for target... +[ INFO] [1732710195.840856232]: wait for target... +[ INFO] [1732710195.940822149]: wait for target... +[ INFO] [1732710196.040854196]: wait for target... +[ INFO] [1732710196.140837415]: wait for target... +[ INFO] [1732710196.240856909]: wait for target... +[ INFO] [1732710196.340846197]: wait for target... +[ INFO] [1732710196.440821224]: wait for target... +[ INFO] [1732710196.540826887]: wait for target... +[ INFO] [1732710196.640866606]: wait for target... +[ INFO] [1732710196.740831317]: wait for target... +[ INFO] [1732710196.844688682]: wait for target... +[ INFO] [1732710196.941003170]: wait for target... +[ INFO] [1732710197.040834562]: wait for target... +[ INFO] [1732710197.140828330]: wait for target... +[ INFO] [1732710197.240826451]: wait for target... +[ INFO] [1732710197.340824662]: wait for target... +[ INFO] [1732710197.440822419]: wait for target... +[ INFO] [1732710197.540828941]: wait for target... +[ INFO] [1732710197.640829657]: wait for target... +[ INFO] [1732710197.740889080]: wait for target... +[ INFO] [1732710197.840817640]: wait for target... +[ INFO] [1732710197.940824446]: wait for target... +[ INFO] [1732710198.040820091]: wait for target... +[ INFO] [1732710198.140858950]: wait for target... +[ INFO] [1732710198.240828056]: wait for target... +[ INFO] [1732710198.340856106]: wait for target... +[ INFO] [1732710198.440850459]: wait for target... +[ INFO] [1732710198.540851208]: wait for target... +[ INFO] [1732710198.640851774]: wait for target... +[ INFO] [1732710198.740819884]: wait for target... +[ INFO] [1732710198.840829325]: wait for target... +[ INFO] [1732710198.940849679]: wait for target... +[ INFO] [1732710199.040834033]: wait for target... +[ INFO] [1732710199.140846393]: wait for target... +[ INFO] [1732710199.240825070]: wait for target... +[ INFO] [1732710199.340822954]: wait for target... +[ INFO] [1732710199.440827252]: wait for target... +[ INFO] [1732710199.540851185]: wait for target... +[ INFO] [1732710199.640823034]: wait for target... +[ INFO] [1732710199.740824589]: wait for target... +[ INFO] [1732710199.840865019]: wait for target... +[ INFO] [1732710199.940828382]: wait for target... +[ INFO] [1732710200.040822660]: wait for target... +[ INFO] [1732710200.140815079]: wait for target... +[ INFO] [1732710200.240832739]: wait for target... +[ INFO] [1732710200.340827205]: wait for target... +[ INFO] [1732710200.440827148]: wait for target... +[ INFO] [1732710200.540820809]: wait for target... +[ INFO] [1732710200.640851713]: wait for target... +[ INFO] [1732710200.740853433]: wait for target... +[ INFO] [1732710200.840818281]: wait for target... +[ INFO] [1732710200.940825574]: wait for target... +[ INFO] [1732710201.040819898]: wait for target... +[ INFO] [1732710201.140861897]: wait for target... +[ INFO] [1732710201.240817159]: wait for target... +[ INFO] [1732710201.340835309]: wait for target... +[ INFO] [1732710201.440828775]: wait for target... +[ INFO] [1732710201.540818264]: wait for target... +[ INFO] [1732710201.640858993]: wait for target... +[ INFO] [1732710201.740844712]: wait for target... +[ INFO] [1732710201.840818195]: wait for target... +[ INFO] [1732710201.940820628]: wait for target... +[ INFO] [1732710202.040860136]: wait for target... +[ INFO] [1732710202.140857470]: wait for target... +[ INFO] [1732710202.240846700]: wait for target... +[ INFO] [1732710202.340827738]: wait for target... +[ INFO] [1732710202.440815912]: wait for target... +[ INFO] [1732710202.540852932]: wait for target... +[ INFO] [1732710202.640849740]: wait for target... +[ INFO] [1732710202.740824465]: wait for target... +[ INFO] [1732710202.840824673]: wait for target... +[ INFO] [1732710202.940829863]: wait for target... +[ INFO] [1732710203.040853937]: wait for target... +[ INFO] [1732710203.140882331]: wait for target... +[ INFO] [1732710203.240814381]: wait for target... +[ INFO] [1732710203.340875733]: wait for target... +[ INFO] [1732710203.440842153]: wait for target... +[ INFO] [1732710203.540865815]: wait for target... +[ INFO] [1732710203.640821897]: wait for target... +[ INFO] [1732710203.740825020]: wait for target... +[ INFO] [1732710203.840836144]: wait for target... +[ INFO] [1732710203.940819998]: wait for target... +[ INFO] [1732710204.040823372]: wait for target... +[ INFO] [1732710204.140817062]: wait for target... +[ INFO] [1732710204.240828223]: wait for target... +[ INFO] [1732710204.340830222]: wait for target... +[ INFO] [1732710204.440864049]: wait for target... +[ INFO] [1732710204.540831661]: wait for target... +[ INFO] [1732710204.640829830]: wait for target... +[ INFO] [1732710204.740824711]: wait for target... +[ INFO] [1732710204.840819341]: wait for target... +[ INFO] [1732710204.941066009]: wait for target... +[ INFO] [1732710205.040828664]: wait for target... +[ INFO] [1732710205.140819232]: wait for target... +[ INFO] [1732710205.240826683]: wait for target... +[ INFO] [1732710205.340877345]: wait for target... +[ INFO] [1732710205.440860660]: wait for target... +[ INFO] [1732710205.540821269]: wait for target... +[ INFO] [1732710205.640818525]: wait for target... +[ INFO] [1732710205.740853266]: wait for target... +[ INFO] [1732710205.840822848]: wait for target... +[ INFO] [1732710205.940834173]: wait for target... +[ INFO] [1732710206.040823662]: wait for target... +[ INFO] [1732710206.140823125]: wait for target... +[ INFO] [1732710206.240855026]: wait for target... +[ INFO] [1732710206.340846193]: wait for target... +[ INFO] [1732710206.440841085]: wait for target... +[ INFO] [1732710206.540822106]: wait for target... +[ INFO] [1732710206.640824895]: wait for target... +[ INFO] [1732710206.740856554]: wait for target... +[ INFO] [1732710206.840854949]: wait for target... +[ INFO] [1732710206.940825654]: wait for target... +[ INFO] [1732710207.040838841]: wait for target... +[ INFO] [1732710207.140824014]: wait for target... +[ INFO] [1732710207.240825966]: wait for target... +[ INFO] [1732710207.340818539]: wait for target... +[ INFO] [1732710207.440826815]: wait for target... +[ INFO] [1732710207.540817606]: wait for target... +[ INFO] [1732710207.640823374]: wait for target... +[ INFO] [1732710207.740827231]: wait for target... +[ INFO] [1732710207.840828416]: wait for target... +[ INFO] [1732710207.940825730]: wait for target... +[ INFO] [1732710208.040850012]: wait for target... +[ INFO] [1732710208.140818758]: wait for target... +[ INFO] [1732710208.240773417]: wait for target... +[ INFO] [1732710208.340827581]: wait for target... +[ INFO] [1732710208.440831259]: wait for target... +[ INFO] [1732710208.540815466]: wait for target... +[ INFO] [1732710208.640828081]: wait for target... +[ INFO] [1732710208.740826041]: wait for target... +[ INFO] [1732710208.840827149]: wait for target... +[ INFO] [1732710208.940854918]: wait for target... +[ INFO] [1732710209.040825572]: wait for target... +[ INFO] [1732710209.140817074]: wait for target... +[ INFO] [1732710209.240855909]: wait for target... +[ INFO] [1732710209.340829721]: wait for target... +[ INFO] [1732710209.440837741]: wait for target... +[ INFO] [1732710209.540827669]: wait for target... +[ INFO] [1732710209.640816119]: wait for target... +[ INFO] [1732710209.740818500]: wait for target... +[ INFO] [1732710209.840826049]: wait for target... +[ INFO] [1732710209.940815126]: wait for target... +[ INFO] [1732710210.040829685]: wait for target... +[ INFO] [1732710210.140827322]: wait for target... +[ INFO] [1732710210.240894978]: wait for target... +[ INFO] [1732710210.340811496]: wait for target... +[ INFO] [1732710210.440818054]: wait for target... +[ INFO] [1732710210.540819804]: wait for target... +[ INFO] [1732710210.640802454]: wait for target... +[ INFO] [1732710210.740858213]: wait for target... +[ INFO] [1732710210.840852018]: wait for target... +[ INFO] [1732710210.940847323]: wait for target... +[ INFO] [1732710211.040830741]: wait for target... +[ INFO] [1732710211.140820632]: wait for target... +[ INFO] [1732710211.240836265]: wait for target... +[ INFO] [1732710211.340825657]: wait for target... +[ INFO] [1732710211.440830083]: wait for target... +[ INFO] [1732710211.540820357]: wait for target... +[ INFO] [1732710211.640823647]: wait for target... +[ INFO] [1732710211.740830481]: wait for target... +[ INFO] [1732710211.840839070]: wait for target... +[ INFO] [1732710211.940832838]: wait for target... +[ INFO] [1732710212.040824012]: wait for target... +[ INFO] [1732710212.140864480]: wait for target... +[ INFO] [1732710212.240842572]: wait for target... +[ INFO] [1732710212.340858404]: wait for target... +[ INFO] [1732710212.440823180]: wait for target... +[ INFO] [1732710212.540863383]: wait for target... +[ INFO] [1732710212.640882833]: wait for target... +[ INFO] [1732710212.740863639]: wait for target... +[ INFO] [1732710212.840827000]: wait for target... +[ INFO] [1732710212.940853155]: wait for target... +[ INFO] [1732710213.040827758]: wait for target... +[ INFO] [1732710213.140831800]: wait for target... +[ INFO] [1732710213.240858841]: wait for target... +[ INFO] [1732710213.340862408]: wait for target... +[ INFO] [1732710213.440887304]: wait for target... +[ INFO] [1732710213.540821108]: wait for target... +[ INFO] [1732710213.640853305]: wait for target... +[ INFO] [1732710213.740826223]: wait for target... +[ INFO] [1732710213.840835834]: wait for target... +[ INFO] [1732710213.940843594]: wait for target... +[ INFO] [1732710214.040835695]: wait for target... +[ INFO] [1732710214.140830165]: wait for target... +[ INFO] [1732710214.240869129]: wait for target... +[ INFO] [1732710214.340834967]: wait for target... +[ INFO] [1732710214.440828577]: wait for target... +[ INFO] [1732710214.540827947]: wait for target... +[ INFO] [1732710214.640835029]: wait for target... +[ INFO] [1732710214.740862829]: wait for target... +[ INFO] [1732710214.840826332]: wait for target... +[ INFO] [1732710214.940829414]: wait for target... +[ INFO] [1732710215.040869883]: wait for target... +[ INFO] [1732710215.140832533]: wait for target... +[ INFO] [1732710215.240829558]: wait for target... +[ INFO] [1732710215.340835149]: wait for target... +[ INFO] [1732710215.440862631]: wait for target... +[ INFO] [1732710215.540866653]: wait for target... +[ INFO] [1732710215.640829729]: wait for target... +[ INFO] [1732710215.740856801]: wait for target... +[ INFO] [1732710215.840854718]: wait for target... +[ INFO] [1732710215.940857732]: wait for target... +[ INFO] [1732710216.040851375]: wait for target... +[ INFO] [1732710216.140843521]: wait for target... +[ INFO] [1732710216.240931713]: wait for target... +[ INFO] [1732710216.340854808]: wait for target... +[ INFO] [1732710216.440842420]: wait for target... +[ INFO] [1732710216.541195245]: wait for target... +[ INFO] [1732710216.640844247]: wait for target... +[ INFO] [1732710216.740859672]: wait for target... +[ INFO] [1732710216.840838081]: wait for target... +[ INFO] [1732710216.940850849]: wait for target... +[ INFO] [1732710217.040844061]: wait for target... +[ INFO] [1732710217.140859284]: wait for target... +[ INFO] [1732710217.240862677]: wait for target... +[ INFO] [1732710217.340859261]: wait for target... +[ INFO] [1732710217.440835506]: wait for target... +[ INFO] [1732710217.540833811]: wait for target... +[ INFO] [1732710217.640829186]: wait for target... +[ INFO] [1732710217.740829772]: wait for target... +[ INFO] [1732710217.840855215]: wait for target... +[ INFO] [1732710217.940823425]: wait for target... +[ INFO] [1732710218.040829868]: wait for target... +[ INFO] [1732710218.140829623]: wait for target... +[ INFO] [1732710218.240873128]: wait for target... +[ INFO] [1732710218.340871276]: wait for target... +[ INFO] [1732710218.440827584]: wait for target... +[ INFO] [1732710218.540832317]: wait for target... +[ INFO] [1732710218.640822423]: wait for target... +[ INFO] [1732710218.740834206]: wait for target... +[ INFO] [1732710218.840856600]: wait for target... +[ INFO] [1732710218.940826800]: wait for target... +[ INFO] [1732710219.040882099]: wait for target... +[ INFO] [1732710219.140871242]: wait for target... +[ INFO] [1732710219.240837675]: wait for target... +[ INFO] [1732710219.340867084]: wait for target... +[ INFO] [1732710219.440873825]: wait for target... +[ INFO] [1732710219.540834924]: wait for target... +[ INFO] [1732710219.640833027]: wait for target... +[ INFO] [1732710219.740847918]: wait for target... +[ INFO] [1732710219.840843426]: wait for target... +[ INFO] [1732710219.940833628]: wait for target... +[ INFO] [1732710220.040829804]: wait for target... +[ INFO] [1732710220.140845255]: wait for target... +[ INFO] [1732710220.240837347]: wait for target... +[ INFO] [1732710220.340842283]: wait for target... +[ INFO] [1732710220.440829596]: wait for target... +[ INFO] [1732710220.540833068]: wait for target... +[ INFO] [1732710220.640845007]: wait for target... +[ INFO] [1732710220.740854287]: wait for target... +[ INFO] [1732710220.840869425]: wait for target... +[ INFO] [1732710220.940835107]: wait for target... +[ INFO] [1732710221.040834798]: wait for target... +[ INFO] [1732710221.140859488]: wait for target... +[ INFO] [1732710221.240844665]: wait for target... +[ INFO] [1732710221.340871158]: wait for target... +[ INFO] [1732710221.440869191]: wait for target... +[ INFO] [1732710221.540837088]: wait for target... +[ INFO] [1732710221.640823889]: wait for target... +[ INFO] [1732710221.740828081]: wait for target... +[ INFO] [1732710221.840830328]: wait for target... +[ INFO] [1732710221.940823982]: wait for target... +[ INFO] [1732710222.040827537]: wait for target... +[ INFO] [1732710222.140834175]: wait for target... +[ INFO] [1732710222.240884823]: wait for target... +[ INFO] [1732710222.340872219]: wait for target... +[ INFO] [1732710222.440851534]: wait for target... +[ INFO] [1732710222.540857655]: wait for target... +[ INFO] [1732710222.640835997]: wait for target... +[ INFO] [1732710222.740824242]: wait for target... +[ INFO] [1732710222.840842693]: wait for target... +[ INFO] [1732710222.940859151]: wait for target... +[ INFO] [1732710223.040869353]: wait for target... +[ INFO] [1732710223.140826570]: wait for target... +[ INFO] [1732710223.240828571]: wait for target... +[ INFO] [1732710223.340850943]: wait for target... +[ INFO] [1732710223.440834912]: wait for target... +[ INFO] [1732710223.540825491]: wait for target... +[ INFO] [1732710223.640879453]: wait for target... +[ INFO] [1732710223.740846253]: wait for target... +[ INFO] [1732710223.840839888]: wait for target... +[ INFO] [1732710223.940875581]: wait for target... +[ INFO] [1732710224.040829618]: wait for target... +[ INFO] [1732710224.140822842]: wait for target... +[ INFO] [1732710224.240832412]: wait for target... +[ INFO] [1732710224.340851230]: wait for target... +[ INFO] [1732710224.440827502]: wait for target... +[ INFO] [1732710224.540820283]: wait for target... +[ INFO] [1732710224.640865609]: wait for target... +[ INFO] [1732710224.740827067]: wait for target... +[ INFO] [1732710224.840824978]: wait for target... +[ INFO] [1732710224.940827936]: wait for target... +[ INFO] [1732710225.040914487]: wait for target... +[ INFO] [1732710225.140835838]: wait for target... +[ INFO] [1732710225.240831648]: wait for target... +[ INFO] [1732710225.340830784]: wait for target... +[ INFO] [1732710225.440846038]: wait for target... +[ INFO] [1732710225.540830485]: wait for target... +[ INFO] [1732710225.640837970]: wait for target... +[ INFO] [1732710225.740831830]: wait for target... +[ INFO] [1732710225.840838083]: wait for target... +[ INFO] [1732710225.940852327]: wait for target... +[ INFO] [1732710226.040831161]: wait for target... +[ INFO] [1732710226.140863909]: wait for target... +[ INFO] [1732710226.240845410]: wait for target... +[ INFO] [1732710226.340818503]: wait for target... +[ INFO] [1732710226.440819421]: wait for target... +[ INFO] [1732710226.540828923]: wait for target... +[ INFO] [1732710226.640824080]: wait for target... +[ INFO] [1732710226.740825457]: wait for target... +[ INFO] [1732710226.840844912]: wait for target... +[ INFO] [1732710226.943041055]: wait for target... +[ INFO] [1732710227.040838895]: wait for target... +[ INFO] [1732710227.140871390]: wait for target... +[ INFO] [1732710227.240825653]: wait for target... +[ INFO] [1732710227.340826780]: wait for target... +[ INFO] [1732710227.440916709]: wait for target... +[ INFO] [1732710227.540817168]: wait for target... +[ INFO] [1732710227.640840446]: wait for target... +[ INFO] [1732710227.740827368]: wait for target... +[ INFO] [1732710227.840834956]: wait for target... +[ INFO] [1732710227.940834171]: wait for target... +[ INFO] [1732710228.040888392]: wait for target... +[ INFO] [1732710228.140825226]: wait for target... +[ INFO] [1732710228.240821563]: wait for target... +[ INFO] [1732710228.340857245]: wait for target... +[ INFO] [1732710228.440828531]: wait for target... +[ INFO] [1732710228.540845255]: wait for target... +[ INFO] [1732710228.640850060]: wait for target... +[ INFO] [1732710228.740830022]: wait for target... +[ INFO] [1732710228.841269176]: wait for target... +[ INFO] [1732710228.940839450]: wait for target... +[ INFO] [1732710229.040830840]: wait for target... +[ INFO] [1732710229.140832996]: wait for target... +[ INFO] [1732710229.240852418]: wait for target... +[ INFO] [1732710229.340843442]: wait for target... +[ INFO] [1732710229.440846746]: wait for target... +[ INFO] [1732710229.540830336]: wait for target... +[ INFO] [1732710229.640821759]: wait for target... +[ INFO] [1732710229.740832096]: wait for target... +[ INFO] [1732710229.840843844]: wait for target... +[ INFO] [1732710229.940858569]: wait for target... +[ INFO] [1732710230.040829195]: wait for target... +[ INFO] [1732710230.140830929]: wait for target... +[ INFO] [1732710230.240844613]: wait for target... +[ INFO] [1732710230.340847029]: wait for target... +[ INFO] [1732710230.440853406]: wait for target... +[ INFO] [1732710230.540827481]: wait for target... +[ INFO] [1732710230.640822267]: wait for target... +[ INFO] [1732710230.740830338]: wait for target... +[ INFO] [1732710230.840829229]: wait for target... +[ INFO] [1732710230.940857095]: wait for target... +[ INFO] [1732710231.040840653]: wait for target... +[ INFO] [1732710231.140854007]: wait for target... +[ INFO] [1732710231.240823844]: wait for target... +[ INFO] [1732710231.340850860]: wait for target... +[ INFO] [1732710231.440820765]: wait for target... +[ INFO] [1732710231.540823967]: wait for target... +[ INFO] [1732710231.640826972]: wait for target... +[ INFO] [1732710231.740833372]: wait for target... +[ INFO] [1732710231.840872922]: wait for target... +[ INFO] [1732710231.940934532]: wait for target... +[ INFO] [1732710232.040834578]: wait for target... +[ INFO] [1732710232.140859426]: wait for target... +[ INFO] [1732710232.240832988]: wait for target... +[ INFO] [1732710232.340842499]: wait for target... +[ INFO] [1732710232.440844903]: wait for target... +[ INFO] [1732710232.540871055]: wait for target... +[ INFO] [1732710232.640848170]: wait for target... +[ INFO] [1732710232.740829422]: wait for target... +[ INFO] [1732710232.840856777]: wait for target... +[ INFO] [1732710232.940841165]: wait for target... +[ INFO] [1732710233.040825491]: wait for target... +[ INFO] [1732710233.140828124]: wait for target... +[ INFO] [1732710233.240834717]: wait for target... +[ INFO] [1732710233.340859184]: wait for target... +[ INFO] [1732710233.440835493]: wait for target... +[ INFO] [1732710233.540848615]: wait for target... +[ INFO] [1732710233.640825923]: wait for target... +[ INFO] [1732710233.740848362]: wait for target... +[ INFO] [1732710233.840843834]: wait for target... +[ INFO] [1732710233.940826097]: wait for target... +[ INFO] [1732710234.040824680]: wait for target... +[ INFO] [1732710234.140859483]: wait for target... +[ INFO] [1732710234.240835845]: wait for target... +[ INFO] [1732710234.340857143]: wait for target... +[ INFO] [1732710234.440852457]: wait for target... +[ INFO] [1732710234.540819204]: wait for target... +[ INFO] [1732710234.640838713]: wait for target... +[ INFO] [1732710234.740814224]: wait for target... +[ INFO] [1732710234.840826872]: wait for target... +[ INFO] [1732710234.940829843]: wait for target... +[ INFO] [1732710235.040840368]: wait for target... +[ INFO] [1732710235.140832829]: wait for target... +[ INFO] [1732710235.240853821]: wait for target... +[ INFO] [1732710235.340825335]: wait for target... +[ INFO] [1732710235.440851761]: wait for target... +[ INFO] [1732710235.540826432]: wait for target... +[ INFO] [1732710235.640849304]: wait for target... +[ INFO] [1732710235.740877371]: wait for target... +[ INFO] [1732710235.840845635]: wait for target... +[ INFO] [1732710235.940912332]: wait for target... +[ INFO] [1732710236.040853027]: wait for target... +[ INFO] [1732710236.140851215]: wait for target... +[ INFO] [1732710236.240857083]: wait for target... +[ INFO] [1732710236.340859861]: wait for target... +[ INFO] [1732710236.440825595]: wait for target... +[ INFO] [1732710236.540818776]: wait for target... +[ INFO] [1732710236.640870933]: wait for target... +[ INFO] [1732710236.740830352]: wait for target... +[ INFO] [1732710236.840819647]: wait for target... +[ INFO] [1732710236.940829115]: wait for target... +[ INFO] [1732710237.040997686]: wait for target... +[ INFO] [1732710237.140838944]: wait for target... +[ INFO] [1732710237.240822663]: wait for target... +[ INFO] [1732710237.340827731]: wait for target... +[ INFO] [1732710237.440888249]: wait for target... +[ INFO] [1732710237.540823269]: wait for target... +[ INFO] [1732710237.640816636]: wait for target... +[ INFO] [1732710237.740823477]: wait for target... +[ INFO] [1732710237.840823789]: wait for target... +[ INFO] [1732710237.940827084]: wait for target... +[ INFO] [1732710238.040827576]: wait for target... +[ INFO] [1732710238.140854544]: wait for target... +[ INFO] [1732710238.240850390]: wait for target... +[ INFO] [1732710238.340827745]: wait for target... +[ INFO] [1732710238.440860084]: wait for target... +[ INFO] [1732710238.540823607]: wait for target... +[ INFO] [1732710238.640858083]: wait for target... +[ INFO] [1732710238.740824154]: wait for target... +[ INFO] [1732710238.840824380]: wait for target... +[ INFO] [1732710238.940851259]: wait for target... +[ INFO] [1732710239.040832477]: wait for target... +[ INFO] [1732710239.140834842]: wait for target... +[ INFO] [1732710239.240850594]: wait for target... +[ INFO] [1732710239.340847401]: wait for target... +[ INFO] [1732710239.440837465]: wait for target... +[ INFO] [1732710239.540831165]: wait for target... +[ INFO] [1732710239.640855100]: wait for target... +[ INFO] [1732710239.740866768]: wait for target... +[ INFO] [1732710239.840834319]: wait for target... +[ INFO] [1732710239.940820740]: wait for target... +[ INFO] [1732710240.040850501]: wait for target... +[ INFO] [1732710240.140824385]: wait for target... +[ INFO] [1732710240.240845562]: wait for target... +[ INFO] [1732710240.340845866]: wait for target... +[ INFO] [1732710240.440821585]: wait for target... +[ INFO] [1732710240.540836340]: wait for target... +[ INFO] [1732710240.640843566]: wait for target... +[ INFO] [1732710240.740907726]: wait for target... +[ INFO] [1732710240.840837397]: wait for target... +[ INFO] [1732710240.940822418]: wait for target... +[ INFO] [1732710241.040828304]: wait for target... +[ INFO] [1732710241.140855510]: wait for target... +[ INFO] [1732710241.240858337]: wait for target... +[ INFO] [1732710241.340851343]: wait for target... +[ INFO] [1732710241.440853867]: wait for target... +[ INFO] [1732710241.540858219]: wait for target... +[ INFO] [1732710241.640846177]: wait for target... +[ INFO] [1732710241.740837438]: wait for target... +[ INFO] [1732710241.840887328]: wait for target... +[ INFO] [1732710241.940862843]: wait for target... +[ INFO] [1732710242.040868909]: wait for target... +[ INFO] [1732710242.140880503]: wait for target... +[ INFO] [1732710242.240923223]: wait for target... +[ INFO] [1732710242.340890119]: wait for target... +[ INFO] [1732710242.440896867]: wait for target... +[ INFO] [1732710242.540924668]: wait for target... +[ INFO] [1732710242.640887462]: wait for target... +[ INFO] [1732710242.740944924]: wait for target... +[ INFO] [1732710242.840946939]: wait for target... +[ INFO] [1732710242.940922989]: wait for target... +[ INFO] [1732710243.040890126]: wait for target... +[ INFO] [1732710243.140965249]: wait for target... +[ INFO] [1732710243.240956823]: wait for target... +[ INFO] [1732710243.340857397]: wait for target... +[ INFO] [1732710243.440922566]: wait for target... +[ INFO] [1732710243.540930115]: wait for target... +[ INFO] [1732710243.640906665]: wait for target... +[ INFO] [1732710243.741203402]: wait for target... +[ INFO] [1732710243.840867645]: wait for target... +[ INFO] [1732710243.940926162]: wait for target... +[ INFO] [1732710244.040940907]: wait for target... +[ INFO] [1732710244.140904130]: wait for target... +[ INFO] [1732710244.240868887]: wait for target... +[ INFO] [1732710244.340863640]: wait for target... +[ INFO] [1732710244.440884479]: wait for target... +[ INFO] [1732710244.540880388]: wait for target... +[ INFO] [1732710244.640945447]: wait for target... +[ INFO] [1732710244.740856246]: wait for target... +[ INFO] [1732710244.840917251]: wait for target... +[ INFO] [1732710244.940934276]: wait for target... +[ INFO] [1732710245.041207365]: wait for target... +[ INFO] [1732710245.140945703]: wait for target... +[ INFO] [1732710245.240915182]: wait for target... +[ INFO] [1732710245.340885060]: wait for target... +[ INFO] [1732710245.440961881]: wait for target... +[ INFO] [1732710245.540947283]: wait for target... +[ INFO] [1732710245.640834764]: wait for target... +[ INFO] [1732710245.740899459]: wait for target... +[ INFO] [1732710245.840903293]: wait for target... +[ INFO] [1732710245.940993702]: wait for target... +[ INFO] [1732710246.040863270]: wait for target... +[ INFO] [1732710246.140912025]: wait for target... +[ INFO] [1732710246.240978623]: wait for target... +[ INFO] [1732710246.340942835]: wait for target... +[ INFO] [1732710246.440925265]: wait for target... +[ INFO] [1732710246.540925856]: wait for target... +[ INFO] [1732710246.640914967]: wait for target... +[ INFO] [1732710246.740896512]: wait for target... +[ INFO] [1732710246.840900639]: wait for target... +[ INFO] [1732710246.940844516]: wait for target... +[ INFO] [1732710247.040955429]: wait for target... +[ INFO] [1732710247.140851079]: wait for target... +[ INFO] [1732710247.240827565]: wait for target... +[ INFO] [1732710247.340889685]: wait for target... +[ INFO] [1732710247.440923060]: wait for target... +[ INFO] [1732710247.540890637]: wait for target... +[ INFO] [1732710247.640872539]: wait for target... +[ INFO] [1732710247.740891915]: wait for target... +[ INFO] [1732710247.840885847]: wait for target... +[ INFO] [1732710247.940852537]: wait for target... +[ INFO] [1732710248.040856114]: wait for target... +[ INFO] [1732710248.140858802]: wait for target... +[ INFO] [1732710248.240855684]: wait for target... +[ INFO] [1732710248.340823562]: wait for target... +[ INFO] [1732710248.440872934]: wait for target... +[ INFO] [1732710248.540865547]: wait for target... +[ INFO] [1732710248.640854702]: wait for target... +[ INFO] [1732710248.740826159]: wait for target... +[ INFO] [1732710248.840843001]: wait for target... +[ INFO] [1732710248.940818133]: wait for target... +[ INFO] [1732710249.040820887]: wait for target... +[ INFO] [1732710249.140858983]: wait for target... +[ INFO] [1732710249.240824387]: wait for target... +[ INFO] [1732710249.340820288]: wait for target... +[ INFO] [1732710249.440883488]: wait for target... +[ INFO] [1732710249.540815600]: wait for target... +[ INFO] [1732710249.640849282]: wait for target... +[ INFO] [1732710249.740818309]: wait for target... +[ INFO] [1732710249.840865706]: wait for target... +[ INFO] [1732710249.940875241]: wait for target... +[ INFO] [1732710250.040831612]: wait for target... +[ INFO] [1732710250.140861512]: wait for target... +[ INFO] [1732710250.240823195]: wait for target... +[ INFO] [1732710250.340847863]: wait for target... +[ INFO] [1732710250.440847714]: wait for target... +[ INFO] [1732710250.540820471]: wait for target... +[ INFO] [1732710250.640846573]: wait for target... +[ INFO] [1732710250.740845956]: wait for target... +[ INFO] [1732710250.840845642]: wait for target... +[ INFO] [1732710250.940858305]: wait for target... +[ INFO] [1732710251.040879912]: wait for target... +[ INFO] [1732710251.140848246]: wait for target... +[ INFO] [1732710251.240822085]: wait for target... +[ INFO] [1732710251.340847264]: wait for target... +[ INFO] [1732710251.440848473]: wait for target... +[ INFO] [1732710251.540855297]: wait for target... +[ INFO] [1732710251.640855318]: wait for target... +[ INFO] [1732710251.740860302]: wait for target... +[ INFO] [1732710251.840855248]: wait for target... +[ INFO] [1732710251.940852123]: wait for target... +[ INFO] [1732710252.040844827]: wait for target... +[ INFO] [1732710252.140865687]: wait for target... +[ INFO] [1732710252.240858285]: wait for target... +[ INFO] [1732710252.340859967]: wait for target... +[ INFO] [1732710252.440818847]: wait for target... +[ INFO] [1732710252.540819183]: wait for target... +[ INFO] [1732710252.640868427]: wait for target... +[ INFO] [1732710252.741005804]: wait for target... +[ INFO] [1732710252.840904179]: wait for target... +[ INFO] [1732710252.940857741]: wait for target... +[ INFO] [1732710253.040812303]: wait for target... +[ INFO] [1732710253.140856291]: wait for target... +[ INFO] [1732710253.240862428]: wait for target... +[ INFO] [1732710253.340852290]: wait for target... +[ INFO] [1732710253.440853396]: wait for target... +[ INFO] [1732710253.540817460]: wait for target... +[ INFO] [1732710253.640987129]: wait for target... +[ INFO] [1732710253.740825742]: wait for target... +[ INFO] [1732710253.840856009]: wait for target... +[ INFO] [1732710253.940853842]: wait for target... +[ INFO] [1732710254.040854051]: wait for target... +[ INFO] [1732710254.140844992]: wait for target... +[ INFO] [1732710254.240870290]: wait for target... +[ INFO] [1732710254.340851994]: wait for target... +[ INFO] [1732710254.440850518]: wait for target... +[ INFO] [1732710254.540856784]: wait for target... +[ INFO] [1732710254.640856103]: wait for target... +[ INFO] [1732710254.740853638]: wait for target... +[ INFO] [1732710254.840868339]: wait for target... +[ INFO] [1732710254.940831089]: wait for target... +[ INFO] [1732710255.040829065]: wait for target... +[ INFO] [1732710255.140803882]: wait for target... +[ INFO] [1732710255.240890916]: wait for target... +[ INFO] [1732710255.340825054]: wait for target... +[ INFO] [1732710255.440815333]: wait for target... +[ INFO] [1732710255.540857327]: wait for target... +[ INFO] [1732710255.640857281]: wait for target... +[ INFO] [1732710255.740817516]: wait for target... +[ INFO] [1732710255.840829034]: wait for target... +[ INFO] [1732710255.940845033]: wait for target... +[ INFO] [1732710256.040855115]: wait for target... +[ INFO] [1732710256.140865100]: wait for target... +[ INFO] [1732710256.240822247]: wait for target... +[ INFO] [1732710256.340825999]: wait for target... +[ INFO] [1732710256.440829636]: wait for target... +[ INFO] [1732710256.540820864]: wait for target... +[ INFO] [1732710256.640835922]: wait for target... +[ INFO] [1732710256.740819468]: wait for target... +[ INFO] [1732710256.840847097]: wait for target... +[ INFO] [1732710256.940860117]: wait for target... +[ INFO] [1732710257.040855011]: wait for target... +[ INFO] [1732710257.140821111]: wait for target... +[ INFO] [1732710257.240899421]: wait for target... +[ INFO] [1732710257.340863771]: wait for target... +[ INFO] [1732710257.440885444]: wait for target... +[ INFO] [1732710257.540843288]: wait for target... +[ INFO] [1732710257.640819909]: wait for target... +[ INFO] [1732710257.740848069]: wait for target... +[ INFO] [1732710257.840846550]: wait for target... +[ INFO] [1732710257.940853234]: wait for target... +[ INFO] [1732710258.040869742]: wait for target... +[ INFO] [1732710258.140859957]: wait for target... +[ INFO] [1732710258.240818743]: wait for target... +[ INFO] [1732710258.340815460]: wait for target... +[ INFO] [1732710258.440920011]: wait for target... +[ INFO] [1732710258.540863490]: wait for target... +[ INFO] [1732710258.640818773]: wait for target... +[ INFO] [1732710258.740818398]: wait for target... +[ INFO] [1732710258.840822414]: wait for target... +[ INFO] [1732710258.940856075]: wait for target... +[ INFO] [1732710259.040882104]: wait for target... +[ INFO] [1732710259.140847542]: wait for target... +[ INFO] [1732710259.240854317]: wait for target... +[ INFO] [1732710259.340861242]: wait for target... +[ INFO] [1732710259.440854110]: wait for target... +[ INFO] [1732710259.540820919]: wait for target... +[ INFO] [1732710259.640880173]: wait for target... +[ INFO] [1732710259.740862327]: wait for target... +[ INFO] [1732710259.840886717]: wait for target... +[ INFO] [1732710259.940821190]: wait for target... +[ INFO] [1732710260.040819085]: wait for target... +[ INFO] [1732710260.140823266]: wait for target... +[ INFO] [1732710260.240839468]: wait for target... +[ INFO] [1732710260.340822690]: wait for target... +[ INFO] [1732710260.440818935]: wait for target... +[ INFO] [1732710260.540860310]: wait for target... +[ INFO] [1732710260.640883521]: wait for target... +[ INFO] [1732710260.740826697]: wait for target... +[ INFO] [1732710260.840846633]: wait for target... +[ INFO] [1732710260.940817119]: wait for target... +[ INFO] [1732710261.040851953]: wait for target... +[ INFO] [1732710261.140814103]: wait for target... +[ INFO] [1732710261.240830847]: wait for target... +[ INFO] [1732710261.340885358]: wait for target... +[ INFO] [1732710261.440865402]: wait for target... +[ INFO] [1732710261.540852855]: wait for target... +[ INFO] [1732710261.640814082]: wait for target... +[ INFO] [1732710261.740863721]: wait for target... +[ INFO] [1732710261.840861987]: wait for target... +[ INFO] [1732710261.940846082]: wait for target... +[ INFO] [1732710262.040813002]: wait for target... +[ INFO] [1732710262.140878542]: wait for target... +[ INFO] [1732710262.240873414]: wait for target... +[ INFO] [1732710262.340850430]: wait for target... +[ INFO] [1732710262.440813115]: wait for target... +[ INFO] [1732710262.540860453]: wait for target... +[ INFO] [1732710262.640822437]: wait for target... +[ INFO] [1732710262.740813674]: wait for target... +[ INFO] [1732710262.840871957]: wait for target... +[ INFO] [1732710262.940848714]: wait for target... +[ INFO] [1732710263.040908416]: wait for target... +[ INFO] [1732710263.140856007]: wait for target... +[ INFO] [1732710263.240850141]: wait for target... +[ INFO] [1732710263.340821421]: wait for target... +[ INFO] [1732710263.440861402]: wait for target... +[ INFO] [1732710263.540856002]: wait for target... +[ INFO] [1732710263.640853725]: wait for target... +[ INFO] [1732710263.740822354]: wait for target... +[ INFO] [1732710263.840846529]: wait for target... +[ INFO] [1732710263.940821864]: wait for target... +[ INFO] [1732710264.040818157]: wait for target... +[ INFO] [1732710264.140823769]: wait for target... +[ INFO] [1732710264.240847661]: wait for target... +[ INFO] [1732710264.340821545]: wait for target... +[ INFO] [1732710264.440865615]: wait for target... +[ INFO] [1732710264.540848902]: wait for target... +[ INFO] [1732710264.640870557]: wait for target... +[ INFO] [1732710264.740852543]: wait for target... +[ INFO] [1732710264.840850550]: wait for target... +[ INFO] [1732710264.940819404]: wait for target... +[ INFO] [1732710265.040882751]: wait for target... +[ INFO] [1732710265.140893978]: wait for target... +[ INFO] [1732710265.240861185]: wait for target... +[ INFO] [1732710265.340843249]: wait for target... +[ INFO] [1732710265.440872221]: wait for target... +[ INFO] [1732710265.540846224]: wait for target... +[ INFO] [1732710265.640852934]: wait for target... +[ INFO] [1732710265.740824315]: wait for target... +[ INFO] [1732710265.840861217]: wait for target... +[ INFO] [1732710265.940888804]: wait for target... +[ INFO] [1732710266.040869653]: wait for target... +[ INFO] [1732710266.140847448]: wait for target... +[ INFO] [1732710266.240827573]: wait for target... +[ INFO] [1732710266.340815394]: wait for target... +[ INFO] [1732710266.440856718]: wait for target... +[ INFO] [1732710266.540858267]: wait for target... +[ INFO] [1732710266.640826029]: wait for target... +[ INFO] [1732710266.740905360]: wait for target... +[ INFO] [1732710266.840830697]: wait for target... +[ INFO] [1732710266.940820106]: wait for target... +[ INFO] [1732710267.040871058]: wait for target... +[ INFO] [1732710267.140815267]: wait for target... +[ INFO] [1732710267.240829533]: wait for target... +[ INFO] [1732710267.340876451]: wait for target... +[ INFO] [1732710267.440852832]: wait for target... +[ INFO] [1732710267.540867114]: wait for target... +[ INFO] [1732710267.640859516]: wait for target... +[ INFO] [1732710267.740845185]: wait for target... +[ INFO] [1732710267.840867270]: wait for target... +[ INFO] [1732710267.940847270]: wait for target... +[ INFO] [1732710268.040850961]: wait for target... +[ INFO] [1732710268.140859821]: wait for target... +[ INFO] [1732710268.240815552]: wait for target... +[ INFO] [1732710268.340906686]: wait for target... +[ INFO] [1732710268.440892861]: wait for target... +[ INFO] [1732710268.540865767]: wait for target... +[ INFO] [1732710268.640819275]: wait for target... +[ INFO] [1732710268.740847921]: wait for target... +[ INFO] [1732710268.840850357]: wait for target... +[ INFO] [1732710268.940901910]: wait for target... +[ INFO] [1732710269.040845397]: wait for target... +[ INFO] [1732710269.140821624]: wait for target... +[ INFO] [1732710269.240817687]: wait for target... +[ INFO] [1732710269.340814578]: wait for target... +[ INFO] [1732710269.440959762]: wait for target... +[ INFO] [1732710269.540851641]: wait for target... +[ INFO] [1732710269.640817466]: wait for target... +[ INFO] [1732710269.740857986]: wait for target... +[ INFO] [1732710269.840825328]: wait for target... +[ INFO] [1732710269.940829711]: wait for target... +[ INFO] [1732710270.040826050]: wait for target... +[ INFO] [1732710270.140822951]: wait for target... +[ INFO] [1732710270.240840902]: wait for target... +[ INFO] [1732710270.340824469]: wait for target... +[ INFO] [1732710270.440847305]: wait for target... +[ INFO] [1732710270.540823863]: wait for target... +[ INFO] [1732710270.640823279]: wait for target... +[ INFO] [1732710270.740823433]: wait for target... +[ INFO] [1732710270.840826826]: wait for target... +[ INFO] [1732710270.940823778]: wait for target... +[ INFO] [1732710271.040884327]: wait for target... +[ INFO] [1732710271.141031469]: wait for target... +[ INFO] [1732710271.240899572]: wait for target... +[ INFO] [1732710271.340854130]: wait for target... +[ INFO] [1732710271.440850115]: wait for target... +[ INFO] [1732710271.540845534]: wait for target... +[ INFO] [1732710271.640846136]: wait for target... +[ INFO] [1732710271.740867041]: wait for target... +[ INFO] [1732710271.840859554]: wait for target... +[ INFO] [1732710271.940848308]: wait for target... +[ INFO] [1732710272.040829563]: wait for target... +[ INFO] [1732710272.140819417]: wait for target... +[ INFO] [1732710272.240822411]: wait for target... +[ INFO] [1732710272.340824779]: wait for target... +[ INFO] [1732710272.440890890]: wait for target... +[ INFO] [1732710272.540856199]: wait for target... +[ INFO] [1732710272.640890487]: wait for target... +[ INFO] [1732710272.740851395]: wait for target... +[ INFO] [1732710272.840848660]: wait for target... +[ INFO] [1732710272.940859622]: wait for target... +[ INFO] [1732710273.040858862]: wait for target... +[ INFO] [1732710273.140858369]: wait for target... +[ INFO] [1732710273.240855806]: wait for target... +[ INFO] [1732710273.340857456]: wait for target... +[ INFO] [1732710273.440885452]: wait for target... +[ INFO] [1732710273.540841487]: wait for target... +[ INFO] [1732710273.640833048]: wait for target... +[ INFO] [1732710273.740848954]: wait for target... +[ INFO] [1732710273.840882012]: wait for target... +[ INFO] [1732710273.940857690]: wait for target... +[ INFO] [1732710274.040859023]: wait for target... +[ INFO] [1732710274.140854335]: wait for target... +[ INFO] [1732710274.240850841]: wait for target... +[ INFO] [1732710274.340850048]: wait for target... +[ INFO] [1732710274.440851207]: wait for target... +[ INFO] [1732710274.540862162]: wait for target... +[ INFO] [1732710274.640843021]: wait for target... +[ INFO] [1732710274.740844044]: wait for target... +[ INFO] [1732710274.840842155]: wait for target... +[ INFO] [1732710274.940852930]: wait for target... +[ INFO] [1732710275.040891227]: wait for target... +[ INFO] [1732710275.140848874]: wait for target... +[ INFO] [1732710275.240818495]: wait for target... +[ INFO] [1732710275.340846792]: wait for target... +[ INFO] [1732710275.440846390]: wait for target... +[ INFO] [1732710275.540848607]: wait for target... +[ INFO] [1732710275.640855562]: wait for target... +[ INFO] [1732710275.740851374]: wait for target... +[ INFO] [1732710275.840851249]: wait for target... +[ INFO] [1732710275.940854915]: wait for target... +[ INFO] [1732710276.040848925]: wait for target... +[ INFO] [1732710276.140844449]: wait for target... +[ INFO] [1732710276.240860417]: wait for target... +[ INFO] [1732710276.340810692]: wait for target... +[ INFO] [1732710276.440816576]: wait for target... +[ INFO] [1732710276.540822832]: wait for target... +[ INFO] [1732710276.640873011]: wait for target... +[ INFO] [1732710276.740822093]: wait for target... +[ INFO] [1732710276.840851333]: wait for target... +[ INFO] [1732710276.941324094]: boxes 6 +[ WARN] [1732710276.989557750]: continuous joint (r_forearm_roll_joint) moves 187.289 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732710276.991850057]: continuous joint (r_forearm_roll_joint) moves 187.289 degree, commanded joint differs from original trajectory to avoid unintentional 360 rotation +[ WARN] [1732710276.991894711]: original trajectory command : +[ WARN] [1732710276.991918685]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2599 43.8772 31.2428 -95.029 167.289 -43.8185 77.0167 0.0 42.8986)) (500) +[ WARN] [1732710276.991949860]: current angle vector : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -60.0 74.0 -70.0 -120.0 -20.0 -30.0 180.0 0.0 42.8986) +[ WARN] [1732710276.991977873]: new trajectory command : dvi = 2 +[ WARN] [1732710276.992025624]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8701 58.9386 -19.3786 -107.514 73.6443 -36.9093 128.508 0.0 42.8986) 250 +[ WARN] [1732710276.992073166]: : #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2599 43.8772 31.2428 -95.029 167.289 -43.8185 77.0167 0.0 42.8986) 250 +[ WARN] [1732710276.992087222]: new trajectory command : +[ WARN] [1732710276.992148781]: : (#f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 -13.8701 58.9386 -19.3786 -107.514 73.6443 -36.9093 128.508 0.0 42.8986) #f(50.0 -13.7467 30.7507 -9.01042 -96.3052 190.024 -64.3506 173.106 32.2599 43.8772 31.2428 -95.029 167.289 -43.8185 77.0167 0.0 42.8986)) (250 250) +[ INFO] [1732710276.995213704]: wait-interpolation debug: start +[ERROR] [1732710278.597984859]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732710278.598038473]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732710278.611889755]: wait-interpolation debug: end +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0505) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0858) violate max-angle(88.0) +;; # :joint-angle(88.0947) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0899) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0861) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0828) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0804) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0775) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732710279.348170477]: wait-interpolation debug: start +[ INFO] [1732710280.605495744]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732710280.689755761]: wait-interpolation debug: start +[ INFO] [1732710281.685371071]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732710281.726877204]: wait-interpolation debug: start +[ INFO] [1732710282.735163948]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732710282.791949519]: wait-interpolation debug: start +[ INFO] [1732710283.783680412]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732710283.843977970]: wait-interpolation debug: start +[ INFO] [1732710284.855043026]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732710284.902868563]: wait-interpolation debug: start +[ INFO] [1732710285.908719146]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732710286.015019015]: wait-interpolation debug: start +[ INFO] [1732710287.012505072]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732710287.057413883]: wait-interpolation debug: start +[ INFO] [1732710288.063046152]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732710288.111078485]: wait-interpolation debug: start +[ INFO] [1732710289.101081605]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732710289.154256758]: wait-interpolation debug: start +[ INFO] [1732710290.150238734]: wait-interpolation debug: end +;; # :joint-angle(88.0772) violate max-angle(88.0) +[ INFO] [1732710292.312786160]: wait-interpolation debug: start +[ INFO] [1732710292.320966487]: wait-interpolation debug: end +[ INFO] [1732710295.169637966]: wait-interpolation debug: start +[ INFO] [1732710295.172387153]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732710295.260147243]: wait-interpolation debug: start +[ INFO] [1732710300.265139137]: wait-interpolation debug: end +[ INFO] [1732710300.359142568]: wait-interpolation debug: start +[ERROR] [1732710313.325605134]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732710313.325645463]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ INFO] [1732710313.326374685]: wait-interpolation debug: end +[ INFO] [1732710316.634177877]: wait-interpolation debug: start +[ INFO] [1732710317.625159115]: wait-interpolation debug: end +[ INFO] [1732710319.581933278]: wait-interpolation debug: start +[ INFO] [1732710319.582104145]: wait-interpolation debug: end +[ INFO] [1732710320.589328572]: wait-interpolation debug: start +[ INFO] [1732710320.592930990]: wait-interpolation debug: end +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +[ INFO] [1732710326.067653176]: wait-interpolation debug: start +[ INFO] [1732710327.063106128]: wait-interpolation debug: end +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +;; # :joint-angle(88.0822) violate max-angle(88.0) +[ INFO] [1732710327.108481388]: wait-interpolation debug: start +[ INFO] [1732710328.101607614]: wait-interpolation debug: end +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732710328.145782129]: wait-interpolation debug: start +[ INFO] [1732710329.138583411]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732710329.177619634]: wait-interpolation debug: start +[ INFO] [1732710330.174746841]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732710330.217949924]: wait-interpolation debug: start +[ INFO] [1732710331.224958363]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732710331.273904436]: wait-interpolation debug: start +[ INFO] [1732710332.282726890]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732710332.327812600]: wait-interpolation debug: start +[ INFO] [1732710333.317433894]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732710333.361730204]: wait-interpolation debug: start +[ INFO] [1732710334.352107731]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732710334.394979724]: wait-interpolation debug: start +[ INFO] [1732710335.386584002]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732710335.434595016]: wait-interpolation debug: start +[ INFO] [1732710336.434805148]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732710336.486705533]: wait-interpolation debug: start +[ INFO] [1732710337.479891944]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732710337.521455193]: wait-interpolation debug: start +[ INFO] [1732710338.515226609]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732710340.619108041]: wait-interpolation debug: start +[ INFO] [1732710340.619408012]: wait-interpolation debug: end +[ INFO] [1732710343.451338723]: wait-interpolation debug: start +[ INFO] [1732710343.457604726]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732710343.536050389]: wait-interpolation debug: start +[ INFO] [1732710348.527748029]: wait-interpolation debug: end +[ INFO] [1732710348.665526229]: wait-interpolation debug: start +[ INFO] [1732710350.664501385]: wait-interpolation debug: end +[ INFO] [1732710350.721008618]: wait-interpolation debug: start +[ INFO] [1732710351.705721904]: wait-interpolation debug: end +[ INFO] [1732710353.661300460]: wait-interpolation debug: start +[ INFO] [1732710353.662088239]: wait-interpolation debug: end +[ INFO] [1732710354.688990019]: wait-interpolation debug: start +[ INFO] [1732710354.695874982]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732710360.163334552]: wait-interpolation debug: start +[ INFO] [1732710361.180854053]: wait-interpolation debug: end +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +;; # :joint-angle(88.0787) violate max-angle(88.0) +[ INFO] [1732710361.230991734]: wait-interpolation debug: start +[ INFO] [1732710362.224359692]: wait-interpolation debug: end +;; # :joint-angle(88.0671) violate max-angle(88.0) +;; # :joint-angle(88.0656) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +;; # :joint-angle(88.0653) violate max-angle(88.0) +[ INFO] [1732710362.265477225]: wait-interpolation debug: start +[ INFO] [1732710363.322590913]: wait-interpolation debug: end +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +;; # :joint-angle(88.065) violate max-angle(88.0) +[ INFO] [1732710363.375214521]: wait-interpolation debug: start +[ INFO] [1732710364.395468307]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732710364.435368433]: wait-interpolation debug: start +[ INFO] [1732710365.446086957]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732710365.482435619]: wait-interpolation debug: start +[ WARN] [1732710367.552927525]: [l_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732710367.555472740]: [r_arm_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732710367.563687379]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732710367.564025868]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732710367.564461054]: [head_traj_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ WARN] [1732710367.566572730]: [torso_controller/follow_joint_trajectory] feedback-cb # received wrong goal +[ INFO] [1732710367.596826238]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732710367.667954279]: wait-interpolation debug: start +[ INFO] [1732710368.666696163]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732710368.717404442]: wait-interpolation debug: start +[ INFO] [1732710369.710106138]: wait-interpolation debug: end +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +;; # :joint-angle(88.0641) violate max-angle(88.0) +[ INFO] [1732710369.757411638]: wait-interpolation debug: start +[ INFO] [1732710370.747561717]: wait-interpolation debug: end +;; # :joint-angle(88.0638) violate max-angle(88.0) +;; # :joint-angle(88.0632) violate max-angle(88.0) +;; # :joint-angle(88.0632) violate max-angle(88.0) +;; # :joint-angle(88.0632) violate max-angle(88.0) +;; # :joint-angle(88.0632) violate max-angle(88.0) +;; # :joint-angle(88.0632) violate max-angle(88.0) +;; # :joint-angle(88.0629) violate max-angle(88.0) +[ INFO] [1732710370.813494357]: wait-interpolation debug: start +[ INFO] [1732710371.803215665]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732710371.848640624]: wait-interpolation debug: start +[ INFO] [1732710372.872716326]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732710372.912974005]: wait-interpolation debug: start +[ INFO] [1732710373.947146026]: wait-interpolation debug: end +;; # :joint-angle(88.0606) violate max-angle(88.0) +[ INFO] [1732710376.040648148]: wait-interpolation debug: start +[ INFO] [1732710376.041276926]: wait-interpolation debug: end +[ INFO] [1732710378.870828594]: wait-interpolation debug: start +[ INFO] [1732710378.871099256]: wait-interpolation debug: end +remaining 280 +[ INFO] [1732710378.917269372]: wait-interpolation debug: start +[ INFO] [1732710383.903734203]: wait-interpolation debug: end +[ INFO] [1732710384.017186756]: wait-interpolation debug: start +[ INFO] [1732710386.008219477]: wait-interpolation debug: end +[ INFO] [1732710386.080802964]: wait-interpolation debug: start +[ INFO] [1732710387.073900742]: wait-interpolation debug: end +[ INFO] [1732710389.025874752]: wait-interpolation debug: start +[ INFO] [1732710389.026052842]: wait-interpolation debug: end +[ INFO] [1732710390.033932255]: wait-interpolation debug: start +[ INFO] [1732710390.037062783]: wait-interpolation debug: end +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +[ INFO] [1732710395.434112584]: wait-interpolation debug: start +[ INFO] [1732710396.426042419]: wait-interpolation debug: end +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +;; # :joint-angle(88.0796) violate max-angle(88.0) +[ INFO] [1732710396.476978606]: wait-interpolation debug: start +[ INFO] [1732710397.467423655]: wait-interpolation debug: end +;; # :joint-angle(88.0618) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +[ INFO] [1732710397.518055237]: wait-interpolation debug: start +[ INFO] [1732710398.508723658]: wait-interpolation debug: end +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +;; # :joint-angle(88.0615) violate max-angle(88.0) +[ INFO] [1732710398.567090676]: wait-interccpolation debug: start +[ INFO] [1732710399.559908091]: wait-interpolation debug: end +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +[ INFO] [1732710399.605591524]: wait-interpolation debug: start +[ INFO] [1732710400.594974613]: wait-interpolation debug: end +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +[ INFO] [1732710400.661196391]: wait-interpolation debug: start +[ INFO] [1732710401.659671102]: wait-interpolation debug: end +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +;; # :joint-angle(88.0609) violate max-angle(88.0) +[ INFO] [1732710401.703238288]: wait-interpolation debug: start +[ INFO] [1732710398.567090676]: wait-interccpolation debug: start C-c C-cinterrupt59.B2-irteusgl$ (send *ri* :robot :larm :end-coords) +# +60.B2-irteusgl$ (send *pr2* :larm :end-coords) +# +61.B2-irteusgl$ (progn (send *ri* :state :potentio-vector)(send *ri* :robot :larm :end-coords)) +;; # :joint-angle(88.0514) violate max-angle(88.0) +# +62.B2-irteusgl$ (progn (send *ri* :state :potentio-vector)(v- (send *ri* :robot :larm :end-coords :worldpos) (send *pr2* :larm :end-coords :worldpos))) +;; # :joint-angle(88.0514) violate max-angle(88.0) +#f(0.013516 0.009894 -0.102491) +63.B2-irteusgl$ (progn (send *ri* :state :potentio-vector)(v- (send *ri* :robot :larm :end-coords :worldpos) (send *pr2* :larm :end-coords :worldpos))) +;; # :joint-angle(88.0514) violate max-angle(88.0) +#f(0.013516 0.009894 -0.102381) +64.B2-irteusgl$ (progn (send *ri* :state :potentio-vector)(v- (send *ri* :robot :larm :end-coords :worldpos) (send *pr2* :larm :end-coords :worldpos))) +;; # :joint-angle(88.0514) violate max-angle(88.0) +#f(0.013516 0.009894 -0.102381) +65.B2-irteusgl$ (progn (send *ri* :state :potentio-vector)(v- (send *ri* :robot :larm :end-coords :worldpos) (send *pr2* :larm :end-coords :worldpos))) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.845103 3.68278 -0.278628) +66.B2-irteusgl$ (progn (ros::rate 10)(do-until-key (send *ri* :state :potentio-vector)(v- (send *ri* :robot :larm :end-coords :worldpos) (send *pr2* :larm :end-coords :worldpos)) (ros::sleep))) +;; # :joint-angle(88.0511) violate max-angle(88.0) +;; # :joint-angle(88.0511) violate max-angle(88.0) +;; # :joint-angle(88.0511) violate max-angle(88.0) +;; # :joint-angle(88.0511) violate max-angle(88.0) +;; # :joint-angle(88.0511) violate max-angle(88.0) +;; # :joint-angle(88.0511) violate max-angle(88.0) +;; # :joint-angle(88.0511) violate max-angle(88.0) +;; # :joint-angle(88.0511) violate max-angle(88.0) +;; # :joint-angle(88.0511) violate max-angle(88.0) +;; # :joint-angle(88.0511) violate max-angle(88.0) +;; # :joint-angle(88.0511) violate max-angle(88.0) +;; # :joint-angle(88.0511) violate max-angle(88.0) +;; # :joint-angle(88.0511) violate max-angle(88.0) +;; # :joint-angle(88.0511) violate max-angle(88.0) + +nil +67.B2-irteusgl$ (progn (ros::rate 10)(do-until-key (send *ri* :state :potentio-vector)(print (v- (send *ri* :robot :larm :end-coords :worldpos) (send *pr2* :larm :end-coords :worldpos))) (ros::sleep))) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001507 0.069675 -0.154756) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001507 0.069675 -0.154756) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.006835 0.006749 -0.154756) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.006835 0.006749 -0.154756) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001507 0.069675 -0.154756) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001507 0.069675 -0.154756) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001507 0.069675 -0.154756) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001507 0.069675 -0.154756) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001507 0.069675 -0.154756) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001507 0.069675 -0.154756) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.014577 0.061042 -0.154757) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.021112 0.056726 -0.154756) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.021112 0.056726 -0.154756) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.021112 0.056726 -0.154756) + +nil +68.B2-irteusgl$ (progn (ros::rate 5)(do-until-key (send *ri* :state :potentio-vector)(print (v- (send *ri* :robot :larm :end-coords :worldpos) (send *pr2* :larm :end-coords :worldpos))) (ros::sleep))) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.033119 -0.003056 -0.100951) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.041462 0.059873 -0.100951) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.041462 0.059873 -0.100951) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.041462 0.059873 -0.100951) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.041462 0.059873 -0.100951) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.041462 0.059873 -0.100951) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.033119 -0.003056 -0.100951) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.033119 -0.003056 -0.100951) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.033119 -0.003056 -0.100951) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.033119 -0.003056 -0.100841) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.041462 0.059873 -0.100841) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.033119 -0.003056 -0.100841) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.033119 -0.003056 -0.100841) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.009375 -0.044515 -0.095923) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.017721 0.018412 -0.095923) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.0174 -0.07087 -0.061592) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.0174 -0.07087 -0.061592) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.004332 -0.062235 -0.061595) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.021023 0.06362 -0.061595) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.004332 -0.062235 -0.061595) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.01268 0.000692 -0.061485) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.004021 -0.125161 -0.061485) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.334417 1.98976 -0.096) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.153097 1.25896 -0.169119) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.336802 1.97007 -0.193638) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.417412 2.14387 -0.091097) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.473585 2.43726 -0.095884) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.473585 2.43726 -0.095884) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.410178 2.22826 -0.086089) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.27737 -0.413614 -0.119625) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.530662 -1.67782 -0.114053) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.205116 -0.340282 -0.153521) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.145734 0.733234 -0.085617) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.258769 1.07799 -0.075968) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.264482 1.08667 -0.07597) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.270194 1.09536 -0.075971) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.275906 1.10404 -0.075972) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.531534 -1.99171 -0.079898) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.200453 -0.634994 -0.084813) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.332383 -1.34686 -0.074952) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.185048 -0.656478 -0.089743) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.227112 -0.971024 -0.089633) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.201858 -0.782299 -0.089633) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.186461 -0.803785 -0.094562) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.186461 -0.803785 -0.094562) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.178052 -0.740874 -0.094562) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.154252 -0.699446 -0.099491) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.145851 -0.636532 -0.099491) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.145851 -0.636532 -0.099491) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.142413 -0.598234 -0.158104) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.424898 -0.914253 -0.534041) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.016335 0.802383 -0.524744) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.315117 1.53918 -0.407914) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.828009 3.16092 -0.193113) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.847688 3.14808 -0.193132) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.847688 3.14808 -0.193132) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.800732 3.06488 -0.183227) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.756896 3.02009 -0.232078) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.725302 2.91551 -0.227177) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.601926 2.53566 -0.266209) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.578393 2.49409 -0.261303) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.467882 2.20192 -0.241678) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.392207 2.05268 -0.28558) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.296852 1.73923 -0.270846) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001957 0.540875 -0.192225) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.580519 -1.95967 0.043252) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.733397 -2.66442 0.053304) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.51979 -1.76606 0.028623) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.562314 -2.08047 0.028623) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.45653 -1.70482 0.01382) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.441109 -1.72633 0.008887) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.376355 -1.51778 -0.000979) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.35247 -1.47639 -0.005801) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.317088 -1.41767 -0.010753) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.292836 -1.28305 -0.015723) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.238246 -1.11135 -0.02561) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.231372 -1.02246 -0.025633) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.208324 -0.968051 -0.030571) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.176867 -0.850729 -0.035508) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.171125 -0.842064 -0.035512) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.139694 -0.724733 -0.040446) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.110155 -0.674635 -0.045375) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.108287 -0.607394 -0.045379) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.084499 -0.565958 -0.050304) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.085292 -0.552966 -0.050309) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.076904 -0.490047 -0.050309) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.059659 -0.444284 -0.055236) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.039748 -0.338877 -0.035885) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.039748 -0.338877 -0.035885) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.04628 -0.334556 -0.035887) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.04628 -0.334556 -0.035887) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.04628 -0.334556 -0.035887) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.014148 -0.230186 -0.040802) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.041027 -0.229007 -0.094496) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.041027 -0.229007 -0.094496) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.032666 -0.166084 -0.094496) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.032666 -0.166084 -0.094496) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.032666 -0.166084 -0.094496) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.032666 -0.166084 -0.094496) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.032666 -0.166084 -0.094496) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.032666 -0.166084 -0.094496) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.032666 -0.166084 -0.094496) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.008915 -0.124632 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.000562 -0.061706 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.000562 -0.061706 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.000562 -0.061706 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.000562 -0.061706 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.000562 -0.061706 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.000562 -0.061706 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.000562 -0.061706 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.000562 -0.061706 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.000562 -0.061706 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.000562 -0.061706 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.000562 -0.061706 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.007786 0.00122 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.007786 0.00122 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.007786 0.00122 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.007786 0.00122 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.007786 0.00122 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.007786 0.00122 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001251 0.005537 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001251 0.005537 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001251 0.005537 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001251 0.005537 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001251 0.005537 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001251 0.005537 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001251 0.005537 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001251 0.005537 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.001251 0.005537 -0.099414) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.013369 0.011065 -0.153107) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.013369 0.011065 -0.153107) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.013369 0.011065 -0.153107) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.013369 0.011065 -0.153107) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.037111 -0.03039 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.028766 0.032533 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.028766 0.032533 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.028766 0.032533 -0.148187) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.005027 0.073991 -0.153107) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.005027 0.073991 -0.153107) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.005027 0.073991 -0.153107) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.005027 0.073991 -0.153107) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.005027 0.073991 -0.153107) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.005027 0.073991 -0.153107) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.005027 0.073991 -0.153107) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.005027 0.073991 -0.153107) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015323 0.077138 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015323 0.077138 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015323 0.077138 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015323 0.077138 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015323 0.077138 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015323 0.077138 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015323 0.077138 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015323 0.077138 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015323 0.077138 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015323 0.077138 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015323 0.077138 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015323 0.077138 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015323 0.077138 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015323 0.077138 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015323 0.077138 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015323 0.077138 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.016761 -0.027245 -0.094495) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.016761 -0.027245 -0.094495) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.016761 -0.027245 -0.094495) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.016761 -0.027245 -0.094495) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.016761 -0.027245 -0.094495) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.016761 -0.027245 -0.094495) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.016761 -0.027245 -0.094495) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.016761 -0.027245 -0.094495) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.016761 -0.027245 -0.094495) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.016761 -0.027245 -0.094495) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.016761 -0.027245 -0.094495) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.016761 -0.027245 -0.094495) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.016761 -0.027245 -0.094495) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.016761 -0.027245 -0.094495) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.016761 -0.027245 -0.094495) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.008736 -0.0536 -0.060168) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.008736 -0.0536 -0.060168) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.008736 -0.0536 -0.060168) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(-0.008736 -0.0536 -0.060168) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.023349 0.050783 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.023349 0.050783 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.023349 0.050783 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.015006 -0.012144 -0.065092) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) +;; # :joint-angle(88.0511) violate max-angle(88.0) +#f(0.006981 0.014211 -0.099413) + C-c C-cinterrupt69.B3-irteusgl$ (setq aa (send *ri* :state :potentio-vector)) +;; # :joint-angle(88.0508) violate max-angle(88.0) +#f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196) +70.B3-irteusgl$ (setq cc (send *ri* :state :potentio-vector)) +;; # :joint-angle(88.0508) violate max-angle(88.0) +#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) +71.B3-irteusgl$ (send *ri* :anlge-vector-sequence (list aa bb) (list 1000 1000) :default-controller 0.1 :end-coords-interpolation t :minjerk-interpolation t) +Call Stack (max depth: 20): + 0: at (send *ri* :anlge-vector-sequence (list aa bb) (list 1000 1000) :default-controller 0.1 :end-coords-interpolation t :minjerk-interpolation t) + 1: at sigint-handler + 2: at sigint-handler + 3: at (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (send *ri* :state :potentio-vector) (print (v- (send *ri* :robot :larm :end-coords :worldpos) (send *pr2* :larm :end-coords :worldpos))) (ros::sleep)) + 4: at (let ((#:prog115254469 (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (send *ri* :state :potentio-vector) (print (v- (send *ri* :robot :larm :end-coords :worldpos) (send *pr2* :larm :end-coords :worldpos))) (ros::sleep)))) (progn (let ((strm (car (select-stream (list *standard-input*) 0.1)))) (if strm (read-line strm nil nil)))) #:prog115254469) + 5: at (prog1 (while (and (null (select-stream (list *standard-input*) 1.000000e-07)) (eval t)) (send *ri* :state :potentio-vector) (print (v- (send *ri* :robot :larm :end-coords :worldpos) (send *pr2* :larm :end-coords :worldpos))) (ros::sleep)) (let ((strm (car (select-stream (list *standard-input*) 0.1)))) (if strm (read-line strm nil nil)))) + 6: at (do-until-key-with-check t (send *ri* :state :potentio-vector) (print (v- (send *ri* :robot :larm :end-coords :worldpos) (send *pr2* :larm :end-coords :worldpos))) (ros::sleep)) + 7: at (do-until-key (send *ri* :state :potentio-vector) (print (v- (send *ri* :robot :larm :end-coords :worldpos) (send *pr2* :larm :end-coords :worldpos))) (ros::sleep)) + 8: at (progn (ros::rate 5) (do-until-key (send *ri* :state :potentio-vector) (print (v- (send *ri* :robot :larm :end-coords :worldpos) (send *pr2* :larm :end-coords :worldpos))) (ros::sleep))) + 9: at sigint-handler + 10: at sigint-handler + 11: at (while (ros::ok) (ros::ros-debug "[~A] :wait-for-result ~A ~A" ros::name-space (ros::simple-goal-states-to-string ros::simple-state) (send ros::comm-state :state)) (send self :spin-once) (if (= ros::simple-state ros::*simple-goal-state-done*) (return)) (if (> ros::timeout 0) (let* ((ros::tm (ros::time- (ros::time-now) ros::start))) (if (> (send ros::tm :to-sec) ros::timeout) (return-from :wait-for-result nil)))) (when ros::return-if-server-down (when (= (ros::get-num-publishers ros::result-topic) 0) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : no publishers found for ~A" ros::name-space ros::result-topic) (return-from :wait-for-result nil)) (when (and ros::status-stamp ros::maximum-status-interval (> (send (ros::time- (ros::time-now) ros::status-stamp) :to-sec) ros::maximum-status-interval)) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : status did not received for 5 seconds" ros::name-space) (return-from :wait-for-result nil))) (ros::sleep)) + 12: at (let ((ros::start (ros::time-now)) (ros::result-topic (format nil "~A/result" ros::name-space))) (ros::ros-debug "[~A] :wait-for-result ~A, timeout=~A" ros::name-space (if ros::goal_id (send ros::goal_id :id)) ros::timeout) (unless ros::goal_id (ros::ros-error "[~A] :wait-for-result (return nil when no goal exists)" ros::name-space) (return-from :wait-for-result nil)) (ros::rate ros::wait-rate) (while (ros::ok) (ros::ros-debug "[~A] :wait-for-result ~A ~A" ros::name-space (ros::simple-goal-states-to-string ros::simple-state) (send ros::comm-state :state)) (send self :spin-once) (if (= ros::simple-state ros::*simple-goal-state-done*) (return)) (if (> ros::timeout 0) (let* ((ros::tm (ros::time- (ros::time-now) ros::start))) (if (> (send ros::tm :to-sec) ros::timeout) (return-from :wait-for-result nil)))) (when ros::return-if-server-down (when (= (ros::get-num-publishers ros::result-topic) 0) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : no publishers found for ~A" ros::name-space ros::result-topic) (return-from :wait-for-result nil)) (when (and ros::status-stamp ros::maximum-status-interval (> (send (ros::time- (ros::time-now) ros::status-stamp) :to-sec) ros::maximum-status-interval)) (ros::ros-error "[~A] Unexpected returns from :wait-for-result : status did not received for 5 seconds" ros::name-space) (return-from :wait-for-result nil))) (ros::sleep)) (ros::ros-debug "[~A] :wait-for-result finished ~A" ros::name-space (ros::goal-status-to-string (send self :get-state))) (if (eq (send self :get-state) actionlib_msgs::goalstatus::*preempted*) (ros::ros-warn "[~A] :wait-for-result finished with preempted status" ros::name-space)) (eq (send self :get-state) actionlib_msgs::goalstatus::*succeeded*)) + 13: at (send-all controller-actions :wait-for-result :timeout timeout) + 14: at (send-all controller-actions :wait-for-result :timeout timeout) + 15: at (send-all controller-actions :wait-for-result :timeout timeout) + 16: at (cond (ctype (let ((cacts (gethash ctype controller-table))) (send-all cacts :wait-for-result :timeout timeout))) (t (send-all controller-actions :wait-for-result :timeout timeout))) + 17: at (if (send self :simulation-modep) (while (send self :interpolatingp) (send self :robot-interface-simulation-callback)) (cond (ctype (let ((cacts (gethash ctype controller-table))) (send-all cacts :wait-for-result :timeout timeout))) (t (send-all controller-actions :wait-for-result :timeout timeout)))) + 18: at (send-message self (class . super) :wait-interpolation ctype timeout) + 19: at (send-message self (class . super) :wait-interpolation ctype timeout) + And more... +/opt/ros/noetic/share/euslisp/jskeus/eus/Linux64/bin/irteusgl 0 error: cannot find method :anlge-vector-sequence in (send *ri* :anlge-vector-sequence (list aa bb) (list 1000 1000) :default-controller 0.1 :end-coords-interpolation t :minjerk-interpolation t) +72.E4-irteusgl$ (send *ri* :angle-vector-sequence (list aa bb) (list 1000 1000) :default-controller 0.1 :end-coords-interpolation t :minjerk-interpolation t) +;; # :joint-angle(88.0508) violate max-angle(88.0) +(#f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196)) +73.E4-irteusgl$ (send *ri* :angle-vector-sequence (list aa bb) (list 2000 2000) :default-controller 0.1 :end-coords-interpolation t :minjerk-interpolation t) +;; # :joint-angle(88.0487) violate max-angle(88.0) +(#f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196)) +74.E4-irteusgl$ (send *ri* :angle-vector-sequence (list aa bb aa) (list 2000 2000 2000) :default-controller 0.1 :end-coords-interpolation t :minjerk-interpolation t) +[ERROR] [1732711051.268615114]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711051.268667460]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732711051.273283960]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711051.273343153]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +;; # :joint-angle(88.0487) violate max-angle(88.0) +(#f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196)) +75.E4-irteusgl$ (send *ri* :angle-vector-sequence (list aa bb aa) (list 2000 2000 2000) :default-controller 0.1 :end-coords-interpolation t :minjerk-interpolation nil) +[ERROR] [1732711056.866193957]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711056.866268752]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732711056.869291702]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711056.869352434]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +;; # :joint-angle(88.0487) violate max-angle(88.0) +(#f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196)) +76.E4-irteusgl$ sene *ri* :angle-vector aa 1000 +sh: 1: sene: not found +32512 +77.E4-irteusgl$ send *ri* :angle-vector aa 1000 +[ERROR] [1732711077.262442297]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711077.262492795]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732711077.262832780]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711077.262858543]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +#f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196) +78.E4-irteusgl$ send *ri* :angle-vector bb 1000 +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) +79.E4-irteusgl$ send *ri* :angle-vector aa 1000 +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +#f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196) +80.E4-irteusgl$ send *ri* :angle-vector bb 1000 +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) +81.E4-irteusgl$ send *ri* :angle-vector aa 1000 +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +#f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196) +82.E4-irteusgl$ (send *ri* :angle-vector-sequence (list aa bb aa) (list 2000 2000 2000) :default-controller 0.1 :end-coords-interpolation t :minjerk-interpolation nil) +;; # :joint-angle(88.0487) violate max-angle(88.0) +(#f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196)) +83.E4-irteusgl$ (send *ri* :angle-vector-sequence (list aa aa bb aa) (list 2000 2000 2000 2000) :default-controller 0.1 :end-coords-interpolation t :minjerk-interpolation nil) +[ERROR] [1732711119.276356486]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711119.276410178]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732711119.276810605]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711119.276838936]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +;; # :joint-angle(88.0487) violate max-angle(88.0) +(#f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196) #f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196)) +84.E4-irteusgl$ send *ri* :angle-vector aa 1000 +[ERROR] [1732711135.681056334]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711135.681114229]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732711135.681498470]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711135.681540128]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +#f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196) +85.E4-irteusgl$ send *ri* :angle-vector bb 1000 +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +;; # :joint-angle(88.0487) violate max-angle(88.0) +#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) +86.E4-irteusgl$ (send *ri* :angle-vector-sequence (list bb aa) (list 2000 2000) :default-controller 0.1 :end-coords-interpolation t :minjerk-interpolation nil) +;; # :joint-angle(88.0487) violate max-angle(88.0) +(#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196)) +87.E4-irteusgl$ (send *ri* :angle-vector-sequence (list bb aa) (list 2000 2000) :default-controller 0.1 :end-coords-interpolation t :minjerk-interpolation nil) +[ERROR] [1732711160.420299274]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711160.420389242]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732711160.421306468]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711160.421373502]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +;; # :joint-angle(88.0487) violate max-angle(88.0) +(#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196)) +88.E4-irteusgl$ (send *ri* :angle-vector-sequence (list bb aa) (list 2000 2000) :default-controller 0.1 :end-coords-interpolatino-steps 20 :end-coords-interpolation t :minjerk-interpolation nil) +[ERROR] [1732711177.712880211]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711177.712960418]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732711177.716180808]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711177.716217626]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +;; # :joint-angle(88.0487) violate max-angle(88.0) +(#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196)) +89.E4-irteusgl$ (send *ri* :angle-vector-sequence (list bb aa) (list 2000 2000) :default-controller 0.1 :end-coords-interpolatino-steps 20 :end-coords-interpolation t :minjerk-interpolation nil) +[ERROR] [1732711181.888952975]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711181.889059400]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732711181.897204042]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711181.897312306]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +;; # :joint-angle(88.0487) violate max-angle(88.0) +(#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196)) +90.E4-irteusgl$ (send *ri* :angle-vector-sequence (list aa bb aa) (list 1000 2000 2000) :default-controller 0.1 :end-coords-interpolatino-steps 20 :end-coords-interpolation t :minjerk-interpolation nil) +[ERROR] [1732711191.260845151]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711191.260883427]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732711191.263097596]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711191.263124971]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +;; # :joint-angle(88.0484) violate max-angle(88.0) +(#f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196)) +91.E4-irteusgl$ (send *ri* :angle-vector-sequence (list aa bb aa) (list 1000 2000 2000) :default-controller 0.0 :end-coords-interpolatino-steps 20 :end-coords-interpolation t :minjerk-interpolation nil) +[ERROR] [1732711212.817027655]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711212.817089284]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +;; # :joint-angle(88.0484) violate max-angle(88.0) +(#f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196)) +92.E4-irteusgl$ (send *ri* :angle-vector-sequence (list aa bb aa) (list 1000 2000 2000) :default-controller 0.0 :end-coords-interpolatino-steps 100 :end-coords-interpolation t :minjerk-interpolation nil) +[ERROR] [1732711237.038529960]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711237.038638582]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732711237.041440875]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711237.041584094]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +;; # :joint-angle(88.0484) violate max-angle(88.0) +(#f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196)) +93.E4-irteusgl$ (send *ri* :angle-vector-sequence (list aa bb aa) (list 5000 5000 5000) :default-controller 0.0 :end-coords-interpolatino-steps 100 :end-coords-interpolation t :minjerk-interpolation nil) +[ERROR] [1732711248.779854347]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711248.779906603]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +;; # :joint-angle(88.0484) violate max-angle(88.0) +(#f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.632 8.79099 6.49026 87.6719 -42.1939 96.0892 -86.7538 236.55 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 -0.00647 44.196)) +94.E4-irteusgl$ (setq cc (send *ri* :state :potentio-vector)) +[ERROR] [1732711277.052656644]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711277.052698973]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +;; # :joint-angle(88.0484) violate max-angle(88.0) +#f(232.581 8.79099 6.49026 87.6719 -42.1939 96.0958 -86.7538 236.55 -7.38971 40.1076 -10.7297 -79.8852 132.477 -41.491 156.975 -0.09647 46.158) +95.E4-irteusgl$ (send *ri* :angle-vector-sequence (list bb cc) (list 5000 5000) :default-controller 0.0 :end-coords-interpolatino-steps 10 :end-coords-interpolation t :minjerk-interpolation nil) +;; # :joint-angle(88.0484) violate max-angle(88.0) +(#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.581 8.79099 6.49026 87.6719 -42.1939 96.0958 -86.7538 236.55 -7.38971 40.1076 -10.7297 -79.8852 132.477 -41.491 156.975 -0.09647 46.158)) +96.E4-irteusgl$ (send *ri* :angle-vector-sequence (list bb cc) (list 5000 10000) :default-controller 0.0 :end-coords-interpolatino-steps 10 :end-coords-interpolation t :minjerk-interpolation nil) +[ERROR] [1732711306.539983721]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711306.540078744]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +[ERROR] [1732711306.544237777]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711306.544299266]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +;; # :joint-angle(88.0484) violate max-angle(88.0) +(#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.581 8.79099 6.49026 87.6719 -42.1939 96.0958 -86.7538 236.55 -7.38971 40.1076 -10.7297 -79.8852 132.477 -41.491 156.975 -0.09647 46.158)) +97.E4-irteusgl$ (send *ri* :angle-vector-sequence (list bb cc) (list 5000 10000) :default-controller 0.0 :end-coords-interpolatino-steps 3 :end-coords-interpolation t :minjerk-interpolation nil) +;; # :joint-angle(88.0481) violate max-angle(88.0) +(#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.581 8.79099 6.49026 87.6719 -42.1939 96.0958 -86.7538 236.55 -7.38971 40.1076 -10.7297 -79.8852 132.477 -41.491 156.975 -0.09647 46.158)) +98.E4-irteusgl$ (send *ri* :angle-vector-sequence (list bb cc) (list 5000 10000) :default-controller 0.0 :end-coords-interpolatino-steps 3 :end-coords-interpolation t :minjerk-interpolation nil) +;; # :joint-angle(88.0478) violate max-angle(88.0) +(#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.581 8.79099 6.49026 87.6719 -42.1939 96.0958 -86.7538 236.55 -7.38971 40.1076 -10.7297 -79.8852 132.477 -41.491 156.975 -0.09647 46.158)) +99.E4-irteusgl$ (send *ri* :angle-vector-sequence (list bb cc) (list 5000 10000) :default-controller 0.0 :end-coords-interpolatino-steps 3 :end-coords-interpolation t :minjerk-interpolation nil) +[ERROR] [1732711327.105290188]: joint trajectory status: (4 . actionlib_msgs::goalstatus::*aborted*) + +[ERROR] [1732711327.105360260]: error_code: (-5 . GOAL_TOLERANCE_VIOLATED) + +;; # :joint-angle(88.0475) violate max-angle(88.0) +(#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.581 8.79099 6.49026 87.6719 -42.1939 96.0958 -86.7538 236.55 -7.38971 40.1076 -10.7297 -79.8852 132.477 -41.491 156.975 -0.09647 46.158)) +100.E4-irteusgl$ (send *ri* :angle-vector-sequence (list bb bb cc) (list 5000 1000 10000) :default-controller 0.0 :end-coords-interpolatino-steps 3 :end-coords-interpolation t :minjerk-interpolation nil) +;; # :joint-angle(88.0472) violate max-angle(88.0) +(#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.581 8.79099 6.49026 87.6719 -42.1939 96.0958 -86.7538 236.55 -7.38971 40.1076 -10.7297 -79.8852 132.477 -41.491 156.975 -0.09647 46.158)) +101.E4-irteusgl$ (send *ri* :angle-vector-sequence (list bb bb cc) (list 5000 1000 10000) :default-controller 0.0 :end-coords-interpolatino-steps 3 :end-coords-interpolation t :minjerk-interpolation nil) +;; # :joint-angle(88.0466) violate max-angle(88.0) +(#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.581 8.79099 6.49026 87.6719 -42.1939 96.0958 -86.7538 236.55 -7.38971 40.1076 -10.7297 -79.8852 132.477 -41.491 156.975 -0.09647 46.158)) +102.E4-irteusgl$ (send *ri* :angle-vector-sequence (list bb bb cc) (list 5000 1000 10000) :default-controller 0.0 :end-coords-interpolatino-steps 3 :end-coords-interpolation t :minjerk-interpolation t) +;; # :joint-angle(88.046) violate max-angle(88.0) +(#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.581 8.79099 6.49026 87.6719 -42.1939 96.0958 -86.7538 236.55 -7.38971 40.1076 -10.7297 -79.8852 132.477 -41.491 156.975 -0.09647 46.158)) +103.E4-irteusgl$ (send *ri* :angle-vector-sequence (list bb bb cc) (list 5000 1000 10000) :default-controller 0.0 :end-coords-interpolatino-steps 5 :end-coords-interpolation t :minjerk-interpolation t) +;; # :joint-angle(88.0454) violate max-angle(88.0) +(#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.581 8.79099 6.49026 87.6719 -42.1939 96.0958 -86.7538 236.55 -7.38971 40.1076 -10.7297 -79.8852 132.477 -41.491 156.975 -0.09647 46.158)) +104.E4-irteusgl$ (send *ri* :angle-vector-sequence (list bb bb cc) (list 5000 1000 10000) :default-controller 0.0 :end-coords-interpolatino-steps 5 :end-coords-interpolation t :minjerk-interpolation t) +;; # :joint-angle(88.0448) violate max-angle(88.0) +(#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.581 8.79099 6.49026 87.6719 -42.1939 96.0958 -86.7538 236.55 -7.38971 40.1076 -10.7297 -79.8852 132.477 -41.491 156.975 -0.09647 46.158)) +105.E4-irteusgl$ (send *ri* :angle-vector-sequence (list bb bb cc) (list 5000 1000 100000) :default-controller 0.0 :end-coords-interpolatino-steps 5 :end-coords-interpolation t :minjerk-interpolation t) +;; # :joint-angle(88.0439) violate max-angle(88.0) +(#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.581 8.79099 6.49026 87.6719 -42.1939 96.0958 -86.7538 236.55 -7.38971 40.1076 -10.7297 -79.8852 132.477 -41.491 156.975 -0.09647 46.158)) +106.E4-irteusgl$ (send *ri* :angle-vector-sequence (list bb bb cc) (list 5000 1000 100000) :default-controller 0.0 :end-coords-interpolatino-steps 5 :end-coords-interpolation t :minjerk-interpolation t) +;; # :joint-angle(88.0436) violate max-angle(88.0) + + + + +(#f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.633 18.3151 6.49511 87.6719 -42.2022 96.0892 -86.7563 236.552 -6.72469 54.6823 -44.8618 -79.8189 132.546 -41.5658 157.039 0.00553 44.196) #f(232.581 8.79099 6.49026 87.6719 -42.1939 96.0958 -86.7538 236.55 -7.38971 40.1076 -10.7297 -79.8852 132.477 -41.491 156.975 -0.09647 46.158)) +107.E4-irteusgl$ nil +107.E4-irteusgl$ nil +107.E4-irteusgl$ nil +107.E4-irteusgl$ nil +107.E4-irteusgl$ +nil +107.E4-irteusgl$ [ERROR] [1732711617.793685655]: couldn't resolve publisher host [pr1040] +[ERROR] [1732711617.794132785]: couldn't resolve publisher host [pr1040] +[ERROR] [1732711619.841304399]: couldn't resolve publisher host [pr1040] +[ERROR] [1732711625.985323275]: couldn't resolve publisher host [pr1040s] +[ERROR] [1732711625.985720657]: couldn't resolve publisher host [pr1040s] +[ERROR] [1732711673.089371555]: couldn't resolve publisher host [pr1040s] +[ERROR] [1732711673.089813557]: couldn't resolve publisher host [pr1040s] +[ERROR] [1732711673.090257609]: couldn't resolve publisher host [pr1040] +[ERROR] [1732711673.090551092]: couldn't resolve publisher host [pr1040] +[ERROR] [1732711673.090919110]: couldn't resolve publisher host [pr1040] +[ERROR] [1732711673.091259541]: couldn't resolve publisher host [pr1040] +[ERROR] [1732711673.091715780]: couldn't resolve publisher host [pr1040] +[ERROR] [1732711673.091993119]: couldn't resolve publisher host [pr1040] +[ERROR] [1732711673.092331943]: couldn't resolve publisher host [pr1040] +[ERROR] [1732711673.093005780]: couldn't resolve publisher host [pr1040] +[ERROR] [1732711673.093381939]: couldn't resolve publisher host [pr1040] diff --git a/jsk_2024_10_semi/surgery_motion_1.l b/jsk_2024_10_semi/surgery_motion_1.l new file mode 100755 index 000000000..5abac9189 --- /dev/null +++ b/jsk_2024_10_semi/surgery_motion_1.l @@ -0,0 +1,291 @@ +#!/usr/bin/env roseus +;chmod u+x ./surgery_motion_1.l --> ./surgery_motion_1.l ;; change from ki00119 Michi-Tsubaki + +;;Okada-seisei seminar homework achievement ;;last editted oct 29 ;; Michi-Tsubaki + +;; +;;Thiscode is for trying to make unique motion for sewing something. Still Trying + + +;;Load packages for using PR2 model and PR2 robot in real. +(require "package://pr2eus/pr2.l") +(require "package://pr2eus/pr2-utils.l") +(require "package://pr2eus/pr2-interface.l") +(require "package://pr2eus/speak.l") ;;use :speak-jp ;;https://github.com/wkentaro/jsk_pr2eus/blob/fad0691e0131275b76568a68096c6c9f6eead13e/pr2eus/speak.l#L4 +(load "models/arrow-object.l") + + +;;Making PR2 object +(if (not (boundp '*pr2*)) (pr2-init)) + + +;;Setting cube as a desk for surgery. +(setq *desk* (make-cube 500 500 800)) +(send *desk* :translate (float-vector 700 0 400)) +(send *desk* :set-color :brown) +;[memo] (send *desk* :translate (float-vector 500 0 80)) ;;CAUTION!!(by Michi-Tsubaki)<-parameter that make robot motion NOT converge + +;;Setting cylinder as needle. +(setq *needle* (make-cylinder 2 40)) +(send *needle* :translate (float-vector 700 0 850)) +(send *needle* :set-color :yellow) +(send *needle* :rotate #d90 :x) + +;;Set hampen +(setq *hampen* (make-cube 60 60 30)) +(send *hampen* :translate (float-vector 700 0 830)) +;(send *hampen* :translate (v+ (float-vector 0 0 310) (send *desk* :pos)) +(send *hampen* :set-color :white) + +;;Set coordination. +(send *desk* :put :left-coords + (make-cascoords + :coords (send (send *desk* :copy-worldcoords) :translate (float-vector 0 0 500)) + :parent *desk*)) +;;Set coordination. +(send *needle* :put :left-coords + (make-cascoords + :coords (send (send *needle* :copy-worldcoords) :translate (float-vector 0 0 -5)) + :parent *needle*)) ;;質問:parent座標をpr2に設定したら収束しなくなった ;;still confusing + +(send *pr2* :larm :inverse-kinematics + (send (send *needle* :get :left-coords) :copy-worldcoords) + :rotation-axis :z) + + +;;Show Worldrecord +(setq *arrow* (arrow)) +(send *arrow* :copy-worldcoords) + +;;Show all objects in viewer. +(objects (list *pr2* *desk* *needle* *hampen*)) ;;Dont forget to add all items + + + +;Setting Initial Pose +(send *ri* :speak-jp "初期姿勢に戻ります" :wait t) +(send *ri* :start-grasp :arms :wait t) +(send *pr2* :reset-pose) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +(unix:sleep 1) +(send *ri* :speak-jp "右手を開きます。スポンジをもたせてください。") +(send *ri* :stop-grasp :rarm :wait t) +(send *irtviewer* :draw-objects) +(unix:sleep 1) +(send *ri* :start-grasp :rarm :wait t) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +(unix:sleep 1) +(send *ri* :speak-jp "左手を開きます。針を持たせてください。") +(send *ri* :stop-grasp :larm :wait t) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +(unix:sleep 1) +(send *ri* :start-grasp :larm :wait t) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +(unix:sleep 1) +(send *ri* :speak-jp "これから針を持って作業します.離れてください.") +(unix:sleep 2) + +;Putting arms above each side of the desk +;;Setting the right arm and the left arm to the initial position. +;;USING INVERSE KINEMATICS +(send *pr2* :larm :inverse-kinematics + (send (send *desk* :get :left-coords) :copy-worldcoords) + :rotation-axis :z) +;(send *pr2* :rarm :inverse-kinematics +; (send (send *desk* :get :left-coords) :copy-worldcoords) +; :rotation-axis :z) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + + +;;Graspe needle +;;1. Reach +(send *pr2* :larm :inverse-kinematics + (send (send *needle* :get :left-coords) :copy-worldcoords) + :rotation-axis :z) +(send *pr2* :larm :end-coords :assoc *needle*) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + +;;2. Graspe +;(send *ri* :start-grasp :larm) +;(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +;(send *ri* :wait-interpolation) +;(send *irtviewer* :draw-objects) +;(unix:sleep 1) + + + +;;Stitch with the left hand +(send *pr2* + :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0.0 -10.0 -10.0)) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :debug-view t) +(send *ri* :angle-vector (send *pr2* :angle-vector) 3000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + + +(send *pr2* :larm :wrist-p :joint-angle -100) +(send *pr2* + :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector 50.0 20.0 0.0)) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :debug-view t) +(send *ri* :angle-vector (send *pr2* :angle-vector) 3000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + + +(send *pr2* + :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0.0 -12.0 20.0)) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :debug-view t) +(send *ri* :angle-vector (send *pr2* :angle-vector) 3000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + + + +(send *pr2* :larm :wrist-p :joint-angle -80) +(send *pr2* + :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector -35.0 -10.0 5.0)) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :debug-view t) +(send *ri* :angle-vector (send *pr2* :angle-vector) 3000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + + +(send *pr2* :larm :elbow-r :joint-angle 95) +(send *pr2* :larm :shoulder-r :joint-angle 95) +(send *pr2* + :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0.0 2.0 2.0)) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :debug-view t) +(send *ri* :angle-vector (send *pr2* :angle-vector) 3000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + + + +;;Switching hands +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + + +(send *pr2* :rarm :inverse-kinematics + (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector -10.0 0 0) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :rarm :end-coords) :parent)) + :rotation-axis :x)) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + + +;(send *ri* :stop-grasp :rarm) +;(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +;(send *ri* :wait-interpolation) +;(send *irtviewer* :draw-objects) + + +;;Grasping needle with right hand +(progn (send (send *needle* :copy-worldcoords) :draw-on :size 50) ;;debug + (setq *next-needle-coords* (send (send *needle* :copy-worldcoords) :transform (make-coords :pos #f(0 0 80) :rpy (float-vector 0 0 0)))) + (send *next-needle-coords* :draw-on :flush t :size 100) ;; debug + (send *pr2* :rarm :inverse-kinematics (send *next-needle-coords* :copy-worldcoords) :rotation-axis t :look-at-target t :debug-view t) + ) +;(send *pr2* :rarm :inverse-kinematics +; (send (send *needle* :get :left-coords) :copy-worldcoords) +; :rotation-axis :y) ;;yだと向きが違うき +(send (send *needle* :parent) :dissoc *needle*) +(send *pr2* :rarm :end-coords :assoc *needle*) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + +(progn (send (send *needle* :copy-worldcoords) :draw-on :size 50) ;;debug + (setq *next-needle-coords* (send (send *needle* :copy-worldcoords) :transform (make-coords :pos #f(0 0 40) :rpy (float-vector 0 0 0)))) + (send *next-needle-coords* :draw-on :flush t :size 100) ;; debug + (send *pr2* :rarm :inverse-kinematics (send *next-needle-coords* :copy-worldcoords) :rotation-axis t :look-at-target t :debug-view t) + ) +;(send *pr2* :rarm :inverse-kinematics +; (send (send *needle* :get :left-coords) :copy-worldcoords) +; :rotation-axis :y) ;;yだと向きが違うき +(send (send *needle* :parent) :dissoc *needle*) +(send *pr2* :rarm :end-coords :assoc *needle*) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + + + +(send *ri* :stop-grasp :larm) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + + + +;(send *pr2* :larm :inverse-kinematics +; (send (send *desk* :get :left-coords) :copy-worldcoords) +; :rotation-axis t) +;(send (send *needle* :parent) :dissoc *needle*) +;(send *pr2* :rarm :end-coords :assoc *needle*) +;(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +;(send *ri* :wait-interpolation) +;(send *irtviewer* :draw-objects) + +(send *pr2* :rarm :inverse-kinematics + (send (send *desk* :get :left-coords) :copy-worldcoords) + :rotation-axis t) +(send (send *needle* :parent) :dissoc *needle*) +(send *pr2* :rarm :end-coords :assoc *needle*) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +;(send *irtviewer* :draw-objects) + + + + +;(send *pr2* :larm :inverse-kinematics +; (send (send *needle* :get :left-coords) :copy-worldcoords) +; :rotation-axis :z) +;(send *pr2* :larm :end-coords :assoc *needle*) +;(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +;(send *ri* :wait-interpolation) +;(send *irtviewer* :draw-objects) + + +;;how to dwaw coordination arrow +;(send (send (send *needle* :get :left-coords) :copy-worldcoords) :draw-on :flush t) + diff --git a/jsk_2024_10_semi/surgery_motion_2.l b/jsk_2024_10_semi/surgery_motion_2.l new file mode 100755 index 000000000..46c26567b --- /dev/null +++ b/jsk_2024_10_semi/surgery_motion_2.l @@ -0,0 +1,314 @@ +#!/usr/bin/env roseus +;chmod u+x ./surgery_motion_1.l --> ./surgery_motion_1.l ;; change from ki00119 Michi-Tsubaki + +;;Okada-seisei seminar homework achievement ;;last editted oct 29 ;; Michi-Tsubaki + +;; +;;Thiscode is for trying to make unique motion for sewing something. Still Trying + + +;;Load packages for using PR2 model and PR2 robot in real. +(require "package://pr2eus/pr2.l") +(require "package://pr2eus/pr2-utils.l") +(require "package://pr2eus/pr2-interface.l") +(require "package://pr2eus/speak.l") ;;use :speak-jp +;;https://github.com/wkentaro/jsk_pr2eus/blob/fad0691e0131275b76568a68096c6c9f6eead13e/pr2eus/speak.l#L4 +(load "models/arrow-object.l") + + +;;Making PR2 object +(if (not (boundp '*pr2*)) (pr2-init)) + + +;;Setting cube as a desk for surgery. +(setq *desk* (make-cube 500 500 750)) +(send *desk* :translate (float-vector 700 0 375)) +(send *desk* :set-color :brown) +;[memo] (send *desk* :translate (float-vector 500 0 80)) ;;CAUTION!!(by Michi-Tsubaki)<-parameter that make robot motion NOT converge + + +;;Setting cylinder as needle. +(setq *needle* (make-cylinder 2 40)) +(send *needle* :translate (float-vector 700 0 800)) +(send *needle* :set-color :yellow) +(send *needle* :rotate #d90 :x) + + +;;Set hampen +(setq *hampen* (make-cube 60 60 24)) +(send *hampen* :translate (float-vector 750 0 762)) +;(send *hampen* :translate (v+ (float-vector 0 0 310) (send *desk* :pos)) +(send *hampen* :set-color :white) + +;;Set coordination. +(send *desk* :put :left-coords + (make-cascoords + :coords (send (send *desk* :copy-worldcoords) :translate (float-vector 0 0 500)) + :parent *desk*)) +;;Set coordination. +(send *needle* :put :left-coords + (make-cascoords + :coords (send (send *needle* :copy-worldcoords) :translate (float-vector 0 0 -5)) + :parent *needle*)) ;;質問:parent座標をpr2に設定したら収束しなくなった ;;still confusing + +(send *pr2* :larm :inverse-kinematics + (send (send *needle* :get :left-coords) :copy-worldcoords) + :rotation-axis :z) + + +;;Show Worldrecord +(setq *arrow* (arrow)) +(send *arrow* :copy-worldcoords) + +;;Show all objects in viewer. +(objects (list *pr2* *desk* *needle* *hampen*)) ;;Dont forget to add all items + + + +;Setting Initial Pose +(send *ri* :speak-jp "初期姿勢に戻ります" :wait t) +(send *ri* :start-grasp :arms :wait t) +(send *pr2* :reset-pose) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +(unix:sleep 1) +(send *ri* :speak-jp "右手を開きます。スポンジをもたせてください。") +(send *ri* :stop-grasp :rarm :wait t) +(send *irtviewer* :draw-objects) +(unix:sleep 1) +(send *ri* :start-grasp :rarm :wait t) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +(unix:sleep 1) +(send *ri* :speak-jp "左手を開きます。針を持たせてください。") +(send *ri* :stop-grasp :larm :wait t) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +(unix:sleep 1) +(send *ri* :start-grasp :larm :wait t) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +(unix:sleep 1) +(send *ri* :speak-jp "これから針を持って作業します.離れてください.") +(unix:sleep 2) + +;Putting arms above each side of the desk +;;Setting the right arm and the left arm to the initial position. +;;USING INVERSE KINEMATICS +(send *pr2* :larm :inverse-kinematics + (send (send *desk* :get :left-coords) :copy-worldcoords) + :rotation-axis :z) +;(send *pr2* :rarm :inverse-kinematics +; (send (send *desk* :get :left-coords) :copy-worldcoords) +; :rotation-axis :z) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +;(unix:sleep 1) + + +;;Graspe needle +;;1. Reach +(send *pr2* :larm :inverse-kinematics + (send (send *needle* :get :left-coords) :copy-worldcoords) + :rotation-axis :z) +(send *pr2* :larm :end-coords :assoc *needle*) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + +(unix:sleep 1) + +;(progn (send (send *needle* :copy-worldcoords) :draw-on :size 50) ;;debug +; (setq *next-needle-coords* (send (send *needle* :copy-worldcoords) +; :transform (make-coords :pos #f(-20 0 0) :rpy (float-vector 0 0 0)))) +; (send *next-needle-coords* :draw-on :flush t :size 100) ;; debug +; (send *pr2* :larm :inverse-kinematics +; (send *next-needle-coords* :copy-worldcoords) +; :rotation-axis :z +; :look-at-target nil +; :debug-view t) +; ) +;(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +;(send *ri* :wait-interpolation) +;(send *irtviewer* :draw-objects) + + + +;;2. Graspe +;(send *ri* :start-grasp :larm) +;(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +;(send *ri* :wait-interpolation) +;(send *irtviewer* :draw-objects) +;(unix:sleep 1) + + + +;;Stitch with the left hand +(send *pr2* + :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector 50.0 -10.0 -50.0)) ;;xが前後方向になっている + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :debug-view t) +(send *ri* :angle-vector (send *pr2* :angle-vector) 3000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + + +;(send *pr2* :larm :wrist-p :joint-angle -100) + +#| +(send *pr2* + :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector 50.0 25.0 0.0)) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :debug-view t) +(send *ri* :angle-vector (send *pr2* :angle-vector) 3000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) +|# + + + +(send *pr2* + :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0.0 -30.0 5.0)) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis :z + :debug-view t) +(send *ri* :angle-vector (send *pr2* :angle-vector) 3000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + + +(defun + +#| +(send *pr2* :larm :wrist-p :joint-angle -80) + +(send *pr2* + :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector -35.0 0.0 5.0)) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :debug-view t) +(send *ri* :angle-vector (send *pr2* :angle-vector) 3000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + + +;(send *pr2* :larm :elbow-r :joint-angle 100) +;(send *pr2* :larm :shoulder-r :joint-angle 95) +(send *pr2* + :inverse-kinematics (send (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector 0.0 2.0 2.0)) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :larm :end-coords) :parent)) + :rotation-axis t + :debug-view t) +(send *ri* :angle-vector (send *pr2* :angle-vector) 3000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + +#| + +;;Switching hands +(send *pr2* :rarm :shoulder-p :joint-angle -20) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + + +(send *pr2* :rarm :inverse-kinematics + (send (send *needle* :get :left-coords) :copy-worldcoords) + :translate (float-vector -10.0 0 0) + :move-target (send *needle* :get :left-coords) + :link-list (send *pr2* :link-list (send (send *pr2* :rarm :end-coords) :parent)) + :rotation-axis :x)) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + + +;(send *ri* :stop-grasp :rarm) +;(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +;(send *ri* :wait-interpolation) +;(send *irtviewer* :draw-objects) + + +;;Grasping needle with right hand +(progn (send (send *needle* :copy-worldcoords) :draw-on :size 50) ;;debug + (setq *next-needle-coords* (send (send *needle* :copy-worldcoords) :transform (make-coords :pos #f(0 0 80) :rpy (float-vector 0 0 0)))) + (send *next-needle-coords* :draw-on :flush t :size 100) ;; debug + (send *pr2* :rarm :inverse-kinematics (send *next-needle-coords* :copy-worldcoords) :rotation-axis t :look-at-target t :debug-view t) + ) +;(send *pr2* :rarm :inverse-kinematics +; (send (send *needle* :get :left-coords) :copy-worldcoords) +; :rotation-axis :y) ;;yだと向きが違うき +(send (send *needle* :parent) :dissoc *needle*) +(send *pr2* :rarm :end-coords :assoc *needle*) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + +(progn (send (send *needle* :copy-worldcoords) :draw-on :size 50) ;;debug + (setq *next-needle-coords* (send (send *needle* :copy-worldcoords) :transform (make-coords :pos #f(0 0 40) :rpy (float-vector 0 0 0)))) + (send *next-needle-coords* :draw-on :flush t :size 100) ;; debug + (send *pr2* :rarm :inverse-kinematics (send *next-needle-coords* :copy-worldcoords) :rotation-axis t :look-at-target t :debug-view t) + ) +;(send *pr2* :rarm :inverse-kinematics +; (send (send *needle* :get :left-coords) :copy-worldcoords) +; :rotation-axis :y) ;;yだと向きが違うき +(send (send *needle* :parent) :dissoc *needle*) +(send *pr2* :rarm :end-coords :assoc *needle*) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + + + +(send *ri* :stop-grasp :larm) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + + + +;(send *pr2* :larm :inverse-kinematics +; (send (send *desk* :get :left-coords) :copy-worldcoords) +; :rotation-axis t) +;(send (send *needle* :parent) :dissoc *needle*) +;(send *pr2* :rarm :end-coords :assoc *needle*) +;(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +;(send *ri* :wait-interpolation) +;(send *irtviewer* :draw-objects) + +(send *pr2* :rarm :inverse-kinematics + (send (send *desk* :get :left-coords) :copy-worldcoords) + :rotation-axis t) +(send (send *needle* :parent) :dissoc *needle*) +(send *pr2* :rarm :end-coords :assoc *needle*) +(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +(send *ri* :wait-interpolation) +;(send *irtviewer* :draw-objects) + + + + +;(send *pr2* :larm :inverse-kinematics +; (send (send *needle* :get :left-coords) :copy-worldcoords) +; :rotation-axis :z) +;(send *pr2* :larm :end-coords :assoc *needle*) +;(send *ri* :angle-vector (send *pr2* :angle-vector) 1000) +;(send *ri* :wait-interpolation) +;(send *irtviewer* :draw-objects) + + +;;how to dwaw coordination arrow +;(send (send (send *needle* :get :left-coords) :copy-worldcoords) :draw-on :flush t) diff --git a/jsk_2024_10_semi/surgery_trajectory_1.l b/jsk_2024_10_semi/surgery_trajectory_1.l new file mode 100755 index 000000000..753605758 --- /dev/null +++ b/jsk_2024_10_semi/surgery_trajectory_1.l @@ -0,0 +1,106 @@ +;;Okada-seisei seminar +;;Surgery-method +;;last editted Nov 12 ;; Michi-Tsubaki + +;; +;;This program is for trying to make unique motion for sewing sponge. Still Trying + + +;;Load packages for using PR2 model and PR2 robot in real. +(require "package://pr2eus/pr2.l") +(require "package://pr2eus/pr2-utils.l") +(require "package://pr2eus/pr2-interface.l") +(require "package://pr2eus/speak.l") ;;pkg for speaking + + +;;Define Trajectory Point (7) +(defvar *tp1* nil) +(defvar *tp2* nil) +(defvar *tp3* nil) +(defvar *tp4* nil) +(defvar *tp5* nil) +(defvar *tp6* nil) +(defvar *tp7* nil) + +;;Define set-trajectory function +(defun set-trajectory (x) + (let ((prev-pos (float-vector x -20 40))) ; 最初の座標を原点に設定 + ;; tp1 + (setq *tp1* (make-cube 2 2 2)) + (send *tp1* :translate (v- (float-vector 0 5 0) (send *center* :pos))) + (send *tp1* :rotate #d90 :x) + (send *tp1* :set-color :red) + (setq prev-pos (send *tp1* :pos)) + ;; tp2 + (setq *tp2* (make-cube 2 2 2)) + (send *tp2* :translate (v- (float-vector 0 5 0) prev-pos)) + (send *tp2* :rotate #d90 :x) + (send *tp2* :set-color :red) + (setq prev-pos (send *tp2* :pos)) + ;; tp3 + (setq *tp3* (make-cube 2 2 2)) + (send *tp3* :translate (v- (float-vector 0 5 0) prev-pos)) + (send *tp3* :rotate #d90 :x) + (send *tp3* :set-color :red) + (setq prev-pos (send *tp3* :pos)) + ;; tp4 + (setq *tp4* (make-cube 2 2 2)) + (send *tp4* :translate (v- (float-vector 0 5 0) prev-pos)) + (send *tp4* :rotate #d90 :x) + (send *tp4* :set-color :red) + (setq prev-pos (send *tp4* :pos)) + ;; tp5 + (setq *tp5* (make-cube 2 2 2)) + (send *tp5* :translate (v- (float-vector 0 5 0) prev-pos)) + (send *tp5* :rotate #d90 :x) + (send *tp5* :set-color :red) + (setq prev-pos (send *tp5* :pos)) + ;; tp6 + (setq *tp6* (make-cube 2 2 2)) + (send *tp6* :translate (v- (float-vector 0 5 0) prev-pos)) + (send *tp6* :rotate #d90 :x) + (send *tp6* :set-color :red) + (setq prev-pos (send *tp6* :pos)) + ;; tp7 + (setq *tp7* (make-cube 2 2 2)) + (send *tp7* :translate (v- (float-vector 0 5 0) prev-pos)) + (send *tp7* :rotate #d90 :x) + (send *tp7* :set-color :red) + (setq prev-pos (send *tp7* :pos)))) + +(set-trajectory 0) + +;;Set Center of a Table +(setq *center* (make-cube 10 10 10)) +(send *center* :translate (float-vector 700 0 750)) +(send *center* :set-color :black) + + + + +;;Set coordination. +(send *desk* :put :left-coords + (make-cascoords + :coords (send (send *desk* :copy-worldcoords) :translate (float-vector 0 0 500)) + :parent *pr2*)) +(send *needle* :put :left-coords + (make-cascoords + :coords (send (send *needle* :copy-worldcoords) :translate (float-vector 0 0 -5)) + :parent *needle*)) + +;;Show all objects in IRTVIEWER +(objects (list *pr2* *center* *arrow* *desk* *needle* *hampen* *tp1* *tp2* *tp3* *tp4* *tp5* *tp6* *tp7*)) + + +(do ((i 0 (+ i 1))) ; i を 0 から 1 ずつ増加 + ((> i 3) 'done) ;; それぞれの位置と角度情報をリストに格納 ; i が 3 より大きくなったら終了 + (set-trajectory (- (* i 10) 3)) ; i の値に基づいて座標計算 + (send *irtviewer* :draw-objects) ; 立方体を描画 + (send *needle* :larm :inverse-kinematics + (send (send *tp1* :get :left-coords) :copy-worldcoords) + :rotation-axis :x) + (send *pr2* :larm :end-coords :assoc *needle*) + (send *ri* :angle-vector (send *pr2* :angle-vector) 1000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + (unix:sleep 1)) ; 1秒間スリープ diff --git a/jsk_2024_10_semi/trajectory.l b/jsk_2024_10_semi/trajectory.l new file mode 100644 index 000000000..ca330275d --- /dev/null +++ b/jsk_2024_10_semi/trajectory.l @@ -0,0 +1,150 @@ +#!/usr/bin/env roseus + +;;Okada-seisei seminar +;;Surgery-method dev2 +;;last editted Nov 12 ;; Michi-Tsubaki + +;; +;;This program is for trying to make unique motion for sewing sponge. Still Trying + +;;Load packages for using PR2 model and PR2 robot in real. +(require "package://pr2eus/pr2.l") +(require "package://pr2eus/pr2-utils.l") +(require "package://pr2eus/pr2-interface.l") +(require "package://pr2eus/speak.l") ;;pkg for speaking +(load "models/arrow-object.l") + +;;Set PR2 +(if (not (boundp '*pr2*)) (pr2-init)) + +;;Set Center of a Table +(setq *center* (make-cube 10 10 10)) +(send *center* :translate (float-vector 700 0 750)) +(send *center* :set-color :black) + +;;Set cube as a desk for surgery. +(setq *desk* (make-cube 500 500 750)) +(send *desk* :translate (float-vector 700 0 750/2)) +(send *desk* :set-color :brown) + +;;Set cylinder as needle. +(setq *needle* (make-cylinder 0.5 70)) +(send *needle* :translate (v+ (float-vector 0 20 100) (send *center* :pos))) +(send *needle* :set-color :yellow) +(send *needle* :rotate #d90 :x) + +;;Set hampen +(setq *hampen* (make-cube 50 50 50)) +(send *hampen* :translate (v+ (float-vector 0 0 10) (send *center* :pos))) +(send *hampen* :set-color :white) +(send *hampen* :rotate #d45 :x) + + + + +(defclass traj + :super cascaded-coords + :slots (points)) +(defmethod traj + (:init (&rest args) + (send-super* :init args) + (dotimes (i 10) + (push + (make-cube 10 10 10 :pos (float-vector (* (- i 5) 20) 0 0)) + points)) + (dotimes (i (- (length points) 1)) + (send (elt points i) :assoc (elt points (+ 1 i)))) + (send self :assoc (car points)) + self) ;; :init + (:points () points) + ) ;; defmethod +;;This program is for trying to make unique motion for sewing sponge. Still Trying + +;;Load pkgs for using PR2 model and PR2 robot in real. +(require "package://pr2eus/pr2.l") +(require "package://pr2eus/pr2-utils.l") +(require "package://pr2eus/pr2-interface.l") +(require "package://pr2eus/speak.l") ;;pkg for speaking +(load "models/arrow-object.l") + +;;Define Trajectory Point (7) +(defvar *tp1* nil) +(defvar *tp2* nil) +(defvar *tp3* nil) +(defvar *tp4* nil) +(defvar *tp5* nil) +(defvar *tp6* nil) +(defvar *tp7* nil) + +;;Set PR2 +(if (not (boundp '*pr2*)) (pr2-init)) + +;;Set Center of a Table +(setq *center* (make-cube 10 10 10)) +(send *center* :translate (float-vector 700 0 750)) +(send *center* :set-color :black) + +;;Set cube as a desk for surgery. +(setq *desk* (make-cube 500 500 750)) +(send *desk* :translate (float-vector 700 0 750/2)) +(send *desk* :set-color :brown) + +;;Set cylinder as needle. +;;Set needle +(setq *needle* (make-cylinder 0.5 70)) +(send *needle* :translate (v+ (float-vector 0 20 100) (send *center* :pos))) +(send *needle* :set-color :yellow) +(send *needle* :rotate #d90 :x) + + +;;Show Worldrecord +(setq *arrow* (arrow)) +(send *arrow* :copy-worldcoords) + +;;Show all objects in IRTVIEWER +(objects (list *pr2* *center* *arrow* *desk* *needle* *hampen*)) + + +;;Set initial pose +(send *ri* :speak-jp "初期姿勢に戻ります。" :wait t) +(send *pr2* :reset-pose) +(send *ri* :start-grasp :arms) + +(send *ri* :angle-vector (send *pr2* :angle-vector) 2000) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + +(send *ri* :speak-jp "左手を開きます。針を持たせてください。") +(send *ri* :stop-grasp :larm :wait t) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + +(send *ri* :speak-jp "閉じます。" :wait t) +(send *ri* :start-grasp :larm :wait t) +(send *ri* :wait-interpolation) +(send *irtviewer* :draw-objects) + +(send *ri* :speak-jp "これから針を持って作業します.離れてください." :wait t) +(unix:sleep 2) + + +(setq r (instance traj :init)) +(send r :rotate pi/2 :z) +(send r :locate #f(800 0 900) :world) +(objects (append (list *pr2* *center* *arrow* *desk* *needle* *hampen*) (send r :points))) + +;;(objects (list *pr2* (elt (send r :points) 0) (elt (send r :points) 1) (elt (send r :points) 2) + +(dolist (e (send r :points) + (send *pr2* :larm :inverse-kinematics e + :rotation-axis t + :debug-view t) + (send *ri* :angle-vector (send *pr2* :angle-vector) 2000) + (send *ri* :wait-interpolation) + (send *irtviewer* :draw-objects) + (format t "debug~%") + (unix:sleep 1) + ) + + ) +