Skip to content

Commit

Permalink
Merge pull request #3209 from SergioRAgostinho/bind-gpu
Browse files Browse the repository at this point in the history
[gpu] Prefer lambdas over binds.
  • Loading branch information
taketwo authored Jul 8, 2019
2 parents 1524e5e + 9c335e1 commit 4320d93
Show file tree
Hide file tree
Showing 5 changed files with 40 additions and 16 deletions.
23 changes: 16 additions & 7 deletions gpu/kinfu/tools/kinfu_app.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -961,18 +961,27 @@ struct KinFuApp
using namespace openni_wrapper;
using DepthImagePtr = boost::shared_ptr<DepthImage>;
using ImagePtr = boost::shared_ptr<Image>;

std::function<void (const ImagePtr&, const DepthImagePtr&, float constant)> func1_dev = boost::bind (&KinFuApp::source_cb2_device, this, _1, _2, _3);
std::function<void (const DepthImagePtr&)> func2_dev = boost::bind (&KinFuApp::source_cb1_device, this, _1);

std::function<void (const ImagePtr&, const DepthImagePtr&, float constant)> func1_oni = boost::bind (&KinFuApp::source_cb2_oni, this, _1, _2, _3);
std::function<void (const DepthImagePtr&)> func2_oni = boost::bind (&KinFuApp::source_cb1_oni, this, _1);

std::function<void (const ImagePtr&, const DepthImagePtr&, float)> func1_dev = [this] (const ImagePtr& img, const DepthImagePtr& depth, float constant)
{
source_cb2_device (img, depth, constant);
};
std::function<void (const DepthImagePtr&)> func2_dev = [this] (const DepthImagePtr& depth) { source_cb1_device (depth); };

std::function<void (const ImagePtr&, const DepthImagePtr&, float)> func1_oni = [this] (const ImagePtr& img, const DepthImagePtr& depth, float constant)
{
source_cb2_oni (img, depth, constant);
};
std::function<void (const DepthImagePtr&)> func2_oni = [this] (const DepthImagePtr& depth) { source_cb1_oni (depth); };

bool is_oni = dynamic_cast<pcl::ONIGrabber*>(&capture_) != nullptr;
std::function<void (const ImagePtr&, const DepthImagePtr&, float constant)> func1 = is_oni ? func1_oni : func1_dev;
std::function<void (const DepthImagePtr&)> func2 = is_oni ? func2_oni : func2_dev;

std::function<void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&) > func3 = boost::bind (&KinFuApp::source_cb3, this, _1);
std::function<void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&) > func3 = [this] (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr& cloud)
{
source_cb3 (cloud);
};

bool need_colors = integrate_colors_ || registration_;
if ( pcd_source_ && !capture_.providesCallback<void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&)>() )
Expand Down
12 changes: 9 additions & 3 deletions gpu/kinfu_large_scale/tools/kinfuLS_app.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -983,9 +983,15 @@ struct KinFuLSApp
using DepthImagePtr = boost::shared_ptr<DepthImage>;
using ImagePtr = boost::shared_ptr<Image>;

std::function<void (const ImagePtr&, const DepthImagePtr&, float constant)> func1 = boost::bind (&KinFuLSApp::source_cb2, this, _1, _2, _3);
std::function<void (const DepthImagePtr&)> func2 = boost::bind (&KinFuLSApp::source_cb1, this, _1);
std::function<void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&) > func3 = boost::bind (&KinFuLSApp::source_cb3, this, _1);
std::function<void (const ImagePtr&, const DepthImagePtr&, float)> func1 = [this] (const ImagePtr& img, const DepthImagePtr& depth, float constant)
{
source_cb2 (img, depth, constant);
};
std::function<void (const DepthImagePtr&)> func2 = [this] (const DepthImagePtr& depth) { source_cb1 (depth); };
std::function<void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr&) > func3 = [this] (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr& cloud)
{
source_cb3 (cloud);
};

bool need_colors = integrate_colors_ || registration_ || enable_texture_extraction_;

Expand Down
10 changes: 8 additions & 2 deletions gpu/kinfu_large_scale/tools/record_maps_rgb.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -258,9 +258,15 @@ void
grabAndSend ()
{
pcl::Grabber* interface = new pcl::OpenNIGrabber ();
//std::function<void (const pcl::PointCloud<pcl::PointXYZRGBA>::ConstPtr& )> f = boost::bind(&grabberCallBack, _1);

std::function<void (const boost::shared_ptr<openni_wrapper::Image>&, const boost::shared_ptr<openni_wrapper::DepthImage>&, float constant)> f = boost::bind (&grabberMapsCallBack, _1, _2, _3);
std::function<void (const openni_wrapper::Image::Ptr&,
const openni_wrapper::DepthImage::Ptr&,
float)> f = [] (const openni_wrapper::Image::Ptr& img,
const openni_wrapper::DepthImage::Ptr& depth,
float constant)
{
grabberMapsCallBack (img, depth, constant);
};


interface->registerCallback (f);
Expand Down
9 changes: 6 additions & 3 deletions gpu/people/tools/people_app.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -281,9 +281,12 @@ class PeoplePCDApp

using DepthImagePtr = boost::shared_ptr<openni_wrapper::DepthImage>;
using ImagePtr = boost::shared_ptr<openni_wrapper::Image>;

std::function<void (const boost::shared_ptr<const PointCloud<PointXYZRGBA> >&)> func1 = boost::bind (&PeoplePCDApp::source_cb1, this, _1);
std::function<void (const ImagePtr&, const DepthImagePtr&, float constant)> func2 = boost::bind (&PeoplePCDApp::source_cb2, this, _1, _2, _3);

std::function<void (const PointCloud<PointXYZRGBA>::ConstPtr&)> func1 = [this] (const PointCloud<PointXYZRGBA>::ConstPtr& cloud) { source_cb1 (cloud); };
std::function<void (const ImagePtr&, const DepthImagePtr&, float)> func2 = [this] (const ImagePtr& img, const DepthImagePtr& depth, float constant)
{
source_cb2 (img, depth, constant);
};
boost::signals2::connection c = cloud_cb_ ? capture_.registerCallback (func1) : capture_.registerCallback (func2);

{
Expand Down
2 changes: 1 addition & 1 deletion gpu/people/tools/people_tracking.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class PeopleTrackingApp
pcl::Grabber* interface = new pcl::OpenNIGrabber();

std::function<void (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr&)> f =
boost::bind (&PeopleTrackingApp::cloud_cb_, this, _1);
[this] (const pcl::PointCloud<pcl::PointXYZRGB>::ConstPtr& cloud) { cloud_cb_ (cloud); };

interface->registerCallback (f);
interface->start ();
Expand Down

0 comments on commit 4320d93

Please sign in to comment.