Illegal Instruction when reading PCD/PLY files readHeader()
EDIT I've narrowed down the issue to reading of PCD/PLY files, so the question has basically changed...
I have been stuck on this issue for days, and finally I've given up and decided to ask for help:
I am trying to run a variation of my_pcl_tutorial, but instead of receiving a point cloud via subscription, I am still setting up a subscriber, but then reading the cloud from a pcb file and then publishing it (via a message forwarder node to avoid sub/pub of the same topic on a single node) on the same topic I am subscribing to. Here is my main():
int main (int argc, char** argv)
{
// Initialize ROS
ros::init (argc, argv, "my_pcl_tutorial");
// Load from file
pcl::PointCloud<pcl::PointXYZ>::Ptr pcloud(new pcl::PointCloud<pcl::PointXYZ>);
//sensor_msgs::PointCloud2::Ptr pcloud(new sensor_msgs::PointCloud2);
if ( pcl::io::loadPCDFile<pcl::PointXYZ> ("/home/user/Documents/table_scene_lms400.pcd", *pcloud) == -1) // load the file
{
std::cout << "Couldn't read file!\n";
return (-1);
}
std::cout << "Loaded " << pcloud->points.size () << " points." << std::endl;
//set up publishers and subscribers
ros::NodeHandle nh;// = ros::NodeHandle(ros::this_node::getName());
ros::Duration(5).sleep();
ros::Publisher pubcloud = nh.advertise<sensor_msgs::PointCloud2> ("/inputforwarder", 1);
ros::Subscriber sub = nh.subscribe ("/input", 1, cloud_cb);
//puboutput = nh.advertise<sensor_msgs::PointCloud2> ("/output", 1);
puboutput = nh.advertise<pcl::ModelCoefficients> ("/output", 1);
ros::Duration(5).sleep();
//publish cloud
sensor_msgs::PointCloud2 pc2;
pcl::toROSMsg(*pcloud, pc2);
pubcloud.publish(pc2);
// Spin
ros::spin ();
return (0);
}
Which gives me the error on my loadPCDFile():
Starting program: /home/user/ros_workspace/my_pcl_tutorial/bin/example
[Thread debugging using libthread_db enabled]
Using host libthread_db library "/lib/x86_64-linux-gnu/libthread_db.so.1".
Program received signal SIGILL, Illegal instruction.
0x00007ffff6f4b1a1 in pcl17::PCDReader::readHeader(std::string const&, sensor_msgs::PointCloud2_<std::allocator<void> >&, Eigen::Matrix<float, 4, 1, 0, 4, 1>&, Eigen::Quaternion<float, 0>&, int&, int&, unsigned int&, int) ()
from /home/user/ros_workspace/fuerte-unstable-devel/pcl17/lib/libpcl_io.so.1.7
(gdb) bt
#0 0x00007ffff6f4b1a1 in pcl17::PCDReader::readHeader(std::string const&, sensor_msgs::PointCloud2_<std::allocator<void> >&, Eigen::Matrix<float, 4, 1, 0, 4, 1>&, Eigen::Quaternion<float, 0>&, int&, int&, unsigned int&, int) ()
from /home/user/ros_workspace/fuerte-unstable-devel/pcl17/lib/libpcl_io.so.1.7
#1 0x00007ffff6f48af4 in pcl17::PCDReader::read(std::string const&, sensor_msgs::PointCloud2_<std::allocator<void> >&, Eigen::Matrix<float, 4, 1, 0, 4, 1>&, Eigen::Quaternion<float, 0>&, int&, int) ()
from /home/user/ros_workspace/fuerte-unstable-devel/pcl17/lib/libpcl_io.so.1.7
#2 0x000000000044e9f4 in pcl17::PCDReader::read<pcl17::PointXYZ> (
this=0x7fffffffd970, file_name=..., cloud=..., offset=0)
at /home/user/ros_workspace/fuerte-unstable-devel/pcl17/include/pcl-1.7/pcl17/io/pcd_io.h:209
#3 0x000000000044af8e in pcl17::io::loadPCDFile<pcl17::PointXYZ> (
file_name=..., cloud=...)
at /home/user/ros_workspace/fuerte-unstable-devel/pcl17/include/pcl-1.7/pcl17/io/pcd_io.h:544
#4 0x0000000000445afd in main (argc=1, argv=0x7fffffffdd38)
at /home/user/ros_workspace/my_pcl_tutorial/src/example.cpp:72
which boils down to an issue in readHeader().
It is finding the file just fine, in case you were wondering. I've tried multiple PCD and PLY ...