Skip to content

Commit

Permalink
fix(accel brake map calibrator): correction of forgotten support for …
Browse files Browse the repository at this point in the history
…util files change (#2509)

* fix accel brake map image server for api

* get calibration_method default value from parameter

* ci(pre-commit): autofix

* fix spell

Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
yabuta and pre-commit-ci[bot] committed Dec 22, 2022
1 parent 4600cf2 commit bfb55a3
Show file tree
Hide file tree
Showing 2 changed files with 38 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
<arg name="pedal_accel_graph_output" default="true"/>
<arg name="progress_file_output" default="false"/>
<arg name="use_sim_time" default="false"/>
<arg name="calibration_method" default="each_cell"/>

<!-- calibration interface -->
<node pkg="accel_brake_map_calibrator" exec="accel_brake_map_calibrator" name="accel_brake_map_calibrator" output="screen">
Expand All @@ -25,7 +26,9 @@
</node>

<!-- calibration plot and map server node -->
<node pkg="accel_brake_map_calibrator" exec="new_accel_brake_map_server.py" name="new_accel_brake_map_server" output="screen"/>
<node pkg="accel_brake_map_calibrator" exec="new_accel_brake_map_server.py" name="new_accel_brake_map_server" output="screen">
<param name="calibration_method" value="$(var calibration_method)"/>
</node>
<!-- Rviz -->
<node pkg="rviz2" exec="rviz2" name="rviz2" output="screen" args="-d $(find-pkg-share accel_brake_map_calibrator)/rviz/occupancy.rviz" if="$(var rviz)"/>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -35,15 +35,43 @@ class DrawGraph(Node):

def __init__(self):
super().__init__("plot_server")

self.srv = self.create_service(
CalibData, "/accel_brake_map_calibrator/get_data_service", self.get_data_callback
)

package_path = get_package_share_directory("accel_brake_map_calibrator")
default_map_path = get_package_share_directory("raw_vehicle_cmd_converter")
self.declare_parameter(
"/accel_brake_map_calibrator/csv_default_map_dir", default_map_path + "/data/default/"
)
self.default_map_dir = (
self.get_parameter("/accel_brake_map_calibrator/csv_default_map_dir")
.get_parameter_value()
.string_value
)

package_path = get_package_share_directory("accel_brake_map_calibrator")
self.declare_parameter(
"/accel_brake_map_calibrator/csv_calibrated_map_dir", package_path + "/config/"
)
self.calibrated_map_dir = (
self.get_parameter("/accel_brake_map_calibrator/csv_calibrated_map_dir")
.get_parameter_value()
.string_value
)

self.declare_parameter("calibration_method", "each_cell")
self.calibration_method = (
self.get_parameter("calibration_method").get_parameter_value().string_value
)
if self.calibration_method is None:
self.calibration_method = "each_cell"
elif not (
(self.calibration_method == "each_cell") | (self.calibration_method == "four_cell")
):
print("invalid method.")
self.calibration_method = "each_cell"

self.default_map_dir = default_map_path + "/data/default/"
self.calibrated_map_dir = package_path + "/config/"
self.log_file = package_path + "/config/log.csv"

config_file = package_path + "/config/accel_brake_map_calibrator.param.yaml"
Expand Down Expand Up @@ -71,6 +99,7 @@ def __init__(self):
# debug
self.get_logger().info("default map dir: {}".format(self.default_map_dir))
self.get_logger().info("calibrated map dir: {}".format(self.calibrated_map_dir))
self.get_logger().info("calibrated method: {}".format(self.calibration_method))
self.get_logger().info("log file :{}".format(self.log_file))
self.get_logger().info("min_vel_thr : {}".format(self.min_vel_thr))
self.get_logger().info("vel_diff_thr : {}".format(self.vel_diff_thr))
Expand All @@ -82,7 +111,7 @@ def __init__(self):

def get_data_callback(self, request, response):
# read csv
# If log file doesn't exsist, return empty data
# If log file doesn't exist, return empty data
if not Path(self.log_file).exists():
response.graph_image = []
self.get_logger().info("svg data is empty")
Expand Down Expand Up @@ -123,6 +152,7 @@ def get_data_callback(self, request, response):
self.vel_diff_thr,
CF.PEDAL_LIST,
self.pedal_diff_thr,
self.calibration_method,
)

count_map, average_map, stddev_map = CalcUtils.create_stat_map(data)
Expand Down

0 comments on commit bfb55a3

Please sign in to comment.