squelette classe Callback

This commit is contained in:
Louis-Guillaume DUBOIS 2015-04-23 14:22:53 +02:00
parent 5fa9d37571
commit 0c093313dc

View file

@ -9,16 +9,42 @@ 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
const ROSCoord::ConstPtr
PCLCoord_to_ROSCoord(const PCLCoord& pcl_coord)
{
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;
}
class Callback {
public:
void
operator()(const PointCloud::ConstPtr& msg)
{
ROS_INFO("PointCloud received");
PCLCoord 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));
*/
}
Callback(ros::Publisher& pub) : publisher(pub), estimator() {}
private:
ros::Publisher publisher;
pcl::NormalEstimationOMP<Point, pcl::Normal> estimator;
const ROSCoord::ConstPtr
to_ROSCoord(const PCLCoord& pcl_coord)
{
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;
}
};
int
main(int argc, char** argv)