Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

3D/2D Sensor Mounted in Vertical Way #86

Closed
David9696 opened this issue Mar 2, 2023 · 9 comments
Closed

3D/2D Sensor Mounted in Vertical Way #86

David9696 opened this issue Mar 2, 2023 · 9 comments

Comments

@David9696
Copy link

Hi,

Thanks for sharing this package.

I have a setup in which my lidar is mounted in vertical way, rotate 90 degree roll from horizontal axis.

I have tried this package with my setup, But it doesn't work. The local map is always shown in horizontal axis.

Could this package works if the lidar is mounted in vertical way?

Thanks.

@benemer
Copy link
Member

benemer commented Mar 3, 2023

Hey!

Could you please be more precise about what you mean by it doesn't work? Does the registration fail? Can you post a screenshot of what the map looks like?

@David9696
Copy link
Author

Hi,

Thanks for your reply. Sorry for not being clear.

Screenshot from 2023-03-04 22-12-08

I have mounted my 2D lidar as above.

The output is as follows:

Screenshot from 2023-03-04 22-02-29

The red line is my 2D Lidar which is mounted vertically wrt base link. The yellow line is the generated local map.

"it doesn't work" refers to the 2D lidar line and generated local map are not in the same plane or ovelapped.

Hope I have made it clear.

Thanks.

@benemer
Copy link
Member

benemer commented Mar 7, 2023

Thank you! Maybe @tizianoGuadagnino or @nachovizzo can help here?

@tizianoGuadagnino
Copy link
Collaborator

Hi @David9696,

could you please send us the data? I want to have a look to better understand what the issue might be.

@David9696
Copy link
Author

Hi @tizianoGuadagnino

The required bag file is attached.

https://drive.google.com/file/d/1hbLbN-jSrOhNq1SBZOIc25E58qQaVuRE/view?usp=share_link

In this bag file, it contains /cloud,/tf and/tf_static topic.

Thanks.

@tizianoGuadagnino
Copy link
Collaborator

Hi @David9696, I think the problem is that you are moving in an ortogonal direction with respect to the scan line of the 2D LiDAR. As such, you simply cannot compute an odometry with this data because there is no overlap between successive scan frames. If this was a 3D LiDAR the odometry can succeed because you will have at least some common observed region in the two pointclouds, but in the 2D case is just impossible.

@David9696
Copy link
Author

Hi @tizianoGuadagnino

Thanks for your analysis. In the bag file, I only moved the lidar forward and backward along the 2D lidar axis. There are some common regions when I moved forward and backward. But, the generated local map is still not in the correct orientation.

FYI, I have tested with my 3D lidar which is mounted in vertical way as well. Although there are some common regions, the generated local map is still not in the correct orientation.

I think it might be related to some TF transformation. I would study further.

Thanks for your great help.

@maxkremmel
Copy link

I think this Issue is related to my Issue #174 where I still haven't found a solution.
After some more trail and error, I assume that KISS needs to know where (in which frame) the scanner is located on the robot. But I still haven't figured out which parameters are responsible for this.

Maybe someone could explain to me how the parameters odom_frame and child_frame work and how they are used.

This could also help @David9696.

Here I linked a rosbag of my setup: https://drive.google.com/file/d/1WoGUFF5nt0fvo7RlQExoEs6ycimKRF4K/view?usp=sharing

Basically what I want is that base_link just turn when I turn the robot, currently it is drifting around (or more precise, base_links behaves like it is the velodyne frame. In my issue (#174) is a GIF that illustrates this well.

Thanks, in advance!

@maxkremmel
Copy link

Hi all,
I managed to solve my problem...probably this is also the solution for @David9696.
I wrote a small node that transforms incoming laser scan messages from the velodyne frame into the base_link frame.
For all that are interested, here is the code of the node:

#include <ros/ros.h>
#include <tf2_ros/transform_listener.h>
#include <tf2_eigen/tf2_eigen.h>
#include <geometry_msgs/TransformStamped.h>
#include <sensor_msgs/PointCloud2.h>
#include <pcl/common/transforms.h>
#include <pcl_ros/point_cloud.h>

class TransformLaserScan
{
public:
    TransformLaserScan(ros::NodeHandle &nTemp) : n(nTemp)
    {
        // Publisher und Subscriber initialisieren
        LaserScanSub = n.subscribe<sensor_msgs::PointCloud2>("/velodyne_points", 10, &TransformLaserScan::callback, this);
        LaserScanPub = n.advertise<sensor_msgs::PointCloud2>("/transformed_laserscan", 1000);
        listener = new tf2_ros::TransformListener(tfBuffer); // TransformListener mit Buffer initialisieren

        try
        {
            transform = tfBuffer.lookupTransform("base_link", "velodyne", ros::Time(0), ros::Duration(3.0)); // Nach Transformation suchen (Timeout von 3 Sekunden)
        }
        catch (tf2::TransformException &ex)
        {
            ROS_WARN("%s", ex.what());
            ros::Duration(1.0).sleep();
        }
    }
    // Die callback Funktion transformiert jede Message des LiDAR Scanners vom velodyne Frame in den base_link Frame
    void callback(const sensor_msgs::PointCloud2ConstPtr &input_scan)
    {
        pcl::PointCloud<pcl::PointXYZ> pcl_input_scan;
        pcl::fromROSMsg(*input_scan, pcl_input_scan);       // Message des Laserscanners von einem ROS Datentypen in einen PCL Datentypen kovertieren
        pcl::PointCloud<pcl::PointXYZ> pcl_transfromed_scan;
        pcl::transformPointCloud(pcl_input_scan, pcl_transfromed_scan, tf2::transformToEigen(transform).matrix()); // Transformation erfolgt hier
        sensor_msgs::PointCloud2 transfromed_scan;          
        pcl::toROSMsg(pcl_transfromed_scan, transfromed_scan); // Transformierte Punktwolke in einen ROS Datentyp konvertieren
        LaserScanPub.publish(transfromed_scan);     // Publishen des transformierten Laserscans
    }

private:
    ros::NodeHandle n;
    ros::Subscriber LaserScanSub;
    ros::Publisher LaserScanPub;
    geometry_msgs::TransformStamped transform; // Transformation von velodyne Frame zu base_link Frame
    tf2_ros::Buffer tfBuffer;
    tf2_ros::TransformListener *listener;
};

int main(int argc, char **argv)
{
    ros::init(argc, argv, "TransformLaserScan");
    ros::NodeHandle n;
    TransformLaserScan Node(n);
    ros::spin();
    return 0;
}

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants