需要浏览某文件夹中的所有.pcd文件,通过键盘进行.pcd文件的更新(切换)。
期望通过 < >两个按键做到将当前点云数据切换为上一个或下一个.pcd文件,目前实现了C++的非阻塞获取键值和使用ros发布键盘话题两种方法。
一、非阻塞获取键值
#include <stdio.h>
#include <stdlib.h>
#include <string>
#include <iostream> //标准输入输出流
#include <pcl/io/pcd_io.h> //PCL的PCD格式文件的输入输出头文件
#include <pcl/point_types.h> //PCL对各种格式的点的支持头文件
#include <pcl/visualization/cloud_viewer.h>
#define TTY_PATH "/dev/tty"
#define STTY_US "stty raw -echo -F "
#define STTY_DEF "stty -raw echo -F "
using namespace std;
int get_char();
//非阻塞获取键值
int get_char()
{
fd_set rfds;
struct timeval tv;
int ch = 0;
FD_ZERO(&rfds);
FD_SET(0, &rfds);
tv.tv_sec = 0;
tv.tv_usec = 10; //设置等待超时时间
//检测键盘是否有输入
if (select(1, &rfds, NULL, NULL, &tv) > 0){
ch = getchar();
}
return ch;
}
int main(int argc, char** argv)
{
typedef pcl::PointXYZRGB PointT;
//pcl::PointCloud::Ptr cloud(new pcl::PointCloud);
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>); // 创建点云(指针)
int index = 1;
if (pcl::io::loadPCDFile("./"+to_string(index)+".pcd", *cloud) == -1) {
//* load the file
PCL_ERROR("Couldn't read PCD file \n");
return (-1);
}
printf("Loaded %d data points from PCD\n",
cloud->width * cloud->height);
pcl::visualization::PCLVisualizer viewer("Cloud viewer");
pcl::visualization::PointCloudColorHandlerCustom<pcl::PointXYZ> single_color(cloud, 255, 255, 255); // green
pcl::PointXYZ a, b, c, o;
o.x=0;
o.y=0;
o.z=0;
a.x=1000;
a.y=0;
a.z=0;
b.x=0;
b.y=1000;
b.z=0;
c.x=0;
c.y=0;
c.z=1000;
viewer.addLine(o, a, 255, 0, 0, "line1");
viewer.addLine(o, c, 0, 255, 0, "line2");
viewer.addLine(o, b, 0, 0, 255, "line3");
viewer.setCameraPosition(0, 0, -3.0, 0, -1, 0);
viewer.addCoordinateSystem(0.3);
// pcl::PointCloud<pcl::PointXYZ>::Ptr yuanzhu(new pcl::PointCloud<pcl::PointXYZ>);
viewer.addPointCloud(cloud,"123");
int ch = 0;
system(STTY_US TTY_PATH);
while(1){
ch = get_char();
switch (ch)
{
case ',':
index--;
cout<<index<<endl;
pcl::io::loadPCDFile("./"+to_string(index)+".pcd", *cloud) ;
viewer.updatePointCloud(cloud,"123");
break;
case '.':
index++;
printf("%d\t\n",index);
pcl::io::loadPCDFile("./"+to_string(index)+".pcd", *cloud) ;
viewer.updatePointCloud(cloud,"123");
break;
default:
viewer.spinOnce(100);
break;
}
}
}
二、使用ros发布键盘话题
直接下载小乌龟的键值获取节点,并修改重新设置新的节点和话题
修改后的代码
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include<base_sks_msgs/testmsg.h>
#include <signal.h>
#include <stdio.h>
#ifndef _WIN32
# include <termios.h>
# include <unistd.h>
#else
# include <windows.h>
#endif
#define KEYCODE_RIGHT 0x43
#define KEYCODE_LEFT 0x44
#define KEYCODE_UP 0x41
#define KEYCODE_DOWN 0x42
#define KEYCODE_B 0x62
#define KEYCODE_C 0x63
#define KEYCODE_D 0x64
#define KEYCODE_E 0x65
#define KEYCODE_F 0x66
#define KEYCODE_G 0x67
#define KEYCODE_Q 0x71
#define KEYCODE_R 0x72
#define KEYCODE_T 0x74
#define KEYCODE_V 0x76
class KeyboardReader
{
public:
KeyboardReader()
#ifndef _WIN32
: kfd(0)
#endif
{
#ifndef _WIN32
// get the console in raw mode
tcgetattr(kfd, &cooked);
struct termios raw;
memcpy(&raw, &cooked, sizeof(struct termios));
raw.c_lflag &=~ (ICANON | ECHO);
// Setting a new line, then end of file
raw.c_cc[VEOL] = 1;
raw.c_cc[VEOF] = 2;
tcsetattr(kfd, TCSANOW, &raw);
#endif
}
void readOne(char * c)
{
#ifndef _WIN32
int rc = read(kfd, c, 1);
if (rc < 0)
{
throw std::runtime_error("read failed");
}
#else
return;
}
#endif
}
void shutdown()
{
#ifndef _WIN32
tcsetattr(kfd, TCSANOW, &cooked);
#endif
}
private:
#ifndef _WIN32
int kfd;
struct termios cooked;
#endif
};
KeyboardReader input;
class TeleopTurtle
{
public:
TeleopTurtle();
void keyLoop();
private:
ros::NodeHandle nh_;
ros::Publisher msg_pub_;
};
TeleopTurtle::TeleopTurtle()
{
msg_pub_ = nh_.advertise<base_sks_msgs::testmsg>("testmsg", 1);
}
void quit(int sig)
{
(void)sig;
input.shutdown();
ros::shutdown();
exit(0);
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "teleop_turtle");
TeleopTurtle teleop_turtle;
signal(SIGINT,quit);
teleop_turtle.keyLoop();
quit(0);
return(0);
}
void TeleopTurtle::keyLoop()
{
char c;
bool dirty=false;
puts("Reading from keyboard");
puts("---------------------------");
puts("123.");
for(;;)
{
// get the next event from the keyboard
try
{
input.readOne(&c);
base_sks_msgs::testmsg msg;
msg.key = c;
msg_pub_.publish(msg);
}
catch (const std::runtime_error &)
{
perror("read():");
return;
}
ROS_DEBUG("value: 0x%02X\n", c);
switch(c)
{
case KEYCODE_Q:
ROS_DEBUG("quit");
return;
}
if(dirty ==true)
{
dirty=false;
}
}
return;
}