Skip to content

Moved the snapping extractor out of the RapidHeightMapManager and to a higher level closer to where its used #796

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

Merged
merged 16 commits into from
May 7, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
16 commits
Select commit Hold shift + click to select a range
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import us.ihmc.footstepPlanning.graphSearch.EnvironmentHandler;
import us.ihmc.humanoidRobotics.communication.ControllerFootstepQueueMonitor;
import us.ihmc.perception.StandAloneRealsenseProcess;
import us.ihmc.perception.gpuHeightMap.SnappingTerrainExtractor;
import us.ihmc.robotics.physics.RobotCollisionModel;
import us.ihmc.ros2.ROS2Node;
import us.ihmc.ros2.ROS2NodeBuilder;
Expand All @@ -26,6 +27,8 @@ public class ContinuousHikingProcess
private final ContinuousPlannerSchedulingTask continuousPlannerSchedulingTask;
private final StandAloneRealsenseProcess standAloneRealsenseProcess;

private final SnappingTerrainExtractor snappingTerrainExtractor;

public ContinuousHikingProcess(DRCRobotModel robotModel, RobotCollisionModel robotCollisionModel)
{
ROS2Node ros2Node = new ROS2NodeBuilder().build("nadia_terrain_perception_node");
Expand All @@ -41,8 +44,9 @@ public ContinuousHikingProcess(DRCRobotModel robotModel, RobotCollisionModel rob

ControllerFootstepQueueMonitor controllerFootstepQueueMonitor = new ControllerFootstepQueueMonitor(ros2Node, robotModel.getSimpleRobotName());

environmentHandler = new EnvironmentHandler();
activeMappingParameterToolBox = new ActiveMappingParameterToolBox(ros2Node, robotModel, "ForContinuousWalking");
environmentHandler = new EnvironmentHandler();
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Both of these are happening at the highest level now

snappingTerrainExtractor = new SnappingTerrainExtractor(activeMappingParameterToolBox.getHeightMapParameters());
standAloneRealsenseProcess = new StandAloneRealsenseProcess(ros2Node,
ros2Helper,
syncedRobot,
Expand All @@ -69,17 +73,21 @@ public void update()
activeMappingParameterToolBox.update();

if (standAloneRealsenseProcess.getLatestHeightMapData() != null)
{
environmentHandler.setHeightMapData(standAloneRealsenseProcess.getLatestHeightMapData());
snappingTerrainExtractor.update(environmentHandler.getHeightMapData());
}

if (standAloneRealsenseProcess.getLatestTerrainMapData() != null)
environmentHandler.setTerrainMapData(standAloneRealsenseProcess.getLatestTerrainMapData());
if (snappingTerrainExtractor.getTerrainMapData() != null)
environmentHandler.setTerrainMapData(snappingTerrainExtractor.getTerrainMapData());

continuousPlannerSchedulingTask.setLatestEnvironmentHandler(environmentHandler);
}

public void destroy()
{
continuousPlannerSchedulingTask.destroy();
snappingTerrainExtractor.close();
standAloneRealsenseProcess.destroy();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -87,14 +87,6 @@ public HeightMapData getLatestHeightMapData()
}
}

public TerrainMapData getLatestTerrainMapData()
{
synchronized (heightMapLock)
{
return heightMapManager.getTerrainMapData();
}
}

@Override
public void kill()
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -94,14 +94,6 @@ public HeightMapData getLatestHeightMapData()
}
}

public TerrainMapData getLatestTerrainMapData()
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Not coming from the height map thread anymore

{
synchronized (heightMapLock)
{
return heightMapManager.getTerrainMapData();
}
}

public void destroy()
{
scheduler.shutdown();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,6 @@
import us.ihmc.communication.ros2.ROS2Helper;
import us.ihmc.communication.ros2.ROS2TunedRigidBodyTransform;
import us.ihmc.humanoidRobotics.communication.ControllerFootstepQueueMonitor;
import us.ihmc.perception.heightMap.TerrainMapData;
import us.ihmc.robotics.physics.RobotCollisionModel;
import us.ihmc.ros2.ROS2Node;
import us.ihmc.sensorProcessing.heightMap.HeightMapData;
Expand Down Expand Up @@ -96,11 +95,6 @@ public HeightMapData getLatestHeightMapData()
return rapidHeightMapThread.getLatestHeightMapData();
}

public TerrainMapData getLatestTerrainMapData()
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Not happening in the realsense process anymore

{
return rapidHeightMapThread.getLatestTerrainMapData();
}

public void destroy()
{
rapidHeightMapThread.destroy();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,7 @@ public class RapidHeightMapExtractorCUDA
private final GpuMat globalHeightMapImage;
private final GpuMat terrainCostImage;
private final GpuMat contactMapImage;
private final GpuMat sensorCroppedHeightMapImage;
private final GpuMat terrainHeightMapImage;
private final GpuMat croppedHeightMapImage;
private final GpuMat emptyGlobalHeightMapImage;
private final CUDAProgram heightMapCUDAProgram;

Expand Down Expand Up @@ -65,11 +64,9 @@ public class RapidHeightMapExtractorCUDA
private float gridOffsetX;
private int centerIndex;
private int cellsPerAxisLocal;
private int cellsPerAxisTerrain;
private int globalCenterIndex;
private int croppedCenterIndex;
private int cellsPerAxisCropped;
private int terrainCenterIndex;
private int globalCellsPerAxis;
private dim3 blockSize;
private dim3 updateKernelGridDim;
Expand Down Expand Up @@ -117,8 +114,7 @@ public RapidHeightMapExtractorCUDA(int mode, HeightMapParameters heightMapParame
globalHeightMapImage = new GpuMat(globalCellsPerAxis, globalCellsPerAxis, opencv_core.CV_16UC1);
terrainCostImage = new GpuMat(globalCellsPerAxis, globalCellsPerAxis, opencv_core.CV_8UC1);
contactMapImage = new GpuMat(globalCellsPerAxis, globalCellsPerAxis, opencv_core.CV_8UC1);
sensorCroppedHeightMapImage = new GpuMat(cellsPerAxisCropped, cellsPerAxisCropped, opencv_core.CV_16UC1);
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This name was confusing

terrainHeightMapImage = new GpuMat(cellsPerAxisTerrain, cellsPerAxisTerrain, opencv_core.CV_16UC1);
croppedHeightMapImage = new GpuMat(cellsPerAxisCropped, cellsPerAxisCropped, opencv_core.CV_16UC1);

emptyGlobalHeightMapImage = new GpuMat(globalCellsPerAxis, globalCellsPerAxis, opencv_core.CV_16UC1);

Expand Down Expand Up @@ -149,9 +145,6 @@ private void recomputeDerivedParameters()
globalCenterIndex = HeightMapTools.computeCenterIndex(heightMapParameters.getInternalGlobalWidthInMeters(), heightMapParameters.getCellSizeInMeters());
globalCellsPerAxis = 2 * globalCenterIndex + 1;

terrainCenterIndex = HeightMapTools.computeCenterIndex(heightMapParameters.getTerrainWidthInMeters(), heightMapParameters.getCellSizeInMeters());
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

There is no concept of a terrain map anymore, its just the cropped map

cellsPerAxisTerrain = 2 * terrainCenterIndex + 1;

croppedCenterIndex = HeightMapTools.computeCenterIndex(heightMapParameters.getCroppedWidthInMeters(), heightMapParameters.getCellSizeInMeters());
cellsPerAxisCropped = 2 * croppedCenterIndex + 1;

Expand Down Expand Up @@ -269,11 +262,9 @@ public void update(GpuMat latestDepthImageGPU,

// Run the cropping kernel
croppingKernel.withPointer(globalHeightMapImage.data()).withLong(globalHeightMapImage.step());
croppingKernel.withPointer(sensorCroppedHeightMapImage.data()).withLong(sensorCroppedHeightMapImage.step());
croppingKernel.withPointer(terrainHeightMapImage.data()).withLong(terrainHeightMapImage.step());
croppingKernel.withPointer(croppedHeightMapImage.data()).withLong(croppedHeightMapImage.step());
croppingKernel.withPointer(parametersDevicePointer);
croppingKernel.withInt(cellsPerAxisCropped);
croppingKernel.withInt(terrainHeightMapImage.rows());
error = cudaStreamSynchronize(stream);
CUDATools.checkCUDAError(error);

Expand Down Expand Up @@ -377,7 +368,6 @@ public float[] populateParameterArray(HeightMapParameters parameters,
(float) parameters.getSearchWindowHeight(),
(float) parameters.getSearchWindowWidth(),
(float) croppedCenterIndex,
(float) terrainCenterIndex,
(float) parameters.getMinClampHeight(),
(float) parameters.getMaxClampHeight(),
(float) parameters.getHeightOffset(),
Expand Down Expand Up @@ -418,8 +408,7 @@ public void destroy()
globalHeightMapImage.close();
terrainCostImage.close();
contactMapImage.close();
sensorCroppedHeightMapImage.close();
terrainHeightMapImage.close();
croppedHeightMapImage.close();

filteredRapidHeightMapExtractor.destroy();
verticalSurfacesExtractor.destroy();
Expand Down Expand Up @@ -449,13 +438,8 @@ public int getSequenceNumber()
return sequenceNumber;
}

public GpuMat getTerrainHeightMapImage()
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Not happening in here any more

{
return terrainHeightMapImage;
}

public GpuMat getVisualizedHeightMap()
public GpuMat getCroppedHeightMap()
{
return sensorCroppedHeightMapImage.clone();
return croppedHeightMapImage.clone();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
import us.ihmc.perception.camera.CameraIntrinsics;
import us.ihmc.perception.cuda.CUDABodyCollisionFilter;
import us.ihmc.perception.filters.CUDAFlyingPointsFilter;
import us.ihmc.perception.heightMap.TerrainMapData;
import us.ihmc.perception.opencv.OpenCVTools;
import us.ihmc.perception.tools.PerceptionMessageTools;
import us.ihmc.robotModels.FullHumanoidRobotModel;
Expand All @@ -28,6 +27,7 @@
import us.ihmc.scs2.simulation.collision.Collidable;
import us.ihmc.sensorProcessing.heightMap.HeightMapData;
import us.ihmc.sensorProcessing.heightMap.HeightMapParameters;
import us.ihmc.sensorProcessing.heightMap.HeightMapTools;

import java.time.Instant;
import java.util.ArrayList;
Expand All @@ -40,7 +40,6 @@ public class RapidHeightMapManager
{
private final HeightMapParameters heightMapParameters;
private final RapidHeightMapExtractorCUDA rapidHeightMapExtractor;
private final SnappingTerrainExtractor snappedFootstepsExtractor;

private final Point3D sensorOrigin = new Point3D();
private final FramePose3D cameraPose = new FramePose3D();
Expand All @@ -56,6 +55,7 @@ public class RapidHeightMapManager
private final ROS2Publisher<ImageMessage> heightMapPublisher;
private final ImageMessage croppedHeightMapImageMessage = new ImageMessage();
private final BytePointer compressedCroppedHeightMapPointer = new BytePointer();
private final GpuMat deviceCroppedHeightMap;

public RapidHeightMapManager(ROS2Node ros2Node,
RobotCollisionModel robotCollisionModel,
Expand All @@ -76,8 +76,10 @@ public RapidHeightMapManager(ROS2Node ros2Node,
rapidHeightMapDriftOffset = new RapidHeightMapDriftOffset(controllerFootstepQueueMonitor);
flyingPointsFilter = new CUDAFlyingPointsFilter();

int croppedCenterIndex = HeightMapTools.computeCenterIndex(heightMapParameters.getCroppedWidthInMeters(), heightMapParameters.getCellSizeInMeters());
int cellsPerAxisCropped = 2 * croppedCenterIndex + 1;
deviceCroppedHeightMap = new GpuMat(cellsPerAxisCropped, cellsPerAxisCropped, opencv_core.CV_16UC1);
rapidHeightMapExtractor = new RapidHeightMapExtractorCUDA(1, heightMapParameters);
snappedFootstepsExtractor = new SnappingTerrainExtractor(heightMapParameters);

// We use a notification to only call resetting the height map in one place
heightMapPublisher = ros2Node.createPublisher(PerceptionAPI.HEIGHT_MAP_CROPPED);
Expand All @@ -96,15 +98,14 @@ public RapidHeightMapManager(ROS2Node ros2Node,
}
}

public void updateAndPublishHeightMap(RawImage depthImage, ReferenceFrame cameraFrame, ReferenceFrame cameraZUpFrame) throws Exception
public void updateAndPublishHeightMap(RawImage depthImage, ReferenceFrame cameraFrame, ReferenceFrame cameraZUpFrame)
{
RawImage depthImageCopy = depthImage.get();
Mat latestDepthImage = depthImageCopy.getCpuImageMat();
Instant acquisitionTime = depthImageCopy.getAcquisitionTime();
CameraIntrinsics depthIntrinsicsCopy = depthImageCopy.getIntrinsicsCopy();

// -------- Update the Height Map with the latest depth image from the sensor --------------
GpuMat deviceCroppedHeightMap = new GpuMat();
updateInternal(latestDepthImage, deviceCroppedHeightMap, depthIntrinsicsCopy, cameraFrame, cameraZUpFrame);

// Publish the height map to anyone who is subscribing
Expand All @@ -121,16 +122,18 @@ public void updateAndPublishHeightMap(RawImage depthImage, ReferenceFrame camera
hostCroppedHeightMap.cols(),
(float) heightMapParameters.getHeightScaleFactor());

deviceCroppedHeightMap.close();
hostCroppedHeightMap.close();
depthImageCopy.release();
}

/**
* Update the Height Map with the latest depth image from the sensor
*/
private void updateInternal(Mat latestDepthImage,
GpuMat deviceHeightMapToPack,
CameraIntrinsics depthIntrinsicsCopy,
ReferenceFrame cameraFrame,
ReferenceFrame cameraZUpFrame) throws Exception
ReferenceFrame cameraZUpFrame)
{
// Option that gets triggered from a message sent from the user
if (lowerHeightMapBackdropRequested.poll())
Expand Down Expand Up @@ -194,7 +197,7 @@ private void updateInternal(Mat latestDepthImage,
sensorOrigin,
computeFootHeight());

GpuMat deviceCroppedHeightMap = rapidHeightMapExtractor.getVisualizedHeightMap();
GpuMat deviceCroppedHeightMap = rapidHeightMapExtractor.getCroppedHeightMap();
// We have used the depth image without the robot, close this to avoid creating a memory leak
depthImageWithoutRobot.close();

Expand All @@ -209,30 +212,24 @@ private void updateInternal(Mat latestDepthImage,

// Don't close this mat as its being used in the extractor till that finish's
deviceCroppedHeightMap.convertTo(deviceHeightMapToPack, deviceCroppedHeightMap.type());

// Now extract the maps to be used in the footstep planning algorithm
snappedFootstepsExtractor.update(rapidHeightMapExtractor.getTerrainHeightMapImage(), sensorOrigin);
}

public TerrainMapData getTerrainMapData()
{
return snappedFootstepsExtractor.getTerrainMapData();
}

public HeightMapData getLatestHeightMapData()
{
HeightMapData latestHeightMapData = new HeightMapData((float) heightMapParameters.getCellSizeInMeters(),
(float) heightMapParameters.getTerrainWidthInMeters(),
(float) heightMapParameters.getCroppedWidthInMeters(),
sensorOrigin.getX(),
sensorOrigin.getY());

Mat heightMapMat = getTerrainMapData().getHeightMap();
PerceptionMessageTools.convertToHeightMapData(heightMapMat,
Mat heightMap = new Mat();
deviceCroppedHeightMap.download(heightMap);
PerceptionMessageTools.convertToHeightMapData(heightMap,
latestHeightMapData,
sensorOrigin,
(float) heightMapParameters.getTerrainWidthInMeters(),
(float) heightMapParameters.getCroppedWidthInMeters(),
(float) heightMapParameters.getCellSizeInMeters(),
heightMapParameters);
heightMap.close();
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

👍


return latestHeightMapData;
}
Expand All @@ -257,8 +254,8 @@ private double computeFootHeight()
public void destroy()
{
rapidHeightMapExtractor.destroy();
snappedFootstepsExtractor.close();
flyingPointsFilter.destroy();
deviceCroppedHeightMap.close();
compressedCroppedHeightMapPointer.close();
}
}
Loading
Loading