diff --git a/jsk_footstep_planner/config/HRP2JSKNTS_footstep_planner_params.yaml b/jsk_footstep_planner/config/HRP2JSKNTS_footstep_planner_params.yaml index a70506b66..a4e9c4209 100644 --- a/jsk_footstep_planner/config/HRP2JSKNTS_footstep_planner_params.yaml +++ b/jsk_footstep_planner/config/HRP2JSKNTS_footstep_planner_params.yaml @@ -4,8 +4,8 @@ footstep_size_x: 0.254 footstep_size_y: 0.150368 rleg_footstep_offset: [0.016411, 0.0, 0.0] lleg_footstep_offset: [0.016411, 0.0, 0.0] -collision_bbox_size: [0.499967, 0.39561, 1.33184] -collision_bbox_offset: [-0.055675, 0.0, 0.0] +collision_bbox_size: [0.499966, 0.396911, 1.03184] +collision_bbox_offset: [-0.055675, 0.00064, 0.805435] successors: - x: 0.15 y: 0.0 @@ -250,3 +250,6 @@ successors: - x: -0.05 y: -0.05 theta: -0.349066 +goal_pos_thr: 0.05 +goal_rot_thr: 0.087266 +transition_limit_yaw: 0.350811 diff --git a/jsk_footstep_planner/euslisp/generate-footstep-planner-parameters-from-robot-model.l b/jsk_footstep_planner/euslisp/generate-footstep-planner-parameters-from-robot-model.l index 7e4ababc8..273ee5c10 100644 --- a/jsk_footstep_planner/euslisp/generate-footstep-planner-parameters-from-robot-model.l +++ b/jsk_footstep_planner/euslisp/generate-footstep-planner-parameters-from-robot-model.l @@ -69,11 +69,11 @@ (float-vector (* 1e-3 (- (elt (find-extream (send bb :vertices) #'(lambda (x) (elt x 0)) #'>) 0) (elt (find-extream (send bb :vertices) #'(lambda (x) (elt x 0)) #'<) 0))) (* 1e-3 (- (elt (find-extream (send bb :vertices) #'(lambda (x) (elt x 1)) #'>) 1) (elt (find-extream (send bb :vertices) #'(lambda (x) (elt x 1)) #'<) 1))) - (* 1e-3 (- (elt (find-extream (send bb :vertices) #'(lambda (x) (elt x 2)) #'>) 2) (elt (find-extream (send bb :vertices) #'(lambda (x) (elt x 2)) #'<) 2))))) + (- (* 1e-3 (- (elt (find-extream (send bb :vertices) #'(lambda (x) (elt x 2)) #'>) 2) (elt (find-extream (send bb :vertices) #'(lambda (x) (elt x 2)) #'<) 2))) 0.3))) ;;0.3[m] from the ground is not considered (neglect-thre (* 1e-3 0.1)) ;; 0.1[mm] (bbox-offset (let ((tmp (scale 1e-3 (send (send robot :foot-midcoords) :inverse-transform-vector (send bb :centroid))))) - (float-vector (neglect-small-value (elt tmp 0) neglect-thre) (neglect-small-value (elt tmp 1) neglect-thre) 0.0) + (float-vector (neglect-small-value (elt tmp 0) neglect-thre) (neglect-small-value (elt tmp 1) neglect-thre) (+ 0.15 (neglect-small-value (elt tmp 2) neglect-thre))) ;;0.3[m] from the ground is not considered ))) (if return-value (list bbox-size bbox-offset)