Skip to content

Commit

Permalink
fix(vehicle_cmd_gate): change /autoware/engage/ to transient_local
Browse files Browse the repository at this point in the history
  • Loading branch information
h-ohta committed Jun 4, 2024
1 parent 6664ec5 commit 107c07d
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,8 @@ Compatibility::Compatibility(rclcpp::Node * node) : node_(node)
"/control/external_cmd_selector/current_selector_mode", 1,
std::bind(&Compatibility::on_selector_mode, this, std::placeholders::_1));

pub_autoware_engage_ = node->create_publisher<AutowareEngage>("/autoware/engage", 1);
pub_autoware_engage_ =
node->create_publisher<AutowareEngage>("/autoware/engage", rclcpp::QoS(1).transient_local());
pub_gate_mode_ = node->create_publisher<GateMode>("/control/gate_mode_cmd", 1);
cli_selector_mode_ =
node->create_client<SelectorModeSrv>("/control/external_cmd_selector/select_external_command");
Expand Down
3 changes: 2 additions & 1 deletion control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,8 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options)
gate_mode_sub_ = create_subscription<GateMode>(
"input/gate_mode", 1, std::bind(&VehicleCmdGate::onGateMode, this, _1));
engage_sub_ = create_subscription<EngageMsg>(
"input/engage", 1, std::bind(&VehicleCmdGate::onEngage, this, _1));
"input/engage", rclcpp::QoS(1).transient_local(),
std::bind(&VehicleCmdGate::onEngage, this, _1));
kinematics_sub_ = create_subscription<Odometry>(
"/localization/kinematic_state", 1,
[this](Odometry::SharedPtr msg) { current_kinematics_ = *msg; });
Expand Down

0 comments on commit 107c07d

Please sign in to comment.