|
|
|
@ -2,12 +2,10 @@ |
|
|
|
#include <pcl_ros/point_cloud.h> |
|
|
|
#include <pcl/point_types.h> |
|
|
|
#include <pcl/features/normal_3d.h> |
|
|
|
#include <geometry_msgs/Quaternion.h> |
|
|
|
#include <hand_control/Plan.h> |
|
|
|
|
|
|
|
typedef pcl::PointXYZRGB Point; |
|
|
|
typedef pcl::PointCloud<Point> PointCloud; |
|
|
|
typedef Eigen::Vector4f PCLCoord; // vecteur, accès par v(0), v(1)...
|
|
|
|
typedef geometry_msgs::Quaternion ROSCoord; // struct : x, y, z, w
|
|
|
|
|
|
|
|
class Callback { |
|
|
|
public: |
|
|
|
@ -15,16 +13,15 @@ class Callback { |
|
|
|
operator()(const PointCloud::ConstPtr& msg) |
|
|
|
{ |
|
|
|
ROS_INFO("PointCloud received"); |
|
|
|
PCLCoord pcl_coord(); |
|
|
|
Eigen::Vector4f pcl_coord(); |
|
|
|
float curvature; |
|
|
|
std::vector<int> indices(); |
|
|
|
// TODO : choisir tous les indices
|
|
|
|
estimator.computePointNormal(*msg, indices, |
|
|
|
PCLCoord, curvature); |
|
|
|
/* TODO
|
|
|
|
if (curvature < ? |
|
|
|
publisher.publish(to_ROSCoord(pcl_coord)); |
|
|
|
*/ |
|
|
|
pcl_coord, curvature); |
|
|
|
// publication
|
|
|
|
ROS_INFO("Plan published") |
|
|
|
publisher.publish(to_Plan(pcl_coord, curvature)); |
|
|
|
} |
|
|
|
|
|
|
|
Callback(ros::Publisher& pub) : publisher(pub), estimator() {} |
|
|
|
@ -32,17 +29,18 @@ class Callback { |
|
|
|
private: |
|
|
|
ros::Publisher publisher; |
|
|
|
|
|
|
|
pcl::NormalEstimationOMP<Point, pcl::Normal> estimator; |
|
|
|
pcl::NormalEstimationOMP<Point, Eigen::Vector4f> estimator; |
|
|
|
|
|
|
|
const ROSCoord::ConstPtr |
|
|
|
to_ROSCoord(const PCLCoord& pcl_coord) |
|
|
|
const hand_control::Plan::ConstPtr |
|
|
|
to_Plan(const Eigen::Vector4f& pcl_coord, const float& curvature) |
|
|
|
{ |
|
|
|
ROSCoord::Ptr ros_coord(new ROSCoord()); |
|
|
|
ros_coord->x = pcl_coord(0); // a
|
|
|
|
ros_coord->y = pcl_coord(1); // b
|
|
|
|
ros_coord->z = pcl_coord(2); // c
|
|
|
|
ros_coord->w = pcl_coord(3); // d
|
|
|
|
return ros_coord; |
|
|
|
hand_control::Plan::Ptr ros_msg(new Plan()); |
|
|
|
ros_msg->normal.x = pcl_coord(0); // a
|
|
|
|
ros_msg->normal.y = pcl_coord(1); // b
|
|
|
|
ros_msg->normal.z = pcl_coord(2); // c
|
|
|
|
ros_msg->altitude = pcl_coord(3); // d
|
|
|
|
ros_msg->curvature = curvature; // \lambda
|
|
|
|
return ros_msg; |
|
|
|
} |
|
|
|
}; |
|
|
|
|
|
|
|
@ -53,8 +51,9 @@ main(int argc, char** argv) |
|
|
|
ros::NodeHandle node("estimator"); |
|
|
|
|
|
|
|
// initialisation
|
|
|
|
ros::Publisher publisher = node.advertise<ROSCoord>("output", 1); |
|
|
|
ros::Publisher publisher = node.advertise<hand_control::Plan>("output", 1); |
|
|
|
Callback callback(publisher); |
|
|
|
|
|
|
|
ros::Subscriber subscriber = node.subscribe<PointCloud>("input", 1, callback); |
|
|
|
|
|
|
|
// démarrage
|
|
|
|
|