diff --git a/odrive_node/src/odrive_can_node.cpp b/odrive_node/src/odrive_can_node.cpp index 8b92c65..2e177ca 100644 --- a/odrive_node/src/odrive_can_node.cpp +++ b/odrive_node/src/odrive_can_node.cpp @@ -155,6 +155,14 @@ void ODriveCanNode::recv_callback(const can_frame& frame) { ctrl_pub_flag_ |= 0b1000; break; } + case CmdId::kSetAxisState: + case CmdId::kSetControllerMode: + case CmdId::kSetInputPos: + case CmdId::kSetInputVel: + case CmdId::kSetInputTorque: + case CmdId::kClearErrors: { + break; // Ignore commands coming from another master/host on the bus + } default: { RCLCPP_WARN(rclcpp::Node::get_logger(), "Received unused message: ID = 0x%x", (frame.can_id & 0x1F)); break;