36 #define BOOST_PARAMETER_MAX_ARITY 7
38 #include <jsk_recognition_msgs/ICPAlign.h>
41 #include <pcl/filters/voxel_grid.h>
42 #include <pcl/filters/passthrough.h>
48 pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
49 DiagnosticNodelet::onInit();
53 pnh_->param(
"global_frame",
global_frame_, std::string(
"map"));
54 pnh_->param(
"odom_frame",
odom_frame_, std::string(
"odom"));
58 pnh_->param(
"initialize_tf",
initialize_tf_, std::string(
"odom_on_ground"));
62 pnh_->param(
"sensor_frame",
sensor_frame_, std::string(
"BODY"));
66 pnh_->param(
"cloud_rate", cloud_rate, 10.0);
68 pnh_->param(
"tf_rate", tf_rate, 20.0);
69 pub_cloud_ = pnh_->advertise<sensor_msgs::PointCloud2>(
"output", 1);
100 pcl::PointCloud<pcl::PointNormal>::Ptr in_cloud,
101 pcl::PointCloud<pcl::PointNormal>& out_cloud)
103 pcl::VoxelGrid<pcl::PointNormal> vg;
104 vg.setInputCloud(in_cloud);
106 vg.filter(out_cloud);
115 sensor_msgs::PointCloud2 ros_cloud;
117 ros_cloud.header.stamp =
stamp;
143 NODELET_FATAL(
"Failed to lookup transformation: %s", e.what());
148 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
150 vital_checker_->poke();
157 pcl::PointCloud<pcl::PointNormal>::Ptr
158 local_cloud (
new pcl::PointCloud<pcl::PointNormal>);
160 NODELET_INFO(
"waiting for tf transformation from %s tp %s",
168 pcl::PointCloud<pcl::PointNormal>::Ptr
169 input_cloud (
new pcl::PointCloud<pcl::PointNormal>);
182 pcl::PointCloud<pcl::PointNormal>::Ptr
183 input_downsampled_cloud (
new pcl::PointCloud<pcl::PointNormal>);
192 = pnh_->serviceClient<jsk_recognition_msgs::ICPAlign>(
"icp_align");
193 jsk_recognition_msgs::ICPAlign icp_srv;
205 cloud_msg->header.stamp,
207 Eigen::Affine3f global_sensor_transform;
209 global_sensor_transform);
210 pcl::PointCloud<pcl::PointNormal>::Ptr sensor_cloud
211 (
new pcl::PointCloud<pcl::PointNormal>);
212 pcl::transformPointCloudWithNormals(
215 global_sensor_transform.inverse());
217 pcl::PassThrough<pcl::PointNormal> pass;
218 pass.setInputCloud(sensor_cloud);
219 pass.setFilterFieldName(
"x");
220 pass.setFilterLimits(0.0, 100.0);
221 pcl::PointCloud<pcl::PointNormal>::Ptr filtered_cloud
222 (
new pcl::PointCloud<pcl::PointNormal>);
223 pass.filter(*filtered_cloud);
224 NODELET_INFO(
"clipping: %lu -> %lu", sensor_cloud->points.size(), filtered_cloud->points.size());
226 pcl::PointCloud<pcl::PointNormal>::Ptr global_filtered_cloud
227 (
new pcl::PointCloud<pcl::PointNormal>);
228 pcl::transformPointCloudWithNormals(
230 *global_filtered_cloud,
231 global_sensor_transform);
233 icp_srv.request.target_cloud);
237 icp_srv.request.target_cloud);
240 icp_srv.request.reference_cloud);
242 if (client.
call(icp_srv)) {
245 Eigen::Vector3f transform_pos(
transform.translation());
246 float roll, pitch, yaw;
247 pcl::getEulerAngles(
transform, roll, pitch, yaw);
254 pcl::PointCloud<pcl::PointNormal>::Ptr
255 transformed_input_cloud (
new pcl::PointCloud<pcl::PointNormal>);
257 pcl::transformPointCloudWithNormals(*input_cloud,
258 *transformed_input_cloud,
262 pcl::transformPointCloud(*input_cloud,
263 *transformed_input_cloud,
266 pcl::PointCloud<pcl::PointNormal>::Ptr
267 concatenated_cloud (
new pcl::PointCloud<pcl::PointNormal>);
268 *concatenated_cloud = *
all_cloud_ + *transformed_input_cloud;
275 boost::mutex::scoped_lock tf_lock(
tf_mutex_);
292 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
297 NODELET_ERROR(
"[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
309 std_srvs::Empty::Request&
req,
310 std_srvs::Empty::Response&
res)
319 jsk_recognition_msgs::UpdateOffset::Request&
req,
320 jsk_recognition_msgs::UpdateOffset::Response&
res)
323 geometry_msgs::TransformStamped next_pose =
req.transformation;