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 1c967a7bc3cb4..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 @@ -72,13 +72,13 @@ void AccelBrakeMapCalibratorButtonPanel::onInitialize() update_suggest_sub_ = raw_node->create_subscription( topic_edit_->text().toStdString(), 10, std::bind( - &AccelBrakeMapCalibratorButtonPanel::callback_update_suggest, this, std::placeholders::_1)); + &AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest, this, std::placeholders::_1)); client_ = raw_node->create_client( "/accel_brake_map_calibrator/update_map_dir"); } -void AccelBrakeMapCalibratorButtonPanel::callback_update_suggest( +void AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest( const std_msgs::msg::Bool::ConstSharedPtr msg) { if (after_calib_) { @@ -96,7 +96,7 @@ void AccelBrakeMapCalibratorButtonPanel::callback_update_suggest( calibration_button_->setEnabled(true); } -void AccelBrakeMapCalibratorButtonPanel::edit_topic() +void AccelBrakeMapCalibratorButtonPanel::editTopic() { update_suggest_sub_.reset(); rclcpp::Node::SharedPtr raw_node = @@ -104,12 +104,12 @@ void AccelBrakeMapCalibratorButtonPanel::edit_topic() update_suggest_sub_ = raw_node->create_subscription( topic_edit_->text().toStdString(), 10, std::bind( - &AccelBrakeMapCalibratorButtonPanel::callback_update_suggest, this, std::placeholders::_1)); + &AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest, this, std::placeholders::_1)); calibration_button_->setText("Wait for subscribe topic"); calibration_button_->setEnabled(false); } -void AccelBrakeMapCalibratorButtonPanel::push_calibration_button() +void AccelBrakeMapCalibratorButtonPanel::pushCalibrationButton() { // lock button calibration_button_->setEnabled(false); diff --git a/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.hpp b/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.hpp index 93fb23ccde3ce..e26789c9f120f 100644 --- a/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.hpp +++ b/common/tier4_calibration_rviz_plugin/src/accel_brake_map_calibrator_button_panel.hpp @@ -42,11 +42,11 @@ class AccelBrakeMapCalibratorButtonPanel : public rviz_common::Panel public: explicit AccelBrakeMapCalibratorButtonPanel(QWidget * parent = nullptr); void onInitialize() override; - void callback_update_suggest(const std_msgs::msg::Bool::ConstSharedPtr msg); + void callbackUpdateSuggest(const std_msgs::msg::Bool::ConstSharedPtr msg); public Q_SLOTS: // NOLINT for Qt - void edit_topic(); - void push_calibration_button(); + void editTopic(); + void pushCalibrationButton(); protected: rclcpp::Subscription::SharedPtr update_suggest_sub_;