Skip to content

Commit af86134

Browse files
TakumiKozaka-T4kenji-miyakepre-commit-ci[bot]
authored
feat: publisher and server for calibration with external application (#722)
* ci: add sync-upstream.yaml (#4) Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * ci(sync-upstream): update settings (#19) Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp> * (editting) add node for creating calibration data Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * (editting) modify server node Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * (editting) add server and client Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * (editting) add client and server Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * modify server and client Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * modify client and server Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * modify server node Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * delete debug codes Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * run pre-commit Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * rebase to autowarefoundation/autoware/main Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * Delete sync-upstream.yaml This file is added by mistake. * merge the latest version of universe main * return empty data when error occurs Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * modify plot_csv_server for adding it to launcher Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * pull the latest universe main * modify test script Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * ci(pre-commit): autofix * rename server file, add test script for calibration status change Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * ci(pre-commit): autofix * change node name Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * Fix status when default accel/brake map is not found Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * run pre-commit Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * return blank data if default map is not found. Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * ci(pre-commit): autofix * change calibration status definition Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * Change print to get_logger(). Delete unnecessary comment. Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * pull the latest foundation main Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * modified as comment in PR Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * Delete unnecessary sentences. Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> * ci(pre-commit): autofix * pull the latest foundation/main Signed-off-by: TakumiKozaka-T4 <takumi.kozaka@tier4.jp> Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent e78c275 commit af86134

File tree

8 files changed

+562
-7
lines changed

8 files changed

+562
-7
lines changed

vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/CMakeLists.txt

+3
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,9 @@ install(
2121
scripts/csv_reader.py
2222
scripts/log_analyzer.py
2323
scripts/view_plot.py
24+
scripts/new_accel_brake_map_server.py
25+
test/plot_csv_client_node.py
26+
test/sim_actuation_status_publisher.py
2427
DESTINATION lib/${PROJECT_NAME}
2528
)
2629

vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp

+6
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,9 @@
4242
#include "std_msgs/msg/string.hpp"
4343
#include "tier4_debug_msgs/msg/float32_multi_array_stamped.hpp"
4444
#include "tier4_debug_msgs/msg/float32_stamped.hpp"
45+
#include "tier4_external_api_msgs/msg/calibration_status.hpp"
46+
#include "tier4_external_api_msgs/msg/calibration_status_array.hpp"
47+
#include "tier4_external_api_msgs/srv/get_accel_brake_map_calibration_data.hpp"
4548
#include "tier4_vehicle_msgs/msg/actuation_status_stamped.hpp"
4649
#include "tier4_vehicle_msgs/srv/update_accel_brake_map.hpp"
4750

@@ -84,6 +87,8 @@ class AccelBrakeMapCalibrator : public rclcpp::Node
8487
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr current_map_error_pub_;
8588
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr updated_map_error_pub_;
8689
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr map_error_ratio_pub_;
90+
rclcpp::Publisher<tier4_external_api_msgs::msg::CalibrationStatus>::SharedPtr
91+
calibration_status_pub_;
8792

8893
rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::VelocityReport>::SharedPtr velocity_sub_;
8994
rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::SteeringReport>::SharedPtr steer_sub_;
@@ -110,6 +115,7 @@ class AccelBrakeMapCalibrator : public rclcpp::Node
110115

111116
// Diagnostic Updater
112117
std::shared_ptr<diagnostic_updater::Updater> updater_ptr_;
118+
bool is_default_map_ = true;
113119

114120
int get_pitch_method_;
115121
int update_method_;

vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/launch/accel_brake_map_calibrator.launch.xml

+2
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,8 @@
2424
<param name="use_sim_time" value="$(var use_sim_time)"/>
2525
</node>
2626

27+
<!-- calibration plot and map server node -->
28+
<node pkg="accel_brake_map_calibrator" exec="new_accel_brake_map_server.py" name="new_accel_brake_map_server" output="screen"/>
2729
<!-- Rviz -->
2830
<node pkg="rviz2" exec="rviz2" name="rviz2" output="screen" args="-d $(find-pkg-share accel_brake_map_calibrator)/rviz/occupancy.rviz" if="$(var rviz)"/>
2931
</launch>

vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
<depend>tf2_ros</depend>
2323
<depend>tier4_autoware_utils</depend>
2424
<depend>tier4_debug_msgs</depend>
25+
<depend>tier4_external_api_msgs</depend>
2526
<depend>tier4_vehicle_msgs</depend>
2627
<depend>visualization_msgs</depend>
2728

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,338 @@
1+
#! /usr/bin/env python3
2+
3+
# Copyright 2022 Tier IV, Inc.
4+
#
5+
# Licensed under the Apache License, Version 2.0 (the "License");
6+
# you may not use this file except in compliance with the License.
7+
# You may obtain a copy of the License at
8+
#
9+
# http://www.apache.org/licenses/LICENSE-2.0
10+
#
11+
# Unless required by applicable law or agreed to in writing, software
12+
# distributed under the License is distributed on an "AS IS" BASIS,
13+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14+
# See the License for the specific language governing permissions and
15+
# limitations under the License.
16+
17+
import math
18+
from pathlib import Path
19+
20+
from ament_index_python.packages import get_package_share_directory
21+
from calc_utils import CalcUtils
22+
import config as CF
23+
from csv_reader import CSVReader
24+
import matplotlib.pyplot as plt
25+
import numpy as np
26+
from plotter import Plotter
27+
import rclpy
28+
from rclpy.node import Node
29+
from tier4_external_api_msgs.srv import GetAccelBrakeMapCalibrationData as CalibData
30+
import yaml
31+
32+
33+
class DrawGraph(Node):
34+
calibrated_map_dir = ""
35+
36+
def __init__(self):
37+
super().__init__("plot_server")
38+
self.srv = self.create_service(
39+
CalibData, "/accel_brake_map_calibrator/get_data_service", self.get_data_callback
40+
)
41+
42+
package_path = get_package_share_directory("accel_brake_map_calibrator")
43+
default_map_path = get_package_share_directory("raw_vehicle_cmd_converter")
44+
45+
self.default_map_dir = default_map_path + "/data/default/"
46+
self.calibrated_map_dir = package_path + "/config/"
47+
self.log_file = package_path + "/config/log.csv"
48+
49+
config_file = package_path + "/config/accel_brake_map_calibrator.param.yaml"
50+
if Path(config_file).exists():
51+
self.get_logger().info("config file exists")
52+
with open(config_file) as yml:
53+
data = yaml.safe_load(yml)
54+
self.min_vel_thr = data["/**"]["ros__parameters"]["velocity_min_threshold"]
55+
self.vel_diff_thr = data["/**"]["ros__parameters"]["velocity_diff_threshold"]
56+
self.pedal_diff_thr = data["/**"]["ros__parameters"]["pedal_diff_threshold"]
57+
self.max_steer_thr = data["/**"]["ros__parameters"]["max_steer_threshold"]
58+
self.max_pitch_thr = data["/**"]["ros__parameters"]["max_pitch_threshold"]
59+
self.max_jerk_thr = data["/**"]["ros__parameters"]["max_jerk_threshold"]
60+
else:
61+
self.get_logger().warning("config file is not found in {}".format(config_file))
62+
self.min_vel_thr = 0.1
63+
self.vel_diff_thr = 0.556
64+
self.pedal_diff_thr = 0.03
65+
self.max_steer_thr = 0.2
66+
self.max_pitch_thr = 0.02
67+
self.max_jerk_thr = 0.7
68+
69+
self.max_pedal_vel_thr = 0.7
70+
71+
# debug
72+
self.get_logger().info("default map dir: {}".format(self.default_map_dir))
73+
self.get_logger().info("calibrated map dir: {}".format(self.calibrated_map_dir))
74+
self.get_logger().info("log file :{}".format(self.log_file))
75+
self.get_logger().info("min_vel_thr : {}".format(self.min_vel_thr))
76+
self.get_logger().info("vel_diff_thr : {}".format(self.vel_diff_thr))
77+
self.get_logger().info("pedal_diff_thr : {}".format(self.pedal_diff_thr))
78+
self.get_logger().info("max_steer_thr : {}".format(self.max_steer_thr))
79+
self.get_logger().info("max_pitch_thr : {}".format(self.max_pitch_thr))
80+
self.get_logger().info("max_jerk_thr : {}".format(self.max_jerk_thr))
81+
self.get_logger().info("max_pedal_vel_thr : {}".format(self.max_pedal_vel_thr))
82+
83+
def get_data_callback(self, request, response):
84+
# read csv
85+
# If log file doesn't exsist, return empty data
86+
if not Path(self.log_file).exists():
87+
response.graph_image = []
88+
self.get_logger().info("svg data is empty")
89+
90+
response.accel_map = ""
91+
self.get_logger().info("accel map is empty")
92+
93+
response.brake_map = ""
94+
self.get_logger().info("brake map is empty")
95+
96+
return response
97+
98+
self.cr = CSVReader(self.log_file, csv_type="file")
99+
100+
# remove unused_data
101+
self.csv_data = self.cr.removeUnusedData(
102+
self.min_vel_thr,
103+
self.max_steer_thr,
104+
self.max_pitch_thr,
105+
self.max_pedal_vel_thr,
106+
self.max_jerk_thr,
107+
)
108+
109+
# get statistics array
110+
vel_data = self.cr.getVelData()
111+
pedal_data = self.cr.getPedalData()
112+
acc_data = self.cr.getAccData()
113+
114+
# get color factor (pitch) array for plotting
115+
color_data = self.cr.getPitchData()
116+
117+
data, full_data = CalcUtils.create_2d_map(
118+
vel_data,
119+
pedal_data,
120+
acc_data,
121+
color_data,
122+
CF.VEL_LIST / 3.6,
123+
self.vel_diff_thr,
124+
CF.PEDAL_LIST,
125+
self.pedal_diff_thr,
126+
)
127+
128+
count_map, average_map, stddev_map = CalcUtils.create_stat_map(data)
129+
velocity_map_list = []
130+
for i in range(len(CF.VEL_LIST)):
131+
velocity_map_list.append(CalcUtils.extract_x_index_map(full_data, i))
132+
133+
default_pedal_list, default_acc_list = self.load_map(self.default_map_dir)
134+
if len(default_pedal_list) == 0 or len(default_acc_list) == 0:
135+
self.get_logger().warning(
136+
"No default map file was found in {}".format(self.default_map_dir)
137+
)
138+
139+
response.graph_image = []
140+
self.get_logger().info("svg data is empty")
141+
142+
response.accel_map = ""
143+
self.get_logger().info("accel map is empty")
144+
145+
response.brake_map = ""
146+
self.get_logger().info("brake map is empty")
147+
148+
return response
149+
150+
calibrated_pedal_list, calibrated_acc_list = self.load_map(self.calibrated_map_dir)
151+
if len(calibrated_pedal_list) == 0 or len(calibrated_acc_list) == 0:
152+
self.get_logger().warning(
153+
"No calibrated map file was found in {}".format(self.calibrated_map_dir)
154+
)
155+
156+
# visualize point from data
157+
plot_width = 3
158+
plot_height = int(math.ceil(len(CF.VEL_LIST) / float(plot_width)))
159+
plotter = Plotter(plot_height, plot_width)
160+
for i in range(len(CF.VEL_LIST)):
161+
self.view_pedal_accel_graph(
162+
plotter,
163+
i,
164+
velocity_map_list,
165+
i,
166+
count_map,
167+
average_map,
168+
stddev_map,
169+
default_pedal_list,
170+
default_acc_list,
171+
calibrated_pedal_list,
172+
calibrated_acc_list,
173+
)
174+
plt.savefig("plot.svg")
175+
self.get_logger().info("svg saved")
176+
177+
# pack response data
178+
text = Path("plot.svg").read_text()
179+
if text == "":
180+
response.graph_image = []
181+
self.get_logger().info("svg data is empty")
182+
else:
183+
byte = text.encode()
184+
for b in byte:
185+
response.graph_image.append(b)
186+
self.get_logger().info("svg data is packed")
187+
188+
accel_map_name = Path(self.calibrated_map_dir + "accel_map.csv")
189+
if accel_map_name.exists():
190+
with open(self.calibrated_map_dir + "accel_map.csv", "r") as calibrated_accel_map:
191+
for accel_data in calibrated_accel_map:
192+
response.accel_map += accel_data
193+
self.get_logger().info("accel map is packed")
194+
else:
195+
response.accel_map = ""
196+
self.get_logger().info("accel map is empty")
197+
198+
brake_map_name = Path(self.calibrated_map_dir + "brake_map.csv")
199+
if brake_map_name.exists():
200+
with open(self.calibrated_map_dir + "brake_map.csv", "r") as calibrated_brake_map:
201+
for brake_data in calibrated_brake_map:
202+
response.brake_map += brake_data
203+
self.get_logger().info("brake map is packed")
204+
else:
205+
response.brake_map = ""
206+
self.get_logger().info("brake map is empty")
207+
208+
return response
209+
210+
def plotter_function(self):
211+
return self.plotter
212+
213+
def view_pedal_accel_graph(
214+
self,
215+
plotter,
216+
subplot_num,
217+
velocity_map_list,
218+
vel_list_idx,
219+
count_map,
220+
average_map,
221+
stddev_map,
222+
default_pedal_list,
223+
default_acc_list,
224+
calibrated_pedal_list,
225+
calibrated_acc_list,
226+
):
227+
228+
fig = plotter.subplot_more(subplot_num)
229+
230+
# calibrated map
231+
if len(calibrated_pedal_list) != 0 and len(calibrated_acc_list) != 0:
232+
plotter.plot(
233+
calibrated_pedal_list[vel_list_idx],
234+
calibrated_acc_list[vel_list_idx],
235+
color="blue",
236+
label="calibrated",
237+
)
238+
239+
# default map
240+
if len(default_pedal_list) != 0 and len(default_acc_list) != 0:
241+
plotter.plot(
242+
default_pedal_list[vel_list_idx],
243+
default_acc_list[vel_list_idx],
244+
color="orange",
245+
label="default",
246+
linestyle="dashed",
247+
)
248+
249+
# plot all data
250+
pedal_list = [0 for i in range(len(CF.PEDAL_LIST))]
251+
if velocity_map_list[vel_list_idx] is not None:
252+
plotter.scatter_color(
253+
velocity_map_list[vel_list_idx][:, 1],
254+
velocity_map_list[vel_list_idx][:, 2],
255+
color=velocity_map_list[vel_list_idx][:, 3],
256+
label="all",
257+
)
258+
259+
for pedal in velocity_map_list[vel_list_idx][:, 1]:
260+
min_pedal = 10
261+
for pedal_idx, ref_pedal in enumerate(CF.PEDAL_LIST):
262+
if min_pedal > abs(pedal - ref_pedal):
263+
min_pedal = abs(pedal - ref_pedal)
264+
min_pedal_idx = pedal_idx
265+
pedal_list[min_pedal_idx] += 1
266+
267+
# plot average data
268+
plotter.scatter(CF.PEDAL_LIST, average_map[:, vel_list_idx], "red", label="average")
269+
270+
# add label of standard deviation
271+
plotter.scatter([], [], "black", label="std dev")
272+
273+
# plot average text
274+
for i in range(len(CF.PEDAL_LIST)):
275+
if count_map[i, vel_list_idx] == 0:
276+
continue
277+
x = CF.PEDAL_LIST[i]
278+
y = average_map[i, vel_list_idx]
279+
y2 = stddev_map[i, vel_list_idx]
280+
# plot average
281+
plotter.plot_text(x, y + 1, y, color="red")
282+
283+
# plot standard deviation
284+
plotter.plot_text(x, y - 1, y2, color="black")
285+
286+
# plot the number of all data
287+
plotter.plot_text(
288+
x, y - 2, "{}\npts".format(pedal_list[i]), num_data_type="str", color="green"
289+
)
290+
291+
pedal_lim = [CF.PEDAL_LIST[0] - 0.05, CF.PEDAL_LIST[-1] + 0.05]
292+
accel_lim = [-5.0, 5.0]
293+
294+
plotter.set_lim(fig, pedal_lim, accel_lim)
295+
plotter.add_label(
296+
str(CF.VEL_LIST[vel_list_idx]) + "kmh; pedal-accel relation", "pedal", "accel"
297+
)
298+
299+
def load_map(self, csv_dir):
300+
try:
301+
accel_pedal_list = []
302+
accel_acc_list = []
303+
with open(csv_dir + "accel_map.csv") as f:
304+
for l_idx, l in enumerate(f.readlines()):
305+
w = l.split(",")
306+
w[-1] = w[-1][:-1]
307+
if l_idx != 0:
308+
accel_pedal_list.append([float(w[0]) for e in w[1:]])
309+
accel_acc_list.append([float(e) for e in w[1:]])
310+
311+
brake_pedal_list = []
312+
brake_acc_list = []
313+
with open(csv_dir + "brake_map.csv") as f:
314+
for l_idx, l in enumerate(f.readlines()):
315+
w = l.split(",")
316+
w[-1] = w[-1][:-1]
317+
if l_idx != 0:
318+
brake_pedal_list.append([-float(w[0]) for e in w[1:]])
319+
brake_acc_list.append([float(e) for e in w[1:]])
320+
321+
return np.hstack(
322+
[np.fliplr(np.array(accel_pedal_list).T), np.array(brake_pedal_list).T.tolist()]
323+
), np.hstack([np.fliplr(np.array(accel_acc_list).T), np.array(brake_acc_list).T])
324+
except OSError as e:
325+
print(e)
326+
return [], []
327+
328+
329+
def main(args=None):
330+
rclpy.init(args=None)
331+
node = DrawGraph()
332+
rclpy.spin(node)
333+
node.destroy_node()
334+
rclpy.shutdown()
335+
336+
337+
if __name__ == "__main__":
338+
main()

0 commit comments

Comments
 (0)