Skip to content

Commit

Permalink
🎈 perf(demo_cmu): Mantain configurations
Browse files Browse the repository at this point in the history
  • Loading branch information
LihanChen2004 committed Dec 23, 2024
1 parent 7ec5af0 commit 82ae1e8
Show file tree
Hide file tree
Showing 2 changed files with 98 additions and 6 deletions.
85 changes: 85 additions & 0 deletions pb2025_nav_bringup/config/simulation/cmu_nav_params.yaml
Original file line number Diff line number Diff line change
@@ -1,3 +1,78 @@
point_lio:
ros__parameters:
use_imu_as_input: False # Change to True to use IMU as input of Point-LIO
prop_at_freq_of_imu: True
check_satu: True
init_map_size: 10
point_filter_num: 4 # Options: 4, 3
space_down_sample: True
filter_size_surf: 0.5 # Options: 0.5, 0.3, 0.2, 0.15, 0.1
filter_size_map: 0.5 # Options: 0.5, 0.3, 0.15, 0.1
ivox_nearby_type: 18 # Options: 0, 6, 18, 26
runtime_pos_log_enable: False # Option: True

common:
lid_topic: "velodyne_points"
imu_topic: "livox/imu"
con_frame: False # True: if you need to combine several LiDAR frames into one
con_frame_num: 1 # the number of frames combined
cut_frame: False # True: if you need to cut one LiDAR frame into several subframes
cut_frame_time_interval: 0.05 # should be integral fraction of 1 / LiDAR frequency
time_diff_lidar_to_imu: 0.0 # Time offset between LiDAR and IMU calibrated by other algorithms, e.g., LI-Init (find in Readme)

prior_pcd:
enable: False
# NOTE: `prior_pcd_map_path` will be provided in the launch file
# prior_pcd_map_path: ""
init_pose: [ 0.0, 0.0, 0.0 ]

preprocess:
lidar_type: 2 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR
scan_line: 32
timestamp_unit: 2 # the unit of time/t field in the PointCloud2 rostopic: 0-second, 1-milisecond, 2-microsecond, 3-nanosecond.
blind: 0.5

mapping:
imu_en: True
extrinsic_est_en: False # for aggressive motion, set this variable False
imu_time_inte: 0.005 # = 1 / frequency of IMU
lidar_time_inte: 0.1
satu_acc: 30.0 # the saturation value of IMU's acceleration. not related to the units
satu_gyro: 35.0 # the saturation value of IMU's angular velocity. not related to the units
acc_norm: 9.81 # 1.0 for g as unit, 9.81 for m/s^2 as unit of the IMU's acceleration
lidar_meas_cov: 0.001 # 0.001
acc_cov_output: 500.0
gyr_cov_output: 1000.0
b_acc_cov: 0.0001
b_gyr_cov: 0.0001
imu_meas_acc_cov: 0.1 # 0.1 # 2
imu_meas_omg_cov: 0.1 # 0.1 # 2
gyr_cov_input: 0.01 # for IMU as input model
acc_cov_input: 0.1 # for IMU as input model
plane_thr: 0.1 # 0.05, the threshold for plane criteria, the smaller, the flatter a plane
match_s: 81.0
ivox_grid_resolution: 0.5
gravity: [ 0.0, -4.9, -8.487047153776548 ] # gravity to be aligned # rpy = [0, pi/6, 0]
gravity_init: [ 0.0, -4.9, -8.487047153776548 ] # preknown gravity in the first IMU body frame, use when imu_en is False or start from a non-stationary state
extrinsic_T: [ 0.0, 0.0, 0.0 ]
extrinsic_R: [ 1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
0.0, 0.0, 1.0 ]

odometry:
publish_odometry_without_downsample: True

publish:
path_en: False # False: close the path output
scan_publish_en: True # False: close all the point cloud output
scan_bodyframe_pub_en: False # True: output the point cloud scans in IMU-body-frame
tf_send_en: False # True: send transform from 'camera_init' to 'aft_mapped'

pcd_save:
pcd_save_en: False
interval: -1 # how many LiDAR frames saved in each pcd file;
# -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.

loam_interface:
ros__parameters:
use_sim_time: True
Expand All @@ -14,6 +89,16 @@ sensor_scan_generation:
base_frame: "base_footprint"
robot_base_frame: "gimbal_yaw"

fake_vel_transform:
ros__parameters:
use_sim_time: True
odom_topic: "odometry"
robot_base_frame: "gimbal_yaw"
fake_robot_base_frame: "gimbal_yaw_fake"
input_cmd_vel_topic: "cmd_vel_controller"
output_cmd_vel_topic: "cmd_vel"
spin_speed: 3.14

terrain_analysis:
ros__parameters:
scanVoxelSize: 0.05
Expand Down
19 changes: 13 additions & 6 deletions pb2025_nav_bringup/launch/demo_cmu_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,10 +51,6 @@ def generate_launch_description():
replacements={"<robot_namespace>": ("/", namespace)},
)

point_lio_params_dir = os.path.join(
bringup_dir, "config", "simulation", "point_lio.yaml"
)

stdout_linebuf_envvar = SetEnvironmentVariable(
"RCUTILS_LOGGING_BUFFERED_STREAM", "1"
)
Expand Down Expand Up @@ -127,11 +123,22 @@ def generate_launch_description():
name="point_lio",
output="screen",
parameters=[
point_lio_params_dir,
configured_params,
{"prior_pcd.prior_pcd_map_path": prior_pcd_file},
],
remappings=remappings,
),
Node(
package="fake_vel_transform",
executable="fake_vel_transform_node",
name="fake_vel_transform",
output="screen",
respawn=use_respawn,
respawn_delay=2.0,
parameters=[configured_params],
arguments=["--ros-args", "--log-level", log_level],
remappings=remappings,
),
Node(
package="sensor_scan_generation",
executable="sensor_scan_generation_node",
Expand Down Expand Up @@ -185,7 +192,7 @@ def generate_launch_description():
respawn_delay=2.0,
parameters=[configured_params],
arguments=["--ros-args", "--log-level", log_level],
remappings=remappings,
remappings=remappings + [("cmd_vel", "cmd_vel_controller")],
),
]
)
Expand Down

0 comments on commit 82ae1e8

Please sign in to comment.