Skip to content

Commit

Permalink
fix: respond to spell checker
Browse files Browse the repository at this point in the history
  • Loading branch information
TetsuKawa committed Dec 16, 2023
1 parent 6321e1e commit e81c9a2
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 8 deletions.
4 changes: 2 additions & 2 deletions system/remapper/include/remapper/remapper_core.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ class Remapper : public rclcpp::Node
rclcpp::Subscription<autoware_auto_system_msgs::msg::AutowareState>::SharedPtr
sub_autoware_state_;
rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::ControlModeReport>::SharedPtr
sub_controle_mode_report_;
sub_control_mode_report_;
rclcpp::Subscription<tier4_external_api_msgs::msg::Emergency>::SharedPtr sub_get_emergency_;
rclcpp::Subscription<autoware_adapi_v1_msgs::msg::MrmState>::SharedPtr sub_mrm_state_;
rclcpp::Subscription<tier4_system_msgs::msg::DiagnosticGraph>::SharedPtr sub_diagnostics_graph_;
Expand All @@ -84,7 +84,7 @@ class Remapper : public rclcpp::Node

rclcpp::Publisher<autoware_auto_system_msgs::msg::AutowareState>::SharedPtr pub_autoware_state_;
rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::ControlModeReport>::SharedPtr
pub_controle_mode_report_;
pub_control_mode_report_;
rclcpp::Publisher<tier4_external_api_msgs::msg::Emergency>::SharedPtr pub_get_emergency_;
rclcpp::Publisher<autoware_adapi_v1_msgs::msg::MrmState>::SharedPtr pub_mrm_state_;
rclcpp::Publisher<tier4_system_msgs::msg::DiagnosticGraph>::SharedPtr pub_diagnostics_graph_;
Expand Down
6 changes: 3 additions & 3 deletions system/remapper/launch/remapper.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
<!-- <arg name="input_initialization_state" default="/api/localization/initialization_state"/> -->
<!-- <arg name="input_routing_state" default="/api/routing/state"/> -->
<!-- <arg name="input_operation_mode_state" default="/api/operation_mode/state"/> -->
<arg name="input_controle_mode" default="/vehicle/status/control_mode"/>
<arg name="input_control_mode" default="/vehicle/status/control_mode"/>
<arg name="input_get_emergency" default="/api/external/get/emergency"/>
<arg name="input_mrm_state" default="/api/fail_safe/mrm_state"/>
<arg name="input_diagnostics_graph" default="/diagnostics_graph"/>
Expand All @@ -35,7 +35,7 @@
<remap from="~/input/api/routing/route" to="$(var input_routing_route)"/>

<remap from="~/input/autoware/state" to="$(var input_autoware_state)"/>
<remap from="~/input/vehicle/status/control_mode" to="$(var input_controle_mode)"/>
<remap from="~/input/vehicle/status/control_mode" to="$(var input_control_mode)"/>
<remap from="~/input/api/external/get/emergency" to="$(var input_get_emergency)"/>
<remap from="~/input/api/fail_safe/mrm_state" to="$(var input_mrm_state)"/>
<remap from="~/input/diagnostics_graph" to="$(var input_diagnostics_graph)"/>
Expand All @@ -53,7 +53,7 @@
<remap from="~/output/api/routing/route" to="/$(var ecu_name)$(var input_routing_route)"/>

<remap from="~/output/autoware/state" to="/$(var ecu_name)$(var input_autoware_state)"/>
<remap from="~/output/vehicle/status/control_mode" to="/$(var ecu_name)$(var input_controle_mode)"/>
<remap from="~/output/vehicle/status/control_mode" to="/$(var ecu_name)$(var input_control_mode)"/>
<remap from="~/output/api/external/get/emergency" to="/$(var ecu_name)$(var input_get_emergency)"/>
<remap from="~/output/api/fail_safe/mrm_state" to="/$(var ecu_name)$(var input_mrm_state)"/>
<remap from="~/output/diagnostics_graph" to="/$(var ecu_name)$(var input_diagnostics_graph)"/>
Expand Down
6 changes: 3 additions & 3 deletions system/remapper/src/remapper_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ Remapper::Remapper() : Node("remapper")
"~/input/api/routing/route", rclcpp::QoS{1}, std::bind(&Remapper::onRoute, this, _1));
sub_autoware_state_ = create_subscription<autoware_auto_system_msgs::msg::AutowareState>(
"~/input/autoware/state", rclcpp::QoS{1}, std::bind(&Remapper::onAutowareState, this, _1));
sub_controle_mode_report_ =
sub_control_mode_report_ =
create_subscription<autoware_auto_vehicle_msgs::msg::ControlModeReport>(
"~/input/vehicle/status/control_mode", rclcpp::QoS{1},
std::bind(&Remapper::onControlModeReport, this, _1));
Expand Down Expand Up @@ -83,7 +83,7 @@ Remapper::Remapper() : Node("remapper")
"~/output/api/routing/route", rclcpp::QoS{1});
pub_autoware_state_ = create_publisher<autoware_auto_system_msgs::msg::AutowareState>(
"~/output/autoware/state", rclcpp::QoS{1});
pub_controle_mode_report_ = create_publisher<autoware_auto_vehicle_msgs::msg::ControlModeReport>(
pub_control_mode_report_ = create_publisher<autoware_auto_vehicle_msgs::msg::ControlModeReport>(
"~/output/vehicle/status/control_mode", rclcpp::QoS{1});
pub_get_emergency_ = create_publisher<tier4_external_api_msgs::msg::Emergency>(
"~/output/api/external/get/emergency", rclcpp::QoS{1});
Expand Down Expand Up @@ -154,7 +154,7 @@ void Remapper::onAutowareState(
void Remapper::onControlModeReport(
const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg)
{
pub_controle_mode_report_->publish(*msg);
pub_control_mode_report_->publish(*msg);
}

void Remapper::onEmergency(const tier4_external_api_msgs::msg::Emergency::ConstSharedPtr msg)
Expand Down

0 comments on commit e81c9a2

Please sign in to comment.