wkentaro / octomap-python

Python binding of the OctoMap library.
81 stars 28 forks source link

OcTree.castRay should return end coordinates regardless of hit #4

Open lericson opened 4 years ago

lericson commented 4 years ago

According to the octomap API, the end coordinates are useful regardless of the return of castRay -- the user needs to check the returned voxel.

From 8823d36e294e836780f67d874a89e113f1687717 Mon Sep 17 00:00:00 2001
From: Ludvig Ericson <ludvig@lericson.se>
Date: Thu, 11 Jun 2020 13:17:36 +0200
Subject: [PATCH] Set end coords regardless of hit in castRay

---
 octomap/octomap.pyx | 3 +--
 1 file changed, 1 insertion(+), 2 deletions(-)

diff --git a/octomap/octomap.pyx b/octomap/octomap.pyx
index 470dd34..0dda7ed 100644
--- a/octomap/octomap.pyx
+++ b/octomap/octomap.pyx
@@ -414,8 +414,7 @@ cdef class OcTree:
             bool(ignoreUnknownCells),
             <double?>maxRange
         )
-        if hit:
-            end[0:3] = e.x(), e.y(), e.z()
+        end[0:3] = e.x(), e.y(), e.z()
         return hit

     read = _octree_read
--
2.17.1

This is suitable for git am.

lericson commented 4 years ago

I bet my patch breaks the tests by the way

lericson commented 4 years ago

A ray is cast from 'origin' with a given direction, the first non-free cell is returned in 'end' (as center coordinate). This could also be the origin node if it is occupied or unknown. castRay() returns true if an occupied node was hit by the raycast. If the raycast returns false you can search() the node at 'end' and see whether it's unknown space.