From 67d5e68e615ef882944902a907b6329820cfce57 Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Thu, 29 Aug 2024 17:09:22 +0900 Subject: [PATCH] feat(raw_vehicle_cmd_converter): set convert_actuation_to_steering_status false by default (#8668) Signed-off-by: kosuke55 --- vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp index 6fb8f4dff44f6..696225db60609 100644 --- a/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp +++ b/vehicle/autoware_raw_vehicle_cmd_converter/src/node.cpp @@ -87,7 +87,7 @@ RawVehicleCommandConverterNode::RawVehicleCommandConverterNode( // NOTE: The steering status can be published from the vehicle side or converted in this node. convert_actuation_to_steering_status_ = - declare_parameter("convert_actuation_to_steering_status"); + declare_parameter("convert_actuation_to_steering_status", false); if (convert_actuation_to_steering_status_) { pub_steering_status_ = create_publisher("~/output/steering_status", 1); } else {