Skip to content

Commit 7326d27

Browse files
committedMay 31, 2023
refactor(pcdless_launc/scripts): remove unnecessary scripts (autowarefoundation#11)
* remove not useful scripts Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp> * rename scripts & add descriptions Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp> * little change Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp> * remove odaiba.rviz Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp> * grammer fix Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp> --------- Signed-off-by: Kento Yabuuchi <kento.yabuuchi.2@tier4.jp>
1 parent 18b3df8 commit 7326d27

8 files changed

+101
-792
lines changed
 

‎localization/yabloc/pcdless_launch/config/odaiba.rviz

-571
This file was deleted.

‎localization/yabloc/pcdless_launch/scripts/control_command_publisher.py

-49
This file was deleted.

‎localization/yabloc/pcdless_launch/scripts/extract_rosbag.py ‎localization/yabloc/pcdless_launch/scripts/extract_rosbag_for_loc.py

+20-13
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,9 @@
1-
#!/usr/bin/python3
1+
#!/usr/bin/env python3
2+
'''
3+
This script extracts only the topics necessary for localization from big rosbag.
4+
5+
e.g. $ ./extract_rosabg_for_loc.py -h
6+
'''
27
import glob
38
import subprocess
49
import shutil
@@ -11,11 +16,8 @@
1116
'/sensing/gnss/ublox/nav_sat_fix',
1217
'/sensing/gnss/ublox/navpvt',
1318
'/sensing/imu/tamagawa/imu_raw',
14-
'/vehicle/status/actuation_status', # iv, universe
1519
'/vehicle/status/twist', # iv
1620
'/vehicle/status/velocity_status', # universe
17-
'/vehicle/status/steering', # iv
18-
'/vehicle/status/steering_status', # universe
1921
]
2022

