Skip to content

Commit cc78a0c

Browse files
author
Shuo
committed
update datasets
1 parent a315e73 commit cc78a0c

File tree

5 files changed

+142
-12
lines changed

5 files changed

+142
-12
lines changed

README.md

+6-2
Original file line numberDiff line numberDiff line change
@@ -39,10 +39,14 @@ roslaunch vilo run_campus_bag_vilo.launch
3939
```shell
4040
roslaunch vilo run_track_bag_vilo.launch
4141
```
42+
4. cut.bag
43+
```shell
44+
roslaunch vilo run_cut_bag_vilo.launch
45+
```
4246

43-
4. outdoor_snow.bag. The bag contains sensor data collected during the snow walking run shown in the second video above.
47+
5. outdoor_snow.bag. The bag contains sensor data collected during the snow walking run shown in the second video above.
4448

45-
5. indoor_with_ground_truth_1.bag. The robot moves forward and back quickly. Groundtruh data is
49+
6. indoor_with_ground_truth_1.bag. The robot moves forward and back quickly. Groundtruh data is
4650

4751
Notice the rosbag play should be slow down for slow computers, otherwise the VILO cannot finish computation in time. In the launch files we play them at 0.5x original speed.
4852

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,105 @@
1+
%YAML:1.0
2+
3+
#common parameters
4+
#support: 1 imu 1 cam; 1 imu 2 cam: 2 cam;
5+
imu: 1
6+
num_of_cam: 2
7+
8+
imu_topic: "/hardware_go1/imu"
9+
image0_topic: "/camera_forward/infra1/image_rect_raw"
10+
image1_topic: "/camera_forward/infra2/image_rect_raw"
11+
output_path: "/root/vilo_ws/src/vilo/output"
12+
13+
cam0_calib: "go1_realsense_left.yaml"
14+
cam1_calib: "go1_realsense_right.yaml"
15+
image_width: 424
16+
image_height: 240
17+
18+
19+
# leg related
20+
robot_type: "go1" # should be go1 or a1
21+
dataset_name: "cut" # to keep track of datasets
22+
use_leg_odom: 1
23+
num_of_leg: 4
24+
leg_topic: "/hardware_go1/joint_foot"
25+
optimize_leg_bias: 1
26+
27+
joint_angle_n: 0.00001
28+
joint_velocity_n: 0.00001
29+
30+
contact_sensor_type: 2 # 0 use KF output; 1 use plan contact; 2 use foot force sensor reading (then a complicated force model is needed)
31+
32+
leg_bias_c_n: 0.00000001
33+
leg_bias_nc_n: 0.00000000001
34+
# contact model
35+
v_n_force_thres_ratio: 0.8
36+
v_n_min_xy: 0.001
37+
v_n_min_z: 0.005
38+
v_n_min: 0.005
39+
v_n_max: 900.0
40+
# v_n_w1: 0.333
41+
# v_n_w2: 0.333
42+
# v_n_w3: 0.333
43+
v_n_term1_steep: 10
44+
v_n_term2_var_rescale: 1.0e-6
45+
v_n_term3_distance_rescale: 1.0e-3
46+
v_n_final_ratio: 0.1
47+
48+
# leg kinematics parameter
49+
lower_leg_length: 0.21
50+
51+
52+
# Extrinsic parameter between IMU and Camera.
53+
estimate_extrinsic: 0 # 0 Have an accurate extrinsic parameters. We will trust the following imu^R_cam, imu^T_cam, don't change it.
54+
# 1 Have an initial guess about extrinsic parameters. We will optimize around your initial guess.
55+
56+
body_T_cam0: !!opencv-matrix
57+
rows: 4
58+
cols: 4
59+
dt: d
60+
data: [ 0, 0, 1, 0.24,
61+
-1, 0, 0, 0.025,
62+
0, -1, 0, 0.1114,
63+
0., 0., 0., 1. ]
64+
65+
body_T_cam1: !!opencv-matrix
66+
rows: 4
67+
cols: 4
68+
dt: d
69+
data: [ 0, 0, 1, 0.24,
70+
-1, 0, 0, -0.025,
71+
0, -1, 0, 0.1114,
72+
0., 0., 0., 1. ]
73+
74+
#Multiple thread support
75+
multiple_thread: 1
76+
77+
#feature traker paprameters
78+
max_cnt: 250 # max feature number in feature tracking
79+
min_dist: 7 # min distance between two features
80+
freq: 15 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image
81+
F_threshold: 1.0 # ransac threshold (pixel)
82+
show_track: 1 # publish tracking image as topic
83+
flow_back: 1 # perform forward and backward optical flow to improve feature tracking accuracy
84+
85+
#optimization parameters
86+
max_solver_time: 0.1 # max solver itration time (ms), to guarantee real time
87+
max_num_iterations: 12 # max solver itrations, to guarantee real time
88+
keyframe_parallax: 10.0 # keyframe selection threshold (pixel)
89+
90+
#imu parameters The more accurate parameters you provide, the better performance
91+
acc_n: 1.0 # accelerometer measurement noise standard deviation. #0.2 0.04
92+
acc_n_z: 5.0
93+
gyr_n: 0.1 # gyroscope measurement noise standard deviation. #0.05 0.004
94+
acc_w: 0.0004 # accelerometer bias random work noise standard deviation. #0.002
95+
gyr_w: 0.0002 # gyroscope bias random work noise standard deviation. #4.0e-5
96+
g_norm: 9.805 # gravity magnitude
97+
98+
#unsynchronization parameters
99+
estimate_td: 0 # online estimate time offset between camera and imu
100+
td: 0.00240 # initial value of time offset. unit: s. readed image clock + td = real image clock (IMU clock)
101+
102+
#loop closure parameters
103+
load_previous_pose_graph: 0 # load and reuse previous pose graph; load from 'pose_graph_save_path'
104+
pose_graph_save_path: "/root/vilo_ws/src/vilo/output/pose_graph/" # save and load path
105+
save_image: 0 # save image in pose graph for visualization prupose; you can close this function by setting 0
+28
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,28 @@
1+
<launch>
2+
<param name="/use_sim_time" value="true"/>
3+
<!-- VILO config -->
4+
<param name="vilo_config_file" type="string" value="$(find vilo)/config/go1_config/hardware_go1_vilo_config_dense.yaml" />
5+
6+
<node name="vilo" pkg="vilo" type="vilo"
7+
args="$(find vilo)/config/go1_config/hardware_go1_vilo_config_dense.yaml" output="screen"/>
8+
<node name="vinsloopfusion" pkg="loop_fusion" type="loop_fusion_node"
9+
args="$(find vilo)/config/go1_config/hardware_go1_vilo_config_dense.yaml" />
10+
11+
<node pkg="tf" type="static_transform_publisher" name="ground_to_world"
12+
args="0.0 0.0 0.28 0.0 0.0 0.0 /a1_world /world 1000" />
13+
14+
<node pkg="tf" type="static_transform_publisher" name="body_to_a1_body"
15+
args="-0.0 0.0 -0.0 0.0 0.0 0.0 /body /a1_body 1000" />
16+
17+
<node pkg="tf" type="static_transform_publisher" name="base_to_a1_body"
18+
args="-0.0 0.0 -0.0 0.0 0.0 0.0 /a1_body /base 1000" />
19+
20+
21+
<!-- visualization using robot description -->
22+
<param name="robot_description" textfile="$(find vilo)/urdf/a1_description/urdf/a1.urdf" />
23+
<remap from="/joint_states" to="/a1_filterd_joint" />
24+
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
25+
26+
<arg name="node_start_delay" default="1.0" />
27+
<node pkg="rosbag" type="play" name="player" output="screen" args="--clock -r 0.5 $(find vilo)/bags/cut.bag" launch-prefix="bash -c 'sleep $(arg node_start_delay); $0 $@' " />
28+
</launch>

launch/hardware_go1/hardware_go1_vilo.launch

+1-4
Original file line numberDiff line numberDiff line change
@@ -10,18 +10,15 @@
1010
<node name="vinsloopfusion" pkg="loop_fusion" type="loop_fusion_node"
1111
args="$(find vilo)/config/go1_config/hardware_go1_vilo_config.yaml" />
1212

13-
<!-- new config when the robot chassis is on the ground, imu is 142mm above the ground, publish a fix transformation -->
1413
<node pkg="tf" type="static_transform_publisher" name="ground_to_world"
15-
args="0.0 0.0 0.15 0.0 0.0 0.0 /a1_world /world 1000" />
14+
args="0.0 0.0 0.28 0.0 0.0 0.0 /a1_world /world 1000" />
1615

1716
<node pkg="tf" type="static_transform_publisher" name="body_to_a1_body"
1817
args="-0.0 0.0 -0.0 0.0 0.0 0.0 /body /a1_body 1000" />
1918

2019
<node pkg="tf" type="static_transform_publisher" name="base_to_a1_body"
2120
args="-0.0 0.0 -0.0 0.0 0.0 0.0 /a1_body /base 1000" />
2221

23-
<!-- <node pkg="tf" type="static_transform_publisher" name="camera_to_downward_camera"
24-
args="0.0 0.1152 0.0 0.0 0.0 -0.785398 /camera /camera_downward_depth_optical_frame 1000" /> -->
2522

2623
<!-- visualization using robot description -->
2724
<param name="robot_description" textfile="$(find vilo)/urdf/a1_description/urdf/a1.urdf" />

launch/hardware_go1/hardware_go1_vins.launch

+2-6
Original file line numberDiff line numberDiff line change
@@ -10,19 +10,15 @@
1010
<node name="vinsloopfusion" pkg="loop_fusion" type="loop_fusion_node"
1111
args="$(find vilo)/config/go1_config/hardware_go1_vins_config.yaml" />
1212

13-
<!-- new config when the robot chassis is on the ground, imu is 142mm above the ground, publish a fix transformation -->
1413
<node pkg="tf" type="static_transform_publisher" name="ground_to_world"
15-
args="0.0 0.0 0.15 0.0 0.0 0.0 /a1_world /world 1000" />
14+
args="0.0 0.0 0.28 0.0 0.0 0.0 /a1_world /world 1000" />
1615

1716
<node pkg="tf" type="static_transform_publisher" name="body_to_a1_body"
1817
args="-0.0 0.0 -0.0 0.0 0.0 0.0 /body /a1_body 1000" />
1918

2019
<node pkg="tf" type="static_transform_publisher" name="base_to_a1_body"
2120
args="-0.0 0.0 -0.0 0.0 0.0 0.0 /a1_body /base 1000" />
22-
23-
<!-- <node pkg="tf" type="static_transform_publisher" name="camera_to_downward_camera"
24-
args="0.0 0.1152 0.0 0.0 0.0 -0.785398 /camera /camera_downward_depth_optical_frame 1000" /> -->
25-
21+
2622
<!-- visualization using robot description -->
2723
<param name="robot_description" textfile="$(find vilo)/urdf/a1_description/urdf/a1.urdf" />
2824
<remap from="/joint_states" to="/a1_filterd_joint" />

0 commit comments

Comments
 (0)