The problem of running real robots
Dear
I tried to execute 'p2p_move_mase_mapping. launch' and connect my real robot and sensors, and also adjusted the YAML file accordingly, but there were the following issues after execution
-
Despite multiple attempts, the global path could not be planned (as shown in the logs displayed in the video)
-
Whether during 3D pose initialization or when publishing 3D navigation points, clicking or dragging on rviz multiple times is necessary to display arrow symbols in the screen. I'm not sure if it's an issue with the clicked2goal.by node or the rviz plugin
-
After the first navigation point is published, if the global path cannot be calculated, and later attempts to select a new navigation point are made, no matter how you click and drag on rviz, there will be no successful publishing arrow (see video for details)
-
Does your 3D navigation framework support other laser SLAM algorithms? If supported, what are the topics that must be provided to this framework when I replace Lego Loam with other SLAM algorithms?
https://github.com/user-attachments/assets/8aba6eb9-ec1f-49d5-931a-70761c1ff65e
https://github.com/user-attachments/assets/426f1f67-abb7-4ae7-9a1b-b7086057dd9a
Two questions:
- Which lidar you are using? Our lego loam package support "repetitive scan lidar".
- Are you running slam + navigation option? If you want to use your own slam algorithm, publish ground pc to topic called: mapground. Remember, the ground is super important for the global path planning.
Two questions:
- Which lidar you are using? Our lego loam package support "repetitive scan lidar".
- Are you running slam + navigation option? If you want to use your own slam algorithm, publish ground pc to topic called: mapground. Remember, the ground is super important for the global path planning.
1、Currently using Hesai XT16 (a kind of multilayer spinning lidar ) 2、Yes, I am trying to execute the file 'p2p_move_base_mapping. launch', Is this launch file corresponding to launch navigating while mapping? 3、Are you saying that if I use my own SLAM algorithm, I must also divide the generated point cloud map into two parts: one part is the point cloud on the ground, which is sent to the "mapground" topic, and the other part is the point cloud of the remaining map, which is sent to the "map" topic, in order to correctly use this 3D navigation framework? 4、Does the current navigation framework support path planning for climbing stairs? I saw that in the source code of the static layer plugin, there is a section of code that involves height difference detection that has been commented out. Is this part related to the path planning of stairs?
Question for you before answering:
- Does your lidar see ground? If yes, by correctly configuring your yaml file, you should see the ground being generated correctly.
- Do you want to make the robot navigating while mapping? Or you just want to map first and then localize your robot?
Comments
-
You need to modify the configuration in: https://github.com/dfl-rlab/dddmr_navigation/blob/main/src/dddmr_lego_loam/lego_loam_bor/config/loam_c16_config.yaml to reflect your lidar setting. If your setup is correct, you should be able to see a good ground pc being generated, since we have implement the algorithm to handle sparse ground pc issue.
-
We need purely ground information is that because when doing global path planning, there is an algorithm that will propagate the ground pc to connect each node, if you include something like wall, the path planning will calculate the path cross the wall. So we recommend you to use our lego_loam package.
-
You found the trophy! The comment out part is deprecated for static ground point cloud, i,e., localization mode. When you use the mapping and navigation mode, the mechanism is different, the path planning will be run on the ground point cloud in real time since ground is keep growing, and we can not generate graph each time when it is growing(taking too much computation resource). The setup is at local and global planners: https://github.com/dfl-rlab/dddmr_navigation/blob/cc9ef9632de51e6053d7fb94c45d3d1f81a14b80/src/dddmr_p2p_move_base/config/p2p_move_base_mapping.yaml#L155 https://github.com/dfl-rlab/dddmr_navigation/blob/cc9ef9632de51e6053d7fb94c45d3d1f81a14b80/src/dddmr_p2p_move_base/config/p2p_move_base_mapping.yaml#L200
Summary for navigating on stairs is Yes, we did work on making our stack works in stairs, but it requires some tuning, including relaxing ground detection threshold in: https://github.com/dfl-rlab/dddmr_navigation/blob/cc9ef9632de51e6053d7fb94c45d3d1f81a14b80/src/dddmr_lego_loam/lego_loam_bor/src/imageProjection.cpp#L335 Also if you are navigating in a narrow space, you will need to make edge distance between poses smaller, say 0.2 m: https://github.com/dfl-rlab/dddmr_navigation/blob/cc9ef9632de51e6053d7fb94c45d3d1f81a14b80/src/dddmr_lego_loam/lego_loam_bor/config/loam_c16_config.yaml#L48
By tuning these or implement your stair detection algorithm, you will have a good ground map. Basically, if you have a good/reasonable ground map, the stack will handle rest of things for you.
- Global planner is default relaxed using ground cloud without any constraint even there are vertical pc connected, so you can do path planning on the stairs given that your ground/stairs are being generated correctly.
Thank you for your reply
Reply to your question
1、My lidar is installed above the head of the quadruped robot and should be able to scan the ground ahead 2、Yes, I want the robot to navigate while mapping
You can pull the latest commit that will initial a ground at first couple frames for you to navigate. Also you dont need to give an initial pose when you are in mapping mode.
Old version:
New version:
Thank you very much for your reply. I have pulled the latest repository code and tested it again on a real robot. Currently, I still found 2 issues
1、Whether choosing “wheel_odometry” or “laser_odometry”, the following error message will appear after running. I have checked all the odometer topics published by the node("/laser_odom_to_init","/integrated_to_init","/aft_mapped_to_init"), all of them is empty
After checking the source code,I found the local_planner node needs to subscribe to data from the topic named "/odom", but it seems that no node was found in the feature pack to publish data to this topic. Does this mean that I need to build my own odometer node and publish data to the "/odom" topic?
2、As shown in the following video, after the start of "p2p_move_base_mapping.launch.by", from the 0:49 -0:58 of the video, the original LiDAR point cloud can be seen, with concentric circular point clouds scanned onto the ground,
Starting from 1:03, when the ground map is displayed, it can be seen that there are two layers of layering on the ground map, and the red point on the top layer does not coincide with the points on the original point cloud ground,
This is due to the mistake of changing one level of ground into two levels when planning the path (as shown at the beginning of the video). Why does the ground map have an abnormal two-layer layering? How can we adjust and avoid this problem? I would like to ask for your advice
https://github.com/user-attachments/assets/d925bacb-5993-4e64-91ae-c7422c40540c
And the following is the modified version of the loam_c16_config.yaml file based on my LiDAR
lego_loam_ip:
ros__parameters:
# leishen16
laser:
num_vertical_scans: 16
num_horizontal_scans: 1000
ground_scan_index: 7
vertical_angle_bottom: -15.0
vertical_angle_top: 15.0
sensor_mount_angle: 0.0
scan_period: 0.05
imageProjection:
segment_valid_point_num: 5
segment_valid_line_num: 2
segment_theta: 60.0 # decrese this value may improve accuracy
maximum_detection_range: 120.0 # point cloud within this range will be used to project image
minimum_detection_range: 0.5
lego_loam_fa:
ros__parameters:
laser:
num_vertical_scans: 16
num_horizontal_scans: 1000
scan_period: 0.05
featureAssociation:
odom_type: "laser_odometry" #wheel_odometry/laser_odometry
robot_frame: "base_link"
sensor_frame: "hesai_lidar"
sensor_x: 0.171
sensor_y: 0.0
sensor_z: 0.0908
sensor_roll: 0.0
sensor_pitch: 0.0 #-0.1745
sensor_yaw: 0.0 #-3.1415926
edge_threshold: 0.1
surf_threshold: 0.1
nearest_feature_search_distance: 3.0
mapping:
to_map_optimization: true
lego_loam_mo:
ros__parameters:
mapping:
distance_between_key_frame: 1.0
angle_between_key_frame: 1.0
enable_loop_closure: true
surrounding_keyframe_search_num: 10
history_keyframe_search_radius: 15.0
history_keyframe_search_num: 5
history_keyframe_fitness_score: 0.5
ground_voxel_size: 0.4
ground_edge_threshold_num: 60
- Yes, you need odometry from the robot, 2D odom might work. Recommend 3D odometry. We are working on dicumentation of 3D odometry for mobile robot, will be release recently. But in your case (legged robot), you will need to provide odometry. Also, the lidar odometry in lego loam is not robust, therefore, we did not pipe in lidar odometry into navigation, just make it as an option for mapping.
- I am interested in your result, do you mind sharing your bag file (10 seconds) for us to justify. We only need lidar point cloud.
- Yes, you need odometry from the robot, 2D odom might work. Recommend 3D odometry. We are working on dicumentation of 3D odometry for mobile robot, will be release recently. But in your case (legged robot), you will need to provide odometry. Also, the lidar odometry in lego loam is not robust, therefore, we did not pipe in lidar odometry into navigation, just make it as an option for mapping.
- I am interested in your result, do you mind sharing your bag file (10 seconds) for us to justify. We only need lidar point cloud.
1、If I customize a odometer, what should be the frame_id and child_frame_id of the odometer? like below?
frame_id="laser_odom"
child_frame_id="base_link"
2、here is the rosbag, thx https://drive.google.com/drive/folders/1RUHmmO_9b2FcOdtWAmhKIWKWkil4-MQz
- Make sure /odom is published. And frame ID can be:
frame_id="odom"
child_frame_id="base_link"
Also, at this stage, we assume base_link in on the ground (usually it was base_footprint)
- Please pull the latest commit to see if the issue been resolved. Multi layer might still appear in some situation. However, the major bug should be resolved.
Before:
After:
I notice that you are in a narrow space, you can reduce ground voxel size to get denser ground: https://github.com/dfl-rlab/dddmr_navigation/blob/24a1f8708e38a85538ba1d25b92466ecac5a71da/src/dddmr_lego_loam/lego_loam_bor/config/loam_c16_config.yaml#L57
ground_voxel_size: 0.2
- From your previous video shows that the global plan will connect multiple layer ground, that is because we do not limit the edge connection by height information. If you are interested, you can implement a height check condition here: https://github.com/dfl-rlab/dddmr_navigation/blob/24a1f8708e38a85538ba1d25b92466ecac5a71da/src/dddmr_global_planner/src/a_star_on_pc.cpp#L233
something like
if(fabs(pcl_current.z - pcl_expanding.z)>xxoo)
continue;
Thank you for your reply,
but I couldn't find the latest submission.
Are you referring to the submission version shown in the screenshot below? I tried running it on this version, but the problem still persists
Forgot to push..., I will push it tonight😅
That is great!
I tried using the latest version, and currently the real robot can navigate based on 3D navigation points!
but there are still some minor issues
- When I give a navigation point, the robot will move towards that target point, but when it reaches the target, it does not stop, but continues to move forward (as shown in the video (0:10-0:30)), during which I have not posted any new navigation points to the robot. Is this normal?
https://github.com/user-attachments/assets/69d346a2-05f3-4626-8369-44480e3c55ec
- The following is the TF tree generated by the self built odometer. Based on your previous suggestion, the frame_id of the odometer was set to "odom", but I did not see this frame called "odom" in the TF tree Is this structure correct? Is it related to my custom odometer that the robot did not stop moving when it reached the target point?
- The ground point cloud posted on the "/lego_loam_ground" topic comes in many colors, Is this because the intensity values of point clouds are different?
- Can you see this log from p2p_move_base:
Goal xy tolerance reach, switch to align goal heading state.
- Is your base_link on the ground? It should match between, noted that one is lidar->base_link, another is base_link->lidar: https://github.com/dfl-rlab/dddmr_navigation/blob/7f47bae409914a2a8e9a4bc569be445c36dea5ef/src/dddmr_lego_loam/lego_loam_bor/config/loam_c16_config.yaml#L30 and https://github.com/dfl-rlab/dddmr_navigation/blob/7f47bae409914a2a8e9a4bc569be445c36dea5ef/src/dddmr_p2p_move_base/launch/p2p_move_base_mapping.launch#L10
I will make this setup easier for next release
-
Regarding TF tree, because you are using slam as localization system, it does not require odom frame as input, though it can subscribe odom topic to enhance the mapping accuracy. For short, lego_loam estimates base_link pose without odom, therefore odom frame is not necessary to be in the TF tree. Thank you to point this out, I will include odom frame in the TF in the next release, but again, your setup is correct.
-
Yes, the intensity is higher at the frontier (There is an algorithm try to detect the edge of each lidar frame and fuse them, but it is the proof-of-concept version). Allows the robot to plan a safer global path, or doing exploring job. For example, the green part in the following picture:
Thank you for your reply!
I have located a specific code snippet to address the issue of being unable to stop after reaching the target point
I found that the main reason is that the calculation logic of “distance” in “local_planner" is,
double distance = sqrt(dx*dx + dy*dy + dz*dz);
while the definition of “xy_goal_tolerance_” in “local_planner", based on variable naming, may only be the distance tolerance of the x-y plane.
declare_parameter("xy_goal_tolerance", rclcpp::ParameterValue(0.3));
which leads to the inability to meet the stop condition because there is always a distance on the Z-axis
Furthermore, from RVIZ, it can be seen that my base_link cannot stick to the ground, even if I follow the method you mentioned and adjust lidar ->base_link (in the YAML file, as shown below)
lego_loam_fa:
ros__parameters:
laser:
num_vertical_scans: 16
num_horizontal_scans: 1000
scan_period: 0.05
featureAssociation:
odom_type: "laser_odometry" #wheel_odometry/laser_odometry
robot_frame: "base_link"
sensor_frame: "hesai_lidar"
sensor_x: 0.171
sensor_y: 0.0
sensor_z: 0.0908
sensor_roll: 0.0
sensor_pitch: 0.0 #-0.1745
sensor_yaw: 0.0 #-3.1415926
edge_threshold: 0.1
surf_threshold: 0.1
nearest_feature_search_distance: 3.0
mapping:
to_map_optimization: true
and base_link ->lidar (in the launch file, as shown below) according to your method
transform_node_2 = Node(
package='tf2_ros',
executable='static_transform_publisher',
name='sensor2baselink',
output='screen',
arguments=['-0.171', '0', '-0.0908', '0', '0', '0', 'hesai_lidar', 'base_link']
)
return LaunchDescription([
# odom_node,
lio_slam_node,
global_planner_node,
nav_3d_bringup_node,
navigation_point_click_node,
start_rviz_node,
transform_node_1,
transform_node_2,
])
it still cannot make base_link stick to the ground
I think the root of the problem lies here. The target point sent is based on the base_link coordinate system as the origin, so I would like to ask for your advice on how to make base_link stick to the ground
It looks like your lidar is very close to baselink (9cm), you can try setup a base_footprint from on the ground, see: https://wiki.ros.org/hector_slam/Tutorials/SettingUpForYourRobot And then, change your local and global planner robot_frame to base_footprint: https://github.com/dfl-rlab/dddmr_navigation/blob/66f0d6972a4549bcaab4236ee957d0924c14a2fc/src/dddmr_p2p_move_base/config/p2p_move_base_mapping.yaml#L145
Another lazy method is to change the z value of base_link->lidar as the height from lidar to ground.
BTW, as mentioned, we are working on the new version, which restructure the tf frame and make the setup easier, see: https://github.com/dfl-rlab/dddmr_navigation/tree/restructure_tf_setup
The TF tree in this version will be the very similar one in Navigation Stack: ma->odom->base_link->lidar
Dear
I pulled the latest code from the repository and tried to run "lego_loam.launch" based on "DDDMR BEGINNER GUIDE", but I found that the ground point cloud cannot be displayed in rviz (it can be displayed normally when using your previous code version), as shown in the following video.
https://github.com/user-attachments/assets/267992a9-29f5-4a78-af4c-1e7b035bd67d
In addition, there seems to be an extra coordinate system "camera_init" in the TF tree, as shown in the following figure
So I would like to ask if there is any necessary configuration under the new version that I made wrong?
The TF tree is correct, but we found some wrong transformation in the commit. Please try this branch: https://github.com/dfl-rlab/dddmr_navigation/tree/tf_tree_correction
Thank you very much for your reply. I have pulled the latest repository code and tested it again on a real robot. Currently, I still found 2 issues
1、Whether choosing “wheel_odometry” or “laser_odometry”, the following error message will appear after running. I have checked all the odometer topics published by the node("/laser_odom_to_init","/integrated_to_init","/aft_mapped_to_init"), all of them is empty
After checking the source code,I found the local_planner node needs to subscribe to data from the topic named "/odom", but it seems that no node was found in the feature pack to publish data to this topic. Does this mean that I need to build my own odometer node and publish data to the "/odom" topic?
2、As shown in the following video, after the start of "p2p_move_base_mapping.launch.by", from the 0:49 -0:58 of the video, the original LiDAR point cloud can be seen, with concentric circular point clouds scanned onto the ground,
Starting from 1:03, when the ground map is displayed, it can be seen that there are two layers of layering on the ground map, and the red point on the top layer does not coincide with the points on the original point cloud ground,
This is due to the mistake of changing one level of ground into two levels when planning the path (as shown at the beginning of the video). Why does the ground map have an abnormal two-layer layering? How can we adjust and avoid this problem? I would like to ask for your advice
Ground.map.abnormality.mp4
hello @FLYivan @tsengapola
I am in the process of testing this with Go2-W and I am getting the same error. I am quite confused on how to customize the odom, would you mind sharing how you did it please? Do I need to calculate odom using lidar or imu and publish to the odom topic?
@zheyisoo I don't have Go2-W but I guess that you can write a node converting Go2 'state' to odom topic. For example, converting /sportmodestate topic to /odom https://github.com/unitreerobotics/unitree_ros2?tab=readme-ov-file#2-connect-and-test
hello @tsengapola thanks a lot for your quick response. When testing with the /sportmodestate topic, i am only getting the imu value, the rest is showing 0. If I were to use that as odom value, I will need to calculate the odom based on imu value.
Separate topic, I am a bit confused, shouldn't lego loam be publishing to the odom topics using lidar information? Should I be running the whole lego_loam or just the mcl_feature when performing navigation.
void FeatureAssociation::assignMappingOdometry(float (&ts)[6]){
tf2::Quaternion quat_tf;
geometry_msgs::msg::Quaternion geoQuat;
//-------------------------------------------
quat_tf.setRPY(ts[2], -ts[0], -ts[1]);
tf2::convert(quat_tf, geoQuat);
mappingOdometry.header.stamp = cloudHeader.stamp;
mappingOdometry.pose.pose.orientation.x = -geoQuat.y;
mappingOdometry.pose.pose.orientation.y = -geoQuat.z;
mappingOdometry.pose.pose.orientation.z = geoQuat.x;
mappingOdometry.pose.pose.orientation.w = geoQuat.w;
mappingOdometry.pose.pose.position.x = ts[3];
mappingOdometry.pose.pose.position.y = ts[4];
mappingOdometry.pose.pose.position.z = ts[5];
//pubLaserOdometry->publish(mappingOdometry);
I also notice that this is commented out under featureAssociation.cpp. Can I uncomment this to use this odom value?
Thanks again.
If you have a map, and want to localize your robot, you don't need whole lego_loam, you just need mcl_feature.
Be aware that this is laser odometry, it might suffer virtual slipping or not accurate due to lacking features. Also please update the code as following, I quickly prototype it to lidar frame, it might need to be verified.
tf2::Quaternion quat_tf;
geometry_msgs::msg::Quaternion geoQuat;
//-------------------------------------------
quat_tf.setRPY(ts[2], -ts[0], -ts[1]);
tf2::convert(quat_tf, geoQuat);
mappingOdometry.header.stamp = cloudHeader.stamp;
mappingOdometry.pose.pose.orientation.x = -geoQuat.y;
mappingOdometry.pose.pose.orientation.y = -geoQuat.z;
mappingOdometry.pose.pose.orientation.z = geoQuat.x;
mappingOdometry.pose.pose.orientation.w = geoQuat.w;
mappingOdometry.pose.pose.position.x = ts[3];
mappingOdometry.pose.pose.position.y = ts[4];
mappingOdometry.pose.pose.position.z = ts[5];
tf2::Quaternion quat_tf_lidar;
quat_tf_lidar.setRPY(ts[2], -ts[0], -ts[1]+3.1415926/2);
nav_msgs::msg::Odometry mappingOdometryLidar;
mappingOdometryLidar = mappingOdometry;
mappingOdometryLidar.pose.pose.orientation.x = -quat_tf_lidar.y();
mappingOdometryLidar.pose.pose.orientation.y = -quat_tf_lidar.z();
mappingOdometryLidar.pose.pose.orientation.z = quat_tf_lidar.x();
mappingOdometryLidar.pose.pose.orientation.w = quat_tf_lidar.w();
pubLaserOdometry->publish(mappingOdometryLidar);
@zheyisoo By the way , according to the document (https://support.unitree.com/home/zh/Go2-W_developer/ROS2_service ), it looks like the Go2-W should provide sportmodestate. Have you checked with Unitree? Didn't they provides odometry data? Or Go2-W does not provide such information?
@zheyisoo By the way , according to the document (https://support.unitree.com/home/zh/Go2-W_developer/ROS2_service ), it looks like the Go2-W should provide sportmodestate. Have you checked with Unitree? Didn't they provides odometry data? Or Go2-W does not provide such information?
hello @pstsengb, when i try to rostopic info the sportmodestate topic, there is nothing publishing to it, I can rostopic info the lf/sportmodestate, which is the low frequency sport mode state, but its only showing the imu value, and the position value is always showing 0. Unfortunately I don't have direct customer support contact with Unitree, and I am waiting for response from the 3rd party supplier that I purchased it from.
If you have a map, and want to localize your robot, you don't need whole lego_loam, you just need mcl_feature.
Be aware that this is laser odometry, it might suffer virtual slipping or not accurate due to lacking features. Also please update the code as following, I quickly prototype it to lidar frame, it might need to be verified.
tf2::Quaternion quat_tf; geometry_msgs::msg::Quaternion geoQuat; //------------------------------------------- quat_tf.setRPY(ts[2], -ts[0], -ts[1]); tf2::convert(quat_tf, geoQuat); mappingOdometry.header.stamp = cloudHeader.stamp; mappingOdometry.pose.pose.orientation.x = -geoQuat.y; mappingOdometry.pose.pose.orientation.y = -geoQuat.z; mappingOdometry.pose.pose.orientation.z = geoQuat.x; mappingOdometry.pose.pose.orientation.w = geoQuat.w; mappingOdometry.pose.pose.position.x = ts[3]; mappingOdometry.pose.pose.position.y = ts[4]; mappingOdometry.pose.pose.position.z = ts[5]; tf2::Quaternion quat_tf_lidar; quat_tf_lidar.setRPY(ts[2], -ts[0], -ts[1]+3.1415926/2); nav_msgs::msg::Odometry mappingOdometryLidar; mappingOdometryLidar = mappingOdometry; mappingOdometryLidar.pose.pose.orientation.x = -quat_tf_lidar.y(); mappingOdometryLidar.pose.pose.orientation.y = -quat_tf_lidar.z(); mappingOdometryLidar.pose.pose.orientation.z = quat_tf_lidar.x(); mappingOdometryLidar.pose.pose.orientation.w = quat_tf_lidar.w(); pubLaserOdometry->publish(mappingOdometryLidar);
hello @tsengapola, thank you so much! I am going to try it now.
Separate topic, when I tried running with just mcl feature using go2_localization.launch, I got a error of "Timed out waiting for transfrom from base_link to map to become available, td error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist. I overcome this issue by having another terminal running the lego_loam.launch. Is this error causing because nothing is publishing to /odom topic?
<node pkg="lego_loam_bor" exec="mcl_feature" output="screen" respawn="false">
<param from="$(find-pkg-share p2p_move_base)/config/go2_localization.yaml" />
<remap from="/lslidar_point_cloud" to="/unitree/slam_lidar_points"/>
<remap from="/odom" to="/odom"/>
<param name="use_sim_time" value="$(var use_sim)"/>
</node>
<node pkg="tf2_ros" exec="static_transform_publisher" name="baselink2footprint" args="0.0 0 -0.219 0.0 0.0 0 base_link base_footprint>
<node pkg="tf2_ros" exec="static_transform_publisher" name="footprint2sensor" args="0.3 0 0.38 -3.14159 0.0 0 base_footprint rslidar>
In my go2_localization.yaml file, my setting is as below:
local planner:
ros__parameters:
odom_topic: laser_odom_to_init
After I launched it sucessfuly, with another terminal running lego_loam.launch. I am able to set a 3d goal, and i am able to see the global path. However, it will keep looping showing goal accepted: dwa planner, waiting for result. I can see that there is path under /trajectory topic, but nothing under /best_trajectory and /accepted_tracjectory.
@zheyisoo Let's solve the localization pipeline issue first. You might need to change the laser odom topic, change the remap line to:
<remap from="/odom" to="/laser_odom_to_init"/>
Because the laser odom topic from lego loam is 'laser_odom_to_init', You can check by:
ros2 topic hz /laser_odom_to_init
In addition, you don't need to launch lego_loam.launch.
hello @tsengapola, thanks a lot for the info, I managed to get the go2_localization running without needing to launch lego_loam.launch. The error of td error: Invalid frame ID "map" passed to canTransform argument target_frame - frame does not exist didin't show up after I made a few changes as below, also I publish the /laser_odom_to_init to /odom topic:
Under featureAssociation.cpp original:
mappingOdometry.header.frame_id = "camera_init";
mappingOdometry.child_frame_id = "laser_odom";
laserOdometryTrans.header.frame_id = "camera_init";
laserOdometryTrans.child_frame_id = "laser_odom";
changed:
mappingOdometry.header.frame_id = "map";
mappingOdometry.child_frame_id = "odom";
laserOdometryTrans.header.frame_id = "odom";
laserOdometryTrans.child_frame_id = "base_link";
However, I am unable to run lego_loam.launch for mapping purposes, the error showing is "Authority undetectable with frame_id and child_frame_id as they are the same". Is this error caused by the changes in mappingOdometry within feature association cpp file?
With the code changes, when I am launching the go2_localization.launch. I kept encountering the pose jump on mcl_3dl, and unable to localize robot on a premapped map. Attaching a video link as below.
https://streamable.com/3bf2aj
您好,当我使用robosenseairy雷达来运行你们的mcl时候 异常卡顿,而且漂移非常严重 请问有什么解决方式吗