-
Notifications
You must be signed in to change notification settings - Fork 5
/
Copy pathlocalization_test.sh
executable file
·70 lines (53 loc) · 2.02 KB
/
localization_test.sh
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
#!/bin/bash
t=$(date +'%Y-%m-%d-%H-%M-%S')
echo "Folder Name: $t"
killall gzserver
killall gzclient
killall rviz
killall roscore
killall rosmaster
LOADWORLD=""
MAPPING=true
GT=false
FILTER=true
while getopts a:l:g:f: option
do
case "${option}"
in
a) MAPPING=${OPTARG};;
l) LOADWORLD=${OPTARG};;
g) GT=${OPTARG};;
f) FILTER=${OPTARG};;
esac
done
roscore -p $ROSPORT&
until rostopic list; do sleep 0.5; done #wait until rosmaster has started
INFILE="/home/$USER/Myhal_Simulation/simulated_runs/$LOADWORLD/raw_data.bag"
c_method="hugues_annotations"
LIDARTOPIC="/hugues_points"
if [ "$GT" == "true" ]; then
LIDARTOPIC="/velodyne_points"
c_method="ground_truth"
fi
mkdir "/home/$USER/Myhal_Simulation/simulated_runs/$t"
mkdir "/home/$USER/Myhal_Simulation/simulated_runs/$t/logs-$t"
# load parameters
rosparam set localization_test true
rosparam set use_sim_time true
rosparam set filter_status $FILTER
rosparam set gmapping_status $MAPPING
rosparam set start_time $t
rosparam set classify true
rosparam set class_method $c_method
rosparam set load_world $LOADWORLD
rosparam load /home/$USER/Myhal_Simulation/simulated_runs/$LOADWORLD/logs-$LOADWORLD/params.yaml
# record logs
cp "/home/$USER/Myhal_Simulation/simulated_runs/$LOADWORLD/logs-$LOADWORLD/myhal_sim.world" "/home/$USER/Myhal_Simulation/simulated_runs/$t/logs-$t/myhal_sim.world"
cp "/home/$USER/Myhal_Simulation/simulated_runs/$LOADWORLD/logs-$LOADWORLD/params.yaml" "/home/$USER/Myhal_Simulation/simulated_runs/$t/logs-$t/params.yaml"
LOGFILE="/home/$USER/Myhal_Simulation/simulated_runs/$t/logs-$t/logs.txt"
touch $LOGFILE
rosbag record -O "/home/$USER/Myhal_Simulation/simulated_runs/$t/localization_test.bag" -a -x "(.*)points(.*)" & # Limiting data to remain under rosbag buffer
roslaunch jackal_velodyne hugues_test.launch mapping:=$MAPPING in_topic:=$LIDARTOPIC filter:=$FILTER &
rosbag play --wait-for-subscribers $INFILE --topics /tf /tf_static $LIDARTOPIC /clock /move_base/result /shutdown_signal /ground_truth/state
sleep 0.5
rosrun dashboard data_processing.py $t