Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[:self-collision-check] ignore links which do not have :faces #571

Merged
merged 5 commits into from Jun 22, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
3 changes: 3 additions & 0 deletions irteus/CBULLET.cpp
Expand Up @@ -117,6 +117,9 @@ long BT_MakeCapsuleModel(double radius, double height)
long BT_MakeMeshModel(double *verticesPoints, long numVertices)
{
btConvexHullShape* pshape = new btConvexHullShape();
if (numVertices == 0) {
fprintf(stderr, "BT_MakeMeshModel with numVertices == 0\n");
}
#define SHRINK_FOR_MARGIN false
if (SHRINK_FOR_MARGIN) {
// Shrink vertices for default margin CONVEX_DISTANCE_MARGIN,
Expand Down
12 changes: 6 additions & 6 deletions irteus/bullet.l
Expand Up @@ -55,8 +55,8 @@
(setq m
(btmakemeshmodel
(scale 1e-3 ;; [m]
(apply #'concatenate float-vector
(mapcar #'(lambda (v) (send b :inverse-transform-vector v)) (send b :vertices))))
(apply #'float-vector (apply #'concatenate cons
(mapcar #'(lambda (v) (send b :inverse-transform-vector v)) (send b :vertices)))))
(length (send b :vertices))
))
(if (> margin 0) (btsetmargin m (* 1e-3 margin)))
Expand All @@ -74,8 +74,8 @@
(setq m
(btmakemeshmodel
(scale 1e-3 ;; [m]
(apply #'concatenate float-vector
(mapcar #'(lambda (v) (send self :inverse-transform-vector v)) vs)))
(apply #'float-vector (apply #'concatenate cons
(mapcar #'(lambda (v) (send self :inverse-transform-vector v)) vs))))
(length vs)
))
(btsetmargin m fat)
Expand All @@ -89,8 +89,8 @@
(setq m
(btmakemeshmodel
(scale 1e-3 ;; [m]
(apply #'concatenate float-vector
(mapcar #'(lambda (v) (send self :inverse-transform-vector v)) vs)))
(apply #'float-vector (apply #'concatenate cons
(mapcar #'(lambda (v) (send self :inverse-transform-vector v)) vs))))
(length vs)
))
(btsetmargin m fat)
Expand Down
26 changes: 18 additions & 8 deletions irteus/irtmodel.l
Expand Up @@ -2661,15 +2661,25 @@
pairs))
(:self-collision-check
(&key (mode :all) (pairs (send self :collision-check-pairs)) (collision-func 'collision-check))
(let ((cpairs) (col-count 0))
(let ((cpairs) (col-count 0) (invalid-links))
(dolist (p pairs)
(let ((colp (/= (funcall collision-func (car p) (cdr p)) 0)))
(when colp
(incf col-count)
(if (eq mode :first)
(return-from :self-collision-check p)
(push p cpairs)))
))
(if (and (send (car p) :faces) (send (cdr p) :faces))
(let ((colp (/= (funcall collision-func (car p) (cdr p)) 0)))
(when colp
(incf col-count)
(if (eq mode :first)
(return-from :self-collision-check p)
(push p cpairs))))
(progn
(when (and (null (send (car p) :faces)) (null (member (car p) invalid-links)))
(warning-message 3 "skip collision between ~A (~A) because of no faces~%"
(send (car p) :name) (length (send (car p) :faces)))
(push (car p) invalid-links))
(when (and (null (send (cdr p) :faces)) (null (member (cdr p) invalid-links)))
(warning-message 3 "skip collision between ~A (~A) because of no faces~%"
(send (cdr p) :name) (length (send (cdr p) :faces)))
(push (cdr p) invalid-links)))
))
cpairs))
(:calc-grasp-matrix
(contact-points
Expand Down
35 changes: 35 additions & 0 deletions irteus/test/test-collision.l
Expand Up @@ -194,6 +194,22 @@
)
))

(load "models/darwin.l")
;; use add no-face link for euscollada-robot, use darwin-robot to override
(defmethod darwin-robot
;; make collision model from faces or gl-vertices
(:make-collision-model-for-links
(&key (fat 0) ((:links ls) (send self :links)))
;;
;; for append camera links for test code
(let (l)
(setq l (instance bodyset-link :init (make-cascoords) :name "dummy-link"))
(send (car links) :add-child-links l)
(setq links (append links (list l)))
(setq ls (send self :links)))
)
)

(when *collision-algorithm-pqp*

(deftest test-collision-sphere-analytical-pqp
Expand Down Expand Up @@ -249,6 +265,7 @@
(test-collision-distance-fat
(body+ (make-cube 200 200 100) (make-cube 100 100 300))
(body+ (make-cube 200 200 100) (make-cube 100 100 300))))

)

(when *collision-algorithm-bullet*
Expand Down Expand Up @@ -309,6 +326,24 @@

)

;; not sure why, but put this function within (when *collision-algorithm-pqp* causes errors...
(deftest test-self-collision-check-pqp
(when *collision-algorithm-pqp*
(setq *collision-algorithm* *collision-algorithm-pqp*)
(let (robot)
(setq robot (instance darwin-robot :init))
(send robot :self-collision-check)
)))


(deftest test-self-collision-check-bullet
(when *collision-algorithm-bullet*
(setq *collision-algorithm* *collision-algorithm-bullet*)
(let (robot)
(setq robot (instance darwin-robot :init))
(send robot :self-collision-check)
)))

(eval-when (load eval)
(run-all-tests)
(exit 0))