diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp index 663a53e9383b7..3c84312bc00a5 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp @@ -245,7 +245,7 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node /** * @brief ControlModeRequest server */ - void on_operation_mode_request( + void on_control_mode_request( const ControlModeRequest::Request::SharedPtr request, const ControlModeRequest::Response::SharedPtr response); diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index 5ef4edb527223..1ef3ea9d845ad 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -109,8 +109,8 @@ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & opt "input/trajectory", QoS{1}, std::bind(&SimplePlanningSimulator::on_trajectory, this, _1)); srv_mode_req_ = create_service( - "operation_mode_request", - std::bind(&SimplePlanningSimulator::on_operation_mode_request, this, _1, _2)); + "control_mode_request", + std::bind(&SimplePlanningSimulator::on_control_mode_request, this, _1, _2)); // TODO(Horibe): will be replaced by mode_request. May still be needed for scenario testing sub_engage_ = create_subscription( @@ -379,7 +379,7 @@ void SimplePlanningSimulator::on_engage(const Engage::ConstSharedPtr msg) simulate_motion_ = msg->engage; } -void SimplePlanningSimulator::on_operation_mode_request( +void SimplePlanningSimulator::on_control_mode_request( const ControlModeRequest::Request::SharedPtr request, const ControlModeRequest::Response::SharedPtr response) {