2015-05-27 15:22:52 +00:00
|
|
|
#include <ros/ros.h>
|
|
|
|
#include <pcl_ros/point_cloud.h>
|
|
|
|
#include <pcl/point_types.h>
|
2015-05-27 16:31:41 +00:00
|
|
|
#include <pcl/features/normal_3d_omp.h>
|
2015-05-27 15:22:52 +00:00
|
|
|
#include <hand_control/Plan.h>
|
|
|
|
#include <time.h>
|
|
|
|
#include <math.h>
|
|
|
|
|
|
|
|
#include <pcl/common/pca.h>
|
|
|
|
|
|
|
|
typedef pcl::PointXYZRGB Point;
|
|
|
|
typedef pcl::PointCloud<Point> PointCloud;
|
2015-05-27 16:31:41 +00:00
|
|
|
typedef Eigen::Matrix3f& Matrix;
|
2015-05-27 15:22:52 +00:00
|
|
|
|
|
|
|
class Callback {
|
|
|
|
public:
|
2015-05-27 21:28:43 +00:00
|
|
|
void operator()(const PointCloud::ConstPtr& msg)
|
2015-05-27 15:22:52 +00:00
|
|
|
{
|
|
|
|
ROS_INFO("PointCloud received");
|
|
|
|
|
2015-05-27 21:28:43 +00:00
|
|
|
if (msg->width > 3){
|
|
|
|
|
|
|
|
analyser.setInputCloud(msg);
|
|
|
|
Matrix eg = analyser.getEigenVectors();
|
|
|
|
|
|
|
|
float x, y, z, th, h, c;
|
|
|
|
x = y = z = th = h = c = 0.;
|
|
|
|
|
|
|
|
// we consider the whole PointCloud
|
|
|
|
std::vector<int> indices;
|
|
|
|
for (int i = 0; i < msg->points.size(); ++i)
|
|
|
|
indices.push_back(i);
|
|
|
|
|
|
|
|
// v = eg_1 ^ eg_2 is the plan normal
|
|
|
|
Eigen::Vector3f v = eg.col(0).cross(eg.col(1));
|
|
|
|
// norm(v) == 1
|
|
|
|
v.normalize();
|
|
|
|
x = v(0); y=v(1); z=v(2);
|
|
|
|
|
|
|
|
// h is the altitude
|
|
|
|
h = (analyser.getMean())(2);
|
|
|
|
|
|
|
|
// this formula is good only if :
|
|
|
|
// -pi/2 <= th <= pi/2
|
|
|
|
// ie cos(th) == m_x >= 0
|
|
|
|
float m_x(eg(0,0));
|
|
|
|
float m_y(eg(1,0));
|
|
|
|
if(x < 0)
|
|
|
|
{
|
|
|
|
m_x *= -1.;
|
|
|
|
m_y *= -1.;
|
|
|
|
}
|
|
|
|
th = 2 * atan(m_y / (1 + m_x));
|
|
|
|
// -pi/2 <= th <= pi/2
|
|
|
|
|
|
|
|
th *= _RAD2DEG;
|
|
|
|
// -90 <= th <= 90
|
|
|
|
|
|
|
|
// publication
|
|
|
|
ROS_INFO("Plan published");
|
|
|
|
publisher.publish(to_Plan(x, y, z, h, th, c, msg->header.seq, msg->header.stamp, msg->width));
|
2015-05-27 18:10:33 +00:00
|
|
|
}
|
2015-05-27 15:22:52 +00:00
|
|
|
}
|
|
|
|
|
2015-05-27 21:28:43 +00:00
|
|
|
Callback(ros::Publisher& pub):publisher(pub), _RAD2DEG(45.f/atan(1.)){};
|
2015-05-27 15:22:52 +00:00
|
|
|
|
|
|
|
private:
|
|
|
|
ros::Publisher publisher;
|
2015-05-27 16:31:41 +00:00
|
|
|
pcl::PCA<Point> analyser;
|
2015-05-27 21:28:43 +00:00
|
|
|
const float _RAD2DEG;
|
2015-05-27 15:22:52 +00:00
|
|
|
|
2015-05-27 21:28:43 +00:00
|
|
|
inline const hand_control::Plan::ConstPtr
|
|
|
|
to_Plan(const float& x, const float& y,
|
|
|
|
const float& z, const float& h,
|
|
|
|
const float& th,
|
|
|
|
const float& c, const uint32_t& seq,
|
|
|
|
const uint64_t& msec64, const uint64_t& number)
|
|
|
|
{
|
|
|
|
hand_control::Plan::Ptr ros_msg(new hand_control::Plan());
|
|
|
|
ros_msg->normal.x = x;
|
|
|
|
ros_msg->normal.y = y;
|
|
|
|
ros_msg->normal.z = z;
|
|
|
|
ros_msg->altitude = h;
|
|
|
|
ros_msg->angle = th;
|
|
|
|
ros_msg->curvature = c;
|
|
|
|
ros_msg->number = number;
|
|
|
|
// uint64_t msec64 is in ms (10-6)
|
|
|
|
uint64_t sec64 = msec64 / 1000000;
|
|
|
|
uint64_t nsec64 = (msec64 % 1000000) * 1000;
|
|
|
|
ros_msg->header.stamp.sec = (uint32_t) sec64;
|
|
|
|
ros_msg->header.stamp.nsec = (uint32_t) nsec64;
|
|
|
|
ros_msg->header.seq = seq;
|
|
|
|
ros_msg->header.frame_id = "0";
|
|
|
|
return ros_msg;
|
|
|
|
}
|
2015-05-27 15:22:52 +00:00
|
|
|
};
|
|
|
|
|
2015-05-27 21:28:43 +00:00
|
|
|
int main(int argc, char** argv)
|
2015-05-27 15:22:52 +00:00
|
|
|
{
|
2015-05-27 21:28:43 +00:00
|
|
|
ros::init(argc, argv, "estimator");
|
|
|
|
ros::NodeHandle node("estimator");
|
2015-05-27 15:22:52 +00:00
|
|
|
|
|
|
|
ros::Publisher publisher = node.advertise<hand_control::Plan>("output", 1);
|
|
|
|
Callback callback(publisher);
|
|
|
|
ros::Subscriber subscriber = node.subscribe<PointCloud>("input", 1, callback);
|
|
|
|
|
|
|
|
ROS_INFO("node started");
|
|
|
|
ros::spin();
|
|
|
|
ROS_INFO("exit");
|
|
|
|
return 0;
|
|
|
|
}
|