PX4 Gazebo Classic SITL Custom Model Not Connecting to QGroundControl, Possible Mavlink Issue

I am trying to simulate a custom rover in gazebo classic using the SITL. I followed all of the steps posted here. When I run make px4_sitl gazebo-classic_kart, everything seems to work. The model spawns in to my custom world. However, when launching QGroundControl, it does not automatically connect like it normally does with the default models. Iā€™m assuming it is a problem with mavlink however, I have yet to identify the issue. Here is my code for the mavlink plugin in my kart.sdf file:

<plugin name='mavlink_interface' filename='libgazebo_mavlink_interface.so'>
      <robotNamespace/>
      <imuSubTopic>/imu</imuSubTopic>
      <magSubTopic>/mag</magSubTopic>
      <baroSubTopic>/baro</baroSubTopic>
      <mavlink_addr>INADDR_ANY</mavlink_addr>
      <mavlink_tcp_port>4560</mavlink_tcp_port>
      <mavlink_udp_port>14560</mavlink_udp_port>
      <serialEnabled>0</serialEnabled>
      <serialDevice>/dev/ttyACM0</serialDevice>
      <baudRate>921600</baudRate>
      <qgc_addr>INADDR_ANY</qgc_addr>
      <qgc_udp_port>14550</qgc_udp_port>
      <sdk_addr>INADDR_ANY</sdk_addr>
      <sdk_udp_port>14540</sdk_udp_port>
      <hil_mode>0</hil_mode>
      <hil_state_level>0</hil_state_level>
      <send_vision_estimation>0</send_vision_estimation>
      <send_odometry>1</send_odometry>
      <enable_lockstep>1</enable_lockstep>
      <use_tcp>1</use_tcp>
      <motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic>
      <control_channels>
        <channel name="rear_left_wheel_drive">
          <input_index>5</input_index>
          <input_offset>0</input_offset>
          <input_scaling>40</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>0</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
          <joint_name>rear_left_wheel_joint</joint_name>
          <joint_control_pid>
            <p>50</p>
            <i>20</i>
            <d>2</d>
            <iMax>800</iMax>
            <iMin>-800</iMin>
            <cmdMax>1200</cmdMax>
            <cmdMin>-1200</cmdMin>
          </joint_control_pid>
        </channel>
        <channel name="rear_right_wheel_drive">
          <input_index>6</input_index>
          <input_offset>0</input_offset>
          <input_scaling>40</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>0</zero_position_armed>
          <joint_control_type>velocity</joint_control_type>
          <joint_name>rear_right_wheel_joint</joint_name>
          <joint_control_pid>
            <p>50</p>
            <i>20</i>
            <d>2</d>
            <iMax>800</iMax>
            <iMin>-800</iMin>
            <cmdMax>1200</cmdMax>
            <cmdMin>-1200</cmdMin>
          </joint_control_pid>
        </channel>
        <channel name="left_wheel_steering">
          <input_index>0</input_index>
          <input_offset>0</input_offset>
          <input_scaling>-0.9</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>0</zero_position_armed>
          <joint_control_type>position</joint_control_type>
          <joint_name>front_left_steering_joint</joint_name>
          <joint_control_pid>
            <p>80</p>
            <i>40</i>
            <d>0.1</d>
            <iMax>40</iMax>
            <iMin>-40</iMin>
            <cmdMax>80</cmdMax>
            <cmdMin>-80</cmdMin>
          </joint_control_pid>
        </channel>
        <channel name="right_wheel_steering">
          <input_index>1</input_index>
          <input_offset>0</input_offset>
          <input_scaling>-0.9</input_scaling>
          <zero_position_disarmed>0</zero_position_disarmed>
          <zero_position_armed>0</zero_position_armed>
          <joint_control_type>position</joint_control_type>
          <joint_name>front_right_steering_joint</joint_name>
          <joint_control_pid>
            <p>80</p>
            <i>40</i>
            <d>0.1</d>
            <iMax>40</iMax>
            <iMin>-40</iMin>
            <cmdMax>80</cmdMax>
            <cmdMin>-80</cmdMin>
          </joint_control_pid>
        </channel>
      </control_channels>
 </plugin>

Any help would be greatly appreciated.