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

是否能够发布livox_ros_driver::CustomMsg消息? #15

Closed
cckaixin opened this issue May 14, 2023 · 4 comments
Closed

是否能够发布livox_ros_driver::CustomMsg消息? #15

cckaixin opened this issue May 14, 2023 · 4 comments

Comments

@cckaixin
Copy link

  您好,首先感谢您开源的这个Livox雷达模拟器,给我带来了很大的方便。
  我在使用的过程中遇到了点云消息格式上的问题。我的需求是在gazebo中仿真livox雷达,并使用fast-lio来做定位。但是livox_laser_simulation发布的点云格式为sensor_msgs::PointCloud,并不是按照Livox的驱动格式livox_ros_driver::CustomMsg发布的,这就导致我没有办法用fast-lio来做定位导航。
   所以我的问题是:目前的livox_laser_simulation是否本就可以发布livox_ros_driver::CustomMsg格式的点云;另外,如果目前的模拟器不能发布livox_ros_driver::CustomMsg格式的点云,那么我应该如何修改这个模拟器,使之能够满足我的需求?
@cckaixin
Copy link
Author

自问自答:目前已通过修改消息格式,将发布的点云更改成我需要的livox_ros_driver::CustomMsg格式

@engcang
Copy link

engcang commented Jun 23, 2023

Hi @cckaixin.
Can you share the modified version of the code please?

@cckaixin
Copy link
Author

ok, i have revised the following function:

void LivoxPointsPlugin::OnNewLaserScans() {
    if (rayShape) 
    {
        std::vector<std::pair<int, AviaRotateInfo>> points_pair;
        InitializeRays(points_pair, rayShape);
        rayShape->Update();

        msgs::Set(laserMsg.mutable_time(), world->SimTime());
        msgs::LaserScan *scan = laserMsg.mutable_scan();
        InitializeScan(scan);

        SendRosTf(parentEntity->WorldPose(), world->Name(), raySensor->ParentName());

        auto rayCount = RayCount();
        auto verticalRayCount = VerticalRayCount();
        auto angle_min = AngleMin().Radian();
        auto angle_incre = AngleResolution();
        auto verticle_min = VerticalAngleMin().Radian();
        auto verticle_incre = VerticalAngleResolution();
////////////////////////////////////////////////
//revised by ckx frome cloud to cloud2 msg
//////////////////////////////////////////////// START

        livox_ros_driver::CustomMsg pp_livox;
        pp_livox.header.stamp = ros::Time::now();
        pp_livox.header.frame_id = "livox";
        int count = 0;
        boost::chrono::high_resolution_clock::time_point start_time = boost::chrono::high_resolution_clock::now();
        
        for (auto &pair : points_pair)
        {
            auto range = rayShape->GetRange(pair.first);
            auto intensity = rayShape->GetRetro(pair.first);
            if (range >= RangeMax()) {
                range = 0;
            } else if (range <= RangeMin()) {
                range = 0;
            }
            auto rotate_info = pair.second;
            ignition::math::Quaterniond ray;
            ray.Euler(ignition::math::Vector3d(0.0, rotate_info.zenith, rotate_info.azimuth));
            auto axis = ray * ignition::math::Vector3d(1.0, 0.0, 0.0);
            auto point = range * axis;

            livox_ros_driver::CustomPoint p;
            p.x = point.X();
            p.y = point.Y();
            p.z = point.Z();
            p.reflectivity = intensity;
            boost::chrono::high_resolution_clock::time_point end_time = boost::chrono::high_resolution_clock::now();
            boost::chrono::nanoseconds elapsed_time = boost::chrono::duration_cast<boost::chrono::nanoseconds>(end_time - start_time);
            // std::cout << "Elapsed time: " << elapsed_time.count() << " microseconds" << std::endl;

            p.offset_time = elapsed_time.count();
            pp_livox.points.push_back(p);
            count ++;
        }

        if (scanPub && scanPub->HasConnections()) scanPub->Publish(laserMsg);
        pp_livox.point_num = count;
        // ROS_INFO_STREAM("pp_livox.point_num: " << pp_livox.point_num << " !");

        livox_pub.publish(pp_livox);
        ros::spinOnce();
    }

////////////////////////////////////////////////
// revised by ckx frome cloud to cloud2 msg
//////////////////////////////////////////////// END
}

and include this header:

#include <livox_ros_driver/CustomMsg.h>

also, you should modify CMakelists.txt by adding livox_ros_driver:

find_package(catkin REQUIRED COMPONENTS
  roscpp
  tf
  livox_ros_driver
)

and include livox_ros_driver package into your worksapce accordingly.

hope you can fix it : )
ckx

@engcang
Copy link

engcang commented Jun 24, 2023

@cckaixin Hi. Thank you for sharing the code!
I coded myself right after the question but yours looks much better :) I will change mine referring yours.
For future users, you guys can refer this repo: https://github.com/engcang/livox_laser_simulation

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

2 participants