diff --git a/odrive_node/src/odrive_can_node.cpp b/odrive_node/src/odrive_can_node.cpp index 0450bde..6af79c5 100644 --- a/odrive_node/src/odrive_can_node.cpp +++ b/odrive_node/src/odrive_can_node.cpp @@ -54,10 +54,7 @@ void ODriveCanNode::deinit() { if (axis_idle_on_shutdown_) { struct can_frame frame; frame.can_id = node_id_ << 5 | CmdId::kSetAxisState; - { - std::unique_lock guard(axis_state_mutex_); - write_le(ODriveAxisState::AXIS_STATE_IDLE, frame.data); - } + write_le(ODriveAxisState::AXIS_STATE_IDLE, frame.data); frame.can_dlc = 4; can_intf_.send_can_frame(frame); }