36 #define BOOST_PARAMETER_MAX_ARITY 7
44 DiagnosticNodelet::onInit();
45 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
46 typename dynamic_reconfigure::Server<Config>::CallbackType
f =
48 srv_->setCallback (
f);
50 pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
"output", 1);
51 pub_xyz_ = advertise<sensor_msgs::PointCloud2>(*pnh_,
"output_xyz", 1);
71 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
83 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
84 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
86 if (polygon_msg->polygons.size() == 0) {
90 if (coefficients_msg->coefficients.size() != polygon_msg->polygons.size()) {
91 NODELET_ERROR(
"The size of coefficients and polygons are not same");
95 std::string
frame_id = polygon_msg->header.frame_id;
96 for (
size_t i = 0;
i < polygon_msg->polygons.size();
i++) {
97 if (
frame_id != polygon_msg->polygons[
i].header.frame_id) {
100 polygon_msg->polygons[
i].header.frame_id.c_str());
104 for (
size_t i = 0;
i < coefficients_msg->coefficients.size();
i++) {
105 if (
frame_id != coefficients_msg->coefficients[
i].header.frame_id) {
108 coefficients_msg->coefficients[
i].header.frame_id.c_str());
116 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
117 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
120 vital_checker_->poke();
126 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr
cloud (
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
127 pcl::PointCloud<pcl::PointXYZ>::Ptr xyz_cloud (
new pcl::PointCloud<pcl::PointXYZ>);
128 for (
size_t i = 0;
i < polygon_msg->polygons.size();
i++) {
131 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr one_cloud
133 pcl::PointCloud<pcl::PointXYZ> one_xyz_cloud;
134 one_xyz_cloud.points.resize(one_cloud->points.size());
135 for (
size_t i = 0;
i < one_cloud->points.size();
i++) {
137 p.getVector3fMap() = one_cloud->points[
i].getVector3fMap();
138 one_xyz_cloud.points[
i] =
p;
140 *xyz_cloud = *xyz_cloud + one_xyz_cloud;
143 sensor_msgs::PointCloud2 ros_cloud;
145 ros_cloud.header = polygon_msg->header;
147 sensor_msgs::PointCloud2 ros_xyz_cloud;
149 ros_xyz_cloud.header = polygon_msg->header;