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

feat:livox-hap LIDAR adapted successfully #1

Open
wants to merge 2 commits into
base: master
Choose a base branch
from

Conversation

zymouse
Copy link

@zymouse zymouse commented Nov 9, 2023

Adaptation of lidar types:

  • Solid State
  • livox had

lidar driver

livox_ros_driver2
Livox-SDK2

Test results:

Successful test, successfully output normal external reference results
image

@xmfcx

Copy link

@StepTurtle StepTurtle left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for your contribution, it looks great. Sorry for late answer.

In addition to reviews, could you remove the result txt's and yaml files instead of simu.yaml

After these changes i think we can merge your commits.

Also I changed Hesai parser code with your changes in this commit. I think i did something wrong and Hesai point cloud looks a little bit broken but right now it looks okey. Thanks again.

@@ -17,11 +17,10 @@ use_gui: false
# 当 segment_num = 1时,即用一段数据标定
segment_num: 1
selected_segment:
- {start_time: 0, end_time: 7, path_bag: /home/ha/catkin_oa_calib/src/OA-LICalib/data/bag/simu_bag.bag}
- {start_time: 0, end_time: 7, path_bag: /root/calib_ws/src/OA-LICalib/data/bag/simu_bag.bag}

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Could you change this with

Suggested change
- {start_time: 0, end_time: 7, path_bag: /root/calib_ws/src/OA-LICalib/data/bag/simu_bag.bag}
- {start_time: 0, end_time: 7, path_bag: /root/catkin_oa_calib/src/OA-LICalib/data/bag/simu_bag.bag}

Also could you change the docker run command in README.md with this:

"docker run -it --env="DISPLAY" --volume="$HOME/.Xauthority:/root/.Xauthority:rw" --volume="/tmp/.X11-unix:/tmp/.X11-unix:rw" --volume="$REPO_PATH:/root/catkin_oa_calib/src/OA-LICalib" calib:v1 bash"

Its look the volume path is wrong so if we change this, everything will okay.



# If you select false, it calculate initial rotations.
# If you know the approximate conversion between the sensors, set true.
# 平面运动时,旋转外参无法初始化

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

English comments are more inclusive for us. Please use English comments.

@@ -238,7 +238,8 @@ int main(int argc, char** argv) {
std::string PACKAGE_PATH = ros::package::getPath(package_name);

std::string config_file_path = PACKAGE_PATH + config_path;
YAML::Node config_node = YAML::LoadFile(config_file_path);

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I did not understand why we need this change.

@@ -79,7 +79,7 @@ class HesaiLiDAR {
point.z = pc_in.at(w,h).z;
// point.intensity = pc_in.at(w,h).intensity;
point.timestamp = timebase + pc_in.at(w,h).timestamp * 1e-9; //may be different according to lidar sensor.

std::cout << h << " " << w << std::endl;

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If it is for debug, we can remove I think.

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

Successfully merging this pull request may close these issues.

None yet

2 participants