2123
LIDAR_TOPICS = [
@@ -40,10 +42,14 @@ def extractIndex(name):
4042

4143
def main():
4244
parser = argparse.ArgumentParser()
43-
parser.add_argument('-b', '--basic', action='store_true', help='include basic topics')
44-
parser.add_argument('-l', '--lidar', action='store_true', help='include lidar topics')
45-
parser.add_argument('-c', '--camera', action='store_true', help='include camera topics')
46-
parser.add_argument('-o', '--output', default='filtered', help='include camera topics')
45+
parser.add_argument('-b', '--basic', action='store_true',
46+
help='include basic topics')
47+
parser.add_argument('-l', '--lidar', action='store_true',
48+
help='include lidar topics')
49+
parser.add_argument('-c', '--camera', action='store_true',
50+
help='include camera topics')
51+
parser.add_argument('-o', '--output', default='filtered',
52+
help='include camera topics')
4753
args = parser.parse_args()
4854

4955
TOPICS = []
@@ -55,7 +61,8 @@ def main():
5561
TOPICS.extend(LIDAR_TOPICS)
5662

5763
if len(TOPICS) == 0:
58-
print_highlight('You have to choice at least on topics among `basic`, `lidar`, `camera`')
64+
print_highlight(
65+
'You have to choice at least on topics among `basic`, `lidar`, `camera`')
5966
parser.print_help()
6067
return
6168

@@ -68,11 +75,11 @@ def main():
6875
indexed_files.sort(key=lambda x: x[0])
6976

7077
# Filter necessary topics
71-
print_highlight('Process '+str(len(indexed_files))+' files.')
78+
print_highlight('Process ' + str(len(indexed_files)) + ' files.')
7279
dst_files = []
7380
for index, f in indexed_files:
74-
print_highlight(str(index)+' '+f)
75-
tmp_dst = 'tmp'+str(index)
81+
print_highlight(str(index) + ' ' + f)
82+
tmp_dst = 'tmp' + str(index)
7683
dst_files.append(tmp_dst)
7784
command = ['ros2', 'bag', 'filter', f, '-o', tmp_dst, '-i']
7885
for t in TOPICS:
@@ -81,7 +88,7 @@ def main():
8188

8289
# Merge tmp files
8390
print_highlight('Merge filtered files.')
84-
command = ['ros2', 'bag', 'merge', '-o', args.output]
91+
command = ['ros2', 'bag', 'merge', '-o', args.output]
8592
for f in dst_files:
8693
command.append(f)
8794
subprocess.run(command)

‎localization/yabloc/pcdless_launch/scripts/initialpose_latch.py

-59
This file was deleted.

‎localization/yabloc/pcdless_launch/scripts/bagplay_for_loc.py ‎localization/yabloc/pcdless_launch/scripts/play_rosbag_for_loc.py

+15-11
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,9 @@
1-
#!/usr/bin/python3
1+
#!/usr/bin/env python3
2+
'''
3+
Script to publish only the topics necessary to make the localization component work from rosbag.
4+
5+
e.g. $ ./play_rosbag_for_loc.py <your_rosbag_path> -o
6+
'''
27
import os
38
import subprocess
49
import argparse
@@ -13,14 +18,10 @@
1318
'/sensing/gnss/ublox/nav_sat_fix',
1419
'/sensing/gnss/ublox/navpvt',
1520
'/sensing/imu/tamagawa/imu_raw',
16-
'/sensing/lidar/left/velodyne_packets',
17-
'/sensing/lidar/right/velodyne_packets',
18-
'/sensing/lidar/rear/velodyne_packets',
1921
'/sensing/lidar/top/velodyne_packets',
2022
'/sensing/camera/traffic_light/camera_info',
2123
'/sensing/camera/traffic_light/image_raw/compressed',
22-
'/vehicle/status/gear_status',
23-
'/vehicle/status/steering_status',
24+
# .universe
2425
'/vehicle/status/velocity_status',
2526
# .iv
2627
'/vehicle/status/twist',
@@ -41,7 +42,8 @@
4142
def doesRosbagIncludeTopics(rosbag):
4243
reader = SequentialReader()
4344
bag_storage_otions = StorageOptions(uri=rosbag, storage_id="sqlite3")
44-
bag_converter_options = ConverterOptions(input_serialization_format="cdr", output_serialization_format="cdr")
45+
bag_converter_options = ConverterOptions(
46+
input_serialization_format="cdr", output_serialization_format="cdr")
4547
reader.open(bag_storage_otions, bag_converter_options)
4648

4749
included = []
@@ -57,13 +59,13 @@ def printCommand(command):
5759
for c in command[0:idx]:
5860
print(c, end=' ')
5961
print(command[idx])
60-
for c in command[idx+1:]:
62+
for c in command[idx + 1:]:
6163
print('\t', c)
6264
print('\033[0m')
6365

6466
print('The following topics are not included in rosbag')
6567
for t in TOPICS:
66-
if not t in command[idx+1:]:
68+
if not t in command[idx + 1:]:
6769
print('\t', t)
6870

6971

@@ -81,8 +83,10 @@ def makeOverrideYaml(yaml_path):
8183
def main():
8284
parser = argparse.ArgumentParser()
8385
parser.add_argument('rosbag', help='rosbag file to replay')
84-
parser.add_argument('-r', '--rate', default='1.0', help='rate at which to play back messages. Valid range > 0.0.')
85-
parser.add_argument('-o', '--override', action='store_true', help='qos profile overrides')
86+
parser.add_argument('-r', '--rate', default='1.0',
87+
help='rate at which to play back messages. Valid range > 0.0.')
88+
parser.add_argument('-o', '--override',
89+
action='store_true', help='qos profile overrides')
8690

8791
args = parser.parse_args()
8892

‎localization/yabloc/pcdless_launch/scripts/plot_navpvt_vel.py

-87
This file was deleted.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,58 @@
1+
#!/usr/bin/env python3
2+
'''
3+
This is a script to visualize the control topic of Autoware to validate planning/control component.
4+
The node subscribes /control/command/control_cmd and publishes it as string and floot value.
5+
6+
e.g. $ ./publish_control_command.py
7+
'''
8+
import rclpy
9+
from rclpy.node import Node
10+
from autoware_auto_control_msgs.msg import AckermannControlCommand
11+
from std_msgs.msg import String
12+
from std_msgs.msg import Float32
13+
import numpy as np
14+
15+
16+
class control_command_publisher(Node):
17+
def __init__(self):
18+
super().__init__('control_command_publisher')
19+
20+
self.sub_command_ = self.create_subscription(
21+
AckermannControlCommand, '/control/command/control_cmd', self.command_callback, 10)
22+
23+
self.pub_string_ = self.create_publisher(String, '/string/command', 10)
24+
self.pub_float_ = self.create_publisher(Float32, '/float/steer', 10)
25+
26+
def command_callback(self, msg: AckermannControlCommand):
27+
28+
commands = {}
29+
commands['steer_angle(deg)'] = msg.lateral.steering_tire_angle * \
30+
180 / np.pi
31+
commands['steer_rate(deg/s)'] = msg.lateral.steering_tire_rotation_rate * 180 / np.pi
32+
commands['speed'] = msg.longitudinal.speed
33+
commands['accel'] = msg.longitudinal.acceleration
34+
commands['jerk '] = msg.longitudinal.jerk
35+
36+
str_msg = String()
37+
str_msg.data = '-- Control Command Status --\n'
38+
for key, value in commands.items():
39+
str_msg.data += key + ': ' + '{:.3f}'.format(value) + '\n'
40+
41+
self.pub_string_.publish(str_msg)
42+
43+
float_msg = Float32()
44+
float_msg.data = msg.lateral.steering_tire_angle * 180 / np.pi
45+
self.pub_float_.publish(float_msg)
46+
47+
48+
def main(args=None):
49+
rclpy.init(args=args)
50+
51+
converter = control_command_publisher()
52+
rclpy.spin(converter)
53+
converter.destroy_node()
54+
rclpy.shutdown()
55+
56+
57+
if __name__ == '__main__':
58+
main()

0 commit comments

Comments
 (0)