Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(accel_brake_map_calibrator): rviz panel type #895

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ void AccelBrakeMapCalibratorButtonPanel::onInitialize()
&AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest, this, std::placeholders::_1));

client_ = raw_node->create_client<tier4_vehicle_msgs::srv::UpdateAccelBrakeMap>(
"/vehicle/calibration/accel_brake_map_calibrator/update_map_dir");
"/accel_brake_map_calibrator/update_map_dir");
}

void AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 <rosbag_file> --clock
```

Expand Down Expand Up @@ -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: '<accel/brake map directory>'"
ros2 service call /accel_brake_map_calibrator/update_map_dir tier4_vehicle_msgs/srv/UpdateAccelBrakeMap "path: '<accel/brake map directory>'"
```

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.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down