From d17a178b2e01fe64d996b7944da221c2f73d7eb7 Mon Sep 17 00:00:00 2001 From: Mamoru Sobue Date: Tue, 17 May 2022 08:37:29 +0900 Subject: [PATCH] fix(accel_brake_map_calibrator): rviz panel type (#895) * fixed panel type Signed-off-by: Mamoru Sobue * modified instruction for rosbag replay case Signed-off-by: Mamoru Sobue * modified update_map_dir service name Signed-off-by: Mamoru Sobue --- .../src/accel_brake_map_calibrator_button_panel.cpp | 2 +- .../accel_brake_map_calibrator/README.md | 4 ++-- .../accel_brake_map_calibrator/rviz/occupancy.rviz | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp b/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp index 542ce6f7bdeda..545bdac7b630d 100644 --- a/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp +++ b/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.cpp @@ -75,7 +75,7 @@ void AccelBrakeMapCalibratorButtonPanel::onInitialize() &AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest, this, std::placeholders::_1)); client_ = raw_node->create_client( - "/vehicle/calibration/accel_brake_map_calibrator/update_map_dir"); + "/accel_brake_map_calibrator/update_map_dir"); } void AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest( diff --git a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/README.md b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/README.md index d7de930308412..0d30686bbe5e2 100644 --- a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/README.md +++ b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/README.md @@ -17,7 +17,7 @@ ros2 launch accel_brake_map_calibrator accel_brake_map_calibrator.launch.xml rvi Or if you want to use rosbag files, run the following commands. ```sh -ros2 param set /use_sim_time true +ros2 launch accel_brake_map_calibrator accel_brake_map_calibrator.launch.xml rviz:=true use_sim_time:=true ros2 bag play --clock ``` @@ -110,7 +110,7 @@ ros2 run accel_brake_map_calibrator view_statistics.py You can save accel and brake map anytime with the following command. ```sh -ros2 service call /accel_brake_map_calibrator/update_map_dir "path: ''" +ros2 service call /accel_brake_map_calibrator/update_map_dir tier4_vehicle_msgs/srv/UpdateAccelBrakeMap "path: ''" ``` You can also save accel and brake map in the default directory where Autoware reads accel_map.csv/brake_map.csv using the RViz plugin (AccelBrakeMapCalibratorButtonPanel) as following. diff --git a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/rviz/occupancy.rviz b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/rviz/occupancy.rviz index ca51dc4ee75fc..c430c21562f32 100644 --- a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/rviz/occupancy.rviz +++ b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/rviz/occupancy.rviz @@ -17,9 +17,9 @@ Panels: - /Current View1 Name: Views Splitter Ratio: 0.5 - - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel + - Class: tier4_localization_rviz_plugin/InitialPoseButtonPanel Name: InitialPoseButtonPanel - - Class: autoware_localization_rviz_plugin/InitialPoseButtonPanel + - Class: tier4_localization_rviz_plugin/InitialPoseButtonPanel Name: InitialPoseButtonPanel Preferences: PromptSaveOnExit: true