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();
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)
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)) {
243 Eigen::Affine3f transform;
245 Eigen::Vector3f transform_pos(transform.translation());
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;
std::string sensor_frame_
void transformEigenToTF(const Eigen::Affine3d &e, tf::Transform &t)
bool clip_unseen_pointcloud_
#define NODELET_ERROR(...)
void transformPointCloudWithNormals(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
tf::Transform localize_transform_
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
tf::StampedTransform lookupTransformWithDuration(tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration)
bool call(MReq &req, MRes &res)
ros::Publisher pub_cloud_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
callback function of ~input topic.
tf::TransformListener * tf_listener_
ros::ServiceServer localization_srv_
virtual void applyDownsampling(pcl::PointCloud< pcl::PointNormal >::Ptr in_cloud, pcl::PointCloud< pcl::PointNormal > &out_cloud)
pcl::PointCloud< pcl::PointNormal >::Ptr all_cloud_
ros::ServiceServer update_offset_srv_
sensor_msgs::PointCloud2::ConstPtr latest_cloud_
virtual bool localizationRequest(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
callback function of ~localize service.
bool use_normal_
Resolution of voxel grid.
std::string global_frame_
Publishes tf transformation of global_frame_ -> odom_frame_.
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::PointCloudLocalization, nodelet::Nodelet)
virtual void unsubscribe()
virtual void cloudTimerCallback(const ros::TimerEvent &event)
cloud periodic timer callback
#define NODELET_INFO(...)
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
std::string initialize_tf_
static tf::TransformListener * getInstance()
tf::TransformBroadcaster tf_broadcast_
#define NODELET_FATAL(...)
virtual bool isFirstTime()
return true if it is the first time to localize
virtual bool updateOffsetCallback(jsk_recognition_msgs::UpdateOffset::Request &req, jsk_recognition_msgs::UpdateOffset::Response &res)
callback function for ~update_offset service
virtual void tfTimerCallback(const ros::TimerEvent &event)
tf periodic timer callback
static void transformStampedMsgToTF(const geometry_msgs::TransformStamped &msg, StampedTransform &bt)