Skip to content

Commit 7d967fe

Browse files
PetervDoorenMatthijsBurgh
authored andcommitted
added docstrings
1 parent 943fb03 commit 7d967fe

File tree

2 files changed

+29
-5
lines changed

2 files changed

+29
-5
lines changed

ed_sensor_integration/include/ed/kinect/image_buffer.h

Lines changed: 26 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,11 @@ namespace tf
2020
class TransformListener;
2121
}
2222

23+
/**
24+
* @brief The ImageBuffer class, provides a buffer to synchronise rgbd images with sensor positions.
25+
* Images are stored until they are removed from the buffer or until a
26+
* certain amount of time has passed
27+
*/
2328
class ImageBuffer
2429
{
2530

@@ -29,12 +34,31 @@ class ImageBuffer
2934

3035
~ImageBuffer();
3136

37+
/**
38+
* @brief initialize, configure the buffer
39+
* @param topic, ros topic on which the rgbd images are published
40+
* @param root_frame, root frame to calculate sensor pose relative to (default: map)
41+
* @param worker_thread_frequency, frequency at which the worker thread updates the most recent image (default: 20)
42+
*/
3243
void initialize(const std::string& topic, const std::string& root_frame="map", const float worker_thread_frequency=20);
3344

34-
// Polls to see if there is a new image with transform. If not, returns false
45+
/**
46+
* @brief nextImage, Returns the most recent combination of image and transform, provided it is different from the previous time the function was called.
47+
*
48+
* @param[out] image, rgbd image to write the next image to. Iff a next image is found
49+
* @param[out] sensor_pose, will be filled with the sensor pose corresponding to the next image. Iff a next image is found
50+
* @return whether or not a novel image is available
51+
*/
3552
bool nextImage(rgbd::ImageConstPtr& image, geo::Pose3D& sensor_pose);
3653

37-
// Blocks until a new image with transform is found. Returns false if no image or tf could be found within 'timeout_sec' seconds
54+
/**
55+
* @brief waitForRecentImage, Blocks until a new image with transform is found. Returns false if no image or tf could be found within 'timeout_sec' seconds
56+
*
57+
* @param[out] image, rgbd image to write the next image to. Iff a next image is found
58+
* @param[out] sensor_pose, will be filled with the sensor pose corresponding to the next image. Iff a next image is found
59+
* @param[in] timeout_sec, maximum duration to block.
60+
* @return whether or not a next image was available within the timeout duration.
61+
*/
3862
bool waitForRecentImage(rgbd::ImageConstPtr& image, geo::Pose3D& sensor_pose, double timeout_sec);
3963

4064
private:

ed_sensor_integration/src/kinect/kinect_plugin.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ void KinectPlugin::initialize(ed::InitData& init)
4949
if (config.value("topic", topic))
5050
{
5151
ROS_INFO_STREAM("[ED KINECT PLUGIN] Initializing kinect client with topic '" << topic << "'.");
52-
image_buffer_.initialize(topic);
52+
image_buffer_.initialize(topic, "map");
5353
}
5454

5555
// - - - - - - - - - - - - - - - - - -
@@ -102,7 +102,7 @@ bool KinectPlugin::srvGetImage(ed_sensor_integration_msgs::GetImage::Request& re
102102
rgbd::ImageConstPtr image;
103103
geo::Pose3D sensor_pose;
104104

105-
if (!image_buffer_.waitForRecentImage("map", image, sensor_pose, 2.0))
105+
if (!image_buffer_.waitForRecentImage(image, sensor_pose, 2.0))
106106
{
107107
res.error_msg = "Could not get image";
108108
return true;
@@ -155,7 +155,7 @@ bool KinectPlugin::srvUpdate(ed_sensor_integration_msgs::Update::Request& req, e
155155
rgbd::ImageConstPtr image;
156156
geo::Pose3D sensor_pose;
157157

158-
if (!image_buffer_.waitForRecentImage("map", image, sensor_pose, 2.0))
158+
if (!image_buffer_.waitForRecentImage(image, sensor_pose, 2.0))
159159
{
160160
res.error_msg = "Could not get image";
161161
return true;

0 commit comments

Comments
 (0)