-
Notifications
You must be signed in to change notification settings - Fork 33
/
Copy pathtest_ros.cpp
89 lines (75 loc) · 2.7 KB
/
test_ros.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
/*
Copyright 2016, Giacomo Dabisias & Michele Mambrini"
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
@Author
Giacomo Dabisias, PhD Student & Michele Mambrini
PERCRO, (Laboratory of Perceptual Robotics)
Scuola Superiore Sant'Anna
via Luigi Alamanni 13D, San Giuliano Terme 56010 (PI), Italy
*/
#include "k2g_ros.h"
// extra headers for writing out ply file
#include <pcl/console/print.h>
#include <pcl/console/parse.h>
#include <pcl/console/time.h>
#include <pcl/io/ply_io.h>
struct PlySaver{
PlySaver(boost::shared_ptr<pcl::PointCloud<pcl::PointXYZRGB>> cloud, bool binary, bool use_camera, K2GRos & ros_grabber):
cloud_(cloud), binary_(binary), use_camera_(use_camera), K2G_ros_(ros_grabber){}
boost::shared_ptr<pcl::PointCloud<pcl::PointXYZRGB>> cloud_;
bool binary_;
bool use_camera_;
K2GRos & K2G_ros_;
};
void KeyboardEventOccurred(const pcl::visualization::KeyboardEvent &event, void * data)
{
std::string pressed = event.getKeySym();
PlySaver * s = (PlySaver*)data;
if(event.keyDown ())
{
if(pressed == "s")
{
pcl::PLYWriter writer;
std::chrono::high_resolution_clock::time_point p = std::chrono::high_resolution_clock::now();
std::string now = std::to_string((long)std::chrono::duration_cast<std::chrono::milliseconds>(p.time_since_epoch()).count());
writer.write ("cloud_" + now, *(s->cloud_), s->binary_, s->use_camera_);
std::cout << "saved " << "cloud_" + now + ".ply" << std::endl;
}
if(pressed == "m")
{
s->K2G_ros_.mirror();
}
if(pressed == "e")
{
s->K2G_ros_.setShutdown();
std::cout << "SHUTTING DOWN" << std::endl;
}
}
}
int main(int argc, char * argv[])
{
std::cout << "Syntax is: " << argv[0] << " [-processor 0|1|2] -processor options 0,1,2,3 correspond to CPU, OPENCL, OPENGL, CUDA respectively\n";
Processor freenectprocessor = OPENGL;
if(argc > 1){
freenectprocessor = static_cast<Processor>(atoi(argv[1]));
}
ros::init(argc, argv, "RosKinect2Grabber");
K2GRos K2G_ros(freenectprocessor);
while((ros::ok()) && (!K2G_ros.terminate()))
{
K2G_ros.publishColor();
K2G_ros.publishCameraInfoColor();
K2G_ros.publishCameraInfoDepth();
}
K2G_ros.shutDown();
return 0;
}