Skip to content

Commit

Permalink
Polishing
Browse files Browse the repository at this point in the history
  • Loading branch information
TomaszTB committed Nov 14, 2024
1 parent 1e1b450 commit 79a1355
Show file tree
Hide file tree
Showing 8 changed files with 8 additions and 16 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@ public final class PerceptionAPI
.withType(BigVideoPacket.class)
.withSuffix("debug_extraction");
public static final ROS2Topic<Empty> REQUEST_REALSENSE = PERCEPTION_MODULE.withSuffix("request_realsense").withType(Empty.class);
public static final ROS2Topic<Empty> REQUEST_REALSENSE_POINT_CLOUD = PERCEPTION_MODULE.withSuffix("request_realsense_point_cloud").withType(Empty.class);
public static final ROS2Topic<Empty> REQUEST_REALSENSE_PUBLICATION = PERCEPTION_MODULE.withSuffix("request_realsense_publication").withType(Empty.class);
public static final SideDependentList<ROS2Topic<BigVideoPacket>> BLACKFLY_VIDEO = new SideDependentList<>(BEST_EFFORT.withModule(BLACKFLY_NAME + "left")
.withType(BigVideoPacket.class)
.withSuffix("video"),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ else if (!requestMessage.getRunIcp()) // ICP Worker no longer needed (
}
});

workerThread = new RepeatingTaskThread(this::runWorkers, "ICPWorkers").setFrequencyLimit(ICP_WORK_FREQUENCY);
workerThread = new RepeatingTaskThread("ICPWorkers", this::runWorkers).setFrequencyLimit(ICP_WORK_FREQUENCY);
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ public StandAloneRealsenseProcess(ROS2Helper ros2Helper, ROS2SyncedRobotModel sy
soleFrameSuppliers.put(side, () -> syncedRobot.getReferenceFrames().getSoleFrame(side));
}
}
realsenseDemandNode = new ROS2DemandGraphNode(ros2Helper, PerceptionAPI.REQUEST_REALSENSE_POINT_CLOUD);
realsenseDemandNode = new ROS2DemandGraphNode(ros2Helper, PerceptionAPI.REQUEST_REALSENSE_PUBLICATION);

realsenseImageRetriever = new RealsenseColorDepthImageRetriever(new RealsenseDeviceManager(),
RealsenseConfiguration.D455_COLOR_720P_DEPTH_720P_30HZ,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -90,15 +90,9 @@ public void blockingStop()
ExceptionTools.handle((RunnableThatThrows) thread::join, exceptionHandler);
}

public void interrupt()
{
if (thread != null)
thread.interrupt();
}

public boolean isRunning()
{
return running.get();
return running.getPlain();
}

boolean isAlive()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ public void runYOLODetectionOnAllModels(RawImage colorImage, RawImage depthImage

/**
* Non-blocking call to run YOLO on the provided images
* @param colorImage RGB color image, used for YOLO detection
* @param colorImage BGR color image, used for YOLO detection
* @param depthImage 16UC1 depth image, used to get points of detected objects
*/
public void runYOLODetection(YOLOv8ObjectDetector yoloDetector, RawImage colorImage, RawImage depthImage)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,5 @@ protected void runTask()
ReferenceFrame pelvisFrame = robotPelvisFrameSupplier.get();
sceneGraph.updateOnRobotOnly(pelvisFrame);
sceneGraph.updatePublication();

// TODO: add behavior tree?
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ public abstract class ImageSensor implements AutoCloseable
public ImageSensor(String sensorName)
{
this.sensorName = sensorName;
grabThread = new RepeatingTaskThread(this::grabAndNotify, sensorName + "Grabber");
grabThread = new RepeatingTaskThread(sensorName + "Grabber", this::grabAndNotify);
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,15 +39,15 @@ public ZEDSVOPlaybackSensor(ROS2PublishSubscribeAPI ros2, int cameraID, ZEDModel
// Subscribe to play message
ros2.subscribeViaCallback(PerceptionAPI.ZED_SVO_PLAY, () -> getGrabThread().startRepeating());

publishInfoThread = new RepeatingTaskThread(() ->
publishInfoThread = new RepeatingTaskThread("PublishSVOInfoThread", () ->
{
svoStatusMessage.setCurrentFileName(svoFileName);
svoStatusMessage.setRecordMode((byte) 1); // playback
svoStatusMessage.setCurrentPosition(getCurrentPosition());
svoStatusMessage.setLength(getLength());

ros2.publish(PerceptionAPI.ZED_SVO_CURRENT_FILE, svoStatusMessage);
}, "PublishSVOInfoThread").setFrequencyLimit(ZEDImageSensor.CAMERA_FPS);
}).setFrequencyLimit(ZEDImageSensor.CAMERA_FPS);
publishInfoThread.start();
}

Expand Down

0 comments on commit 79a1355

Please sign in to comment.