Skip to content

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

Open
@lericson

Description

@lericson

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 <[email protected]>
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.

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions