From 1144e236b9589410bef5f5c20ad467ba9490f128 Mon Sep 17 00:00:00 2001 From: MeierTobias Date: Sun, 11 Jan 2026 19:29:39 +0100 Subject: [PATCH] fix: initialize can_frame struct to avoid warnings --- odrive_node/src/odrive_can_node.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/odrive_node/src/odrive_can_node.cpp b/odrive_node/src/odrive_can_node.cpp index 5f7ae42..6aa1764 100644 --- a/odrive_node/src/odrive_can_node.cpp +++ b/odrive_node/src/odrive_can_node.cpp @@ -61,7 +61,7 @@ ODriveCanNode::ODriveCanNode(const std::string& node_name) : rclcpp::Node(node_n void ODriveCanNode::deinit() { if (axis_idle_on_shutdown_) { - struct can_frame frame; + struct can_frame frame = {}; frame.can_id = node_id_ << 5 | CmdId::kSetAxisState; write_le(ODriveAxisState::AXIS_STATE_IDLE, frame.data); frame.can_dlc = 4; @@ -221,7 +221,7 @@ void ODriveCanNode::service_callback(const std::shared_ptr r response->procedure_result = ctrl_stat_.procedure_result; } -void ODriveCanNode::service_clear_errors_callback(const std::shared_ptr request, std::shared_ptr response) { +void ODriveCanNode::service_clear_errors_callback(const std::shared_ptr /*request*/, std::shared_ptr /*response*/) { RCLCPP_INFO(rclcpp::Node::get_logger(), "clearing errors"); srv_clear_errors_evt_.set(); } @@ -251,7 +251,7 @@ void ODriveCanNode::request_state_callback() { } void ODriveCanNode::request_clear_errors_callback() { - struct can_frame frame; + struct can_frame frame = {}; frame.can_id = node_id_ << 5 | CmdId::kClearErrors; write_le(0, frame.data); frame.can_dlc = 1;