koide3 / hdl_localization

Real-time 3D localization using a (velodyne) 3D LIDAR
BSD 2-Clause "Simplified" License
798 stars 315 forks source link

error: no matching function for call to ‘transformPointCloud #77

Open Dysonsun opened 3 years ago

Dysonsun commented 3 years ago
src/hdl_localizaton/apps/hdl_localization_nodelet.cpp:209:94: error: no matching function for call to ‘transformPointCloud(std::__cxx11::string&, pcl::PointCloud<pcl::PointXYZI>&, pcl::PointCloud<pcl::PointXYZI>&, tf2_ros::Buffer&)’
     if(!pcl_ros::transformPointCloud(odom_child_frame_id, *pcl_cloud, *cloud, this->tf_buffer)) {

when i open the #include <pcl_ros/transforms.h> I find
template bool transformPointCloudWithNormals (const std::string &target_frame, const pcl::PointCloud &cloud_in, pcl::PointCloud &cloud_out, const tf::TransformListener &tf_listener); which means tf_listener is tf::TransformListener but not this->tf_buffer(tf2_ros::TransformListener)

how to fix it?

sihanh commented 3 years ago

hi i am experiencing the same issue, did you fix it?

Dysonsun commented 3 years ago

I delete this line

At 2021-05-21 13:28:25, "sihanh" @.***> wrote:

hi i am experiencing the same issue, did you fix it?

— You are receiving this because you authored the thread. Reply to this email directly, view it on GitHub, or unsubscribe.

sihanh commented 3 years ago

I delete this line At 2021-05-21 13:28:25, "sihanh" @.***> wrote: hi i am experiencing the same issue, did you fix it? — You are receiving this because you authored the thread. Reply to this email directly, view it on GitHub, or unsubscribe.

Yeah I tracked the problem. The reason is that in ros-kinetic, the pcl_ros library transforms.h has no matching function template with relative input. You can either upgrade the pcl version or adding functions by yourself, I added it myself and fixed it.

clobot-nate commented 3 years ago

You can install pcl 1.8.0 version manually.

Shangareer commented 3 years ago

The newest version of hdl_localization uses tf2 instead of tf in "hdl_localization_nodelet.cpp", but pcl_ros in ros-kinetic does not support for tf2. Thanks to the author, who kept the history version in branch "global_localization" that still used tf. If you have the same issue, try to change the "master" branch to "global_localization" branch (https://github.com/koide3/hdl_localization/tree/global_localization) and download it. Note that the "global_localization" here differs from "hdl_global_localization" which is another program downloaded by "git clone https://github.com/koide3/hdl_global_localization". After doing this, you may encounter error like "error: 'atomic_bool' in namespace 'std' does not name a type". Don't worry, this can solved by changing "-std=c++11" to "-std=c++14" in "CMakeLists.txt" and adding header file "#include<atomic>" in "hdl_localization_nodelet.cpp". It worked for me in ubuntu16.04 + ros-kinetic. Good Luck!

wjh731 commented 2 years ago
    // transform pointcloud into odom_child_frame_id
    pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>());
    /*if(!pcl_ros::transformPointCloud(odom_child_frame_id, *pcl_cloud, *cloud, this->tf_buffer)) {
        NODELET_ERROR("point cloud cannot be transformed into target frame!!");
        return;
    } */

    tf::TransformListener tf_listener;
    if(!tf_listener.canTransform(odom_child_frame_id, pcl_cloud->header.frame_id, ros::Time(0))) {
        std::cerr << "failed to find transform between " << odom_child_frame_id << " and " << pcl_cloud->header.frame_id << std::endl;
    }

    tf::StampedTransform transform;
    tf_listener.waitForTransform(odom_child_frame_id, pcl_cloud->header.frame_id, ros::Time(0), ros::Duration(2.0));
    tf_listener.lookupTransform(odom_child_frame_id, pcl_cloud->header.frame_id, ros::Time(0), transform);

    //okagv
    if(!transformPointCloud(odom_child_frame_id,*pcl_cloud,*cloud, tf_listener)) {
      NODELET_ERROR("point cloud cannot be transformed into target frame!!");
      return;
    }
bool transformPointCloud (const std::string &target_frame, const pcl::PointCloud <PointT> &cloud_in,
                     pcl::PointCloud <PointT> &cloud_out, const tf::TransformListener &tf_listener)
{
  if (cloud_in.header.frame_id == target_frame)
  {
    cloud_out = cloud_in;
    return (true);
  }

  tf::StampedTransform transform;
  try
  {
    tf_listener.lookupTransform (target_frame, cloud_in.header.frame_id, 
                                              pcl_conversions::fromPCL(cloud_in.header).stamp, transform);
  }
  catch (tf::LookupException &e)
  {
    ROS_ERROR ("%s", e.what ());
    return (false);
  }
  catch (tf::ExtrapolationException &e)
  {
    ROS_ERROR ("%s", e.what ());
    return (false);
  }
  transformPointCloud (cloud_in, cloud_out, transform);
  cloud_out.header.frame_id = target_frame;
  return (true);
}

void transformPointCloud (const pcl::PointCloud <PointT> &cloud_in, 
                               pcl::PointCloud <PointT> &cloud_out, const tf::Transform &transform)
{
  tf::Quaternion q = transform.getRotation ();
  Eigen::Quaternionf rotation (q.w (), q.x (), q.y (), q.z ());       // internally stored as (x,y,z,w)
  tf::Vector3 v = transform.getOrigin ();
  Eigen::Vector3f origin (v.x (), v.y (), v.z ());
  pcl::transformPointCloud (cloud_in, cloud_out, origin, rotation);
}

You can change the code like above. Because it require tf2_ros::Buffer, you can change to tf. Need add two transform function if in pcl 1.7 and kinetic system.

zzppphone163 commented 1 year ago

The newest version of hdl_localization uses tf2 instead of tf in "hdl_localization_nodelet.cpp", but pcl_ros in ros-kinetic does not support for tf2. Thanks to the author, who kept the history version in branch "global_localization" that still used tf. If you have the same issue, try to change the "master" branch to "global_localization" branch (https://github.com/koide3/hdl_localization/tree/global_localization) and download it. Note that the "global_localization" here differs from "hdl_global_localization" which is another program downloaded by "git clone https://github.com/koide3/hdl_global_localization". After doing this, you may encounter error like "error: 'atomic_bool' in namespace 'std' does not name a type". Don't worry, this can solved by changing "-std=c++11" to "-std=c++14" in "CMakeLists.txt" and adding header file "#include<atomic>" in "hdl_localization_nodelet.cpp". It worked for me in ubuntu16.04 + ros-kinetic. Good Luck!


thanks!

wjh731 commented 1 year ago

亲的邮件已经收到,会尽快回复~