Skip to content

Jacob/finalize command vector changes#478

Merged
JMoore5353 merged 7 commits intomainfrom
jacob/finalize-command-vector-changes
Jan 27, 2026
Merged

Jacob/finalize command vector changes#478
JMoore5353 merged 7 commits intomainfrom
jacob/finalize-command-vector-changes

Conversation

@JMoore5353
Copy link
Contributor

This PR:

  1. Changes the command vector from the [Qx,Qy,Qz,Fx,Fy,Fz] vector to an arbitrary 10 vector. This will be needed as we "transition" to supporting the quadplane platform.
  2. Rearranges the implicit "default" ordering of the command vector from [torques, forces] to [forces, torques] to match with what the mixer expects.

Note that this default ordering is used when mapping RC values to the command vector, and it should also be used when using the canned mixers, due to how the canned mixers have been hard-coded.

I'm pushing this PR through right now since it is a major (breaking) change. We need to push this through before v2.0, preferably.

Copy link

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

This PR migrates the flight-control “command vector” interface from a fixed 6-DOF [Qx,Qy,Qz,Fx,Fy,Fz] layout to a 10-element vector (u[10]), and changes the default ordering to [forces, torques] to align with mixer expectations (in preparation for quadplane support).

Changes:

  • Refactors command/controls plumbing across CommandManager, Controller, and Mixer to use u[10] instead of named 6-DOF fields.
  • Expands custom mixer parameter matrices from 6×10 to 10×10 and updates canned mixers to the new matrix layout.
  • Updates MAVLink OFFBOARD_CONTROL message to carry u[10] instead of six scalar fields.

Reviewed changes

Copilot reviewed 19 out of 19 changed files in this pull request and generated 10 comments.

Show a summary per file
File Description
test/command_manager_test.cpp Updates tests to assert against the new u[] indexing/order.
src/param.cpp Adds defaults for the expanded (10×10) primary/secondary mixer parameter matrices.
src/mixer.cpp Migrates mixing and mixer-param handling to the new u[10] / 10×10 matrix approach.
src/controller.cpp Updates PID/control computation to read/write the new u[] command channels.
src/command_manager.cpp Updates RC interpretation and offboard timeout handling for the new u[] structure.
src/comm_manager.cpp Updates offboard control callback to populate control_t.u[10] and types.
include/param.h Extends mixer param enum to include rows 6–9 for a 10×10 matrix.
include/mixer.h Replaces per-axis mixer rows with u[10][10] and updates canned mixer definitions.
include/controller.h Replaces Fx/Fy/Fz/Qx/Qy/Qz output fields with u[10].
include/command_manager.h Replaces named control fields with u[10] and reorders default channel meaning.
include/comm_manager.h Widens send_params_index_ to uint16_t to support larger param counts.
include/comm_link.h Updates OffboardControl to carry u[10] instead of six named channels.
comms/mavlink/v1.0/rosflight/version.h Updates generated MAVLink build date.
comms/mavlink/v1.0/rosflight/testsuite.h Updates generated OFFBOARD_CONTROL serialization tests for u[10].
comms/mavlink/v1.0/rosflight/rosflight.h Updates generated MAVLink hashes/lengths/CRCs for the modified message set.
comms/mavlink/v1.0/rosflight/mavlink_msg_offboard_control.h Updates generated OFFBOARD_CONTROL message definition to u[10].
comms/mavlink/v1.0/rosflight/mavlink.h Updates generated MAVLink primary XML hash.
comms/mavlink/rosflight.xml Updates MAVLink XML definition of OFFBOARD_CONTROL to u[10] and new ignore bits.
comms/mavlink/mavlink.cpp Updates message decoding to populate u[10] in OffboardControl.
Comments suppressed due to low confidence (2)

src/controller.cpp:297

  • run_pid_loops() never sets out.u[6..9]. Since Controller::Output defaults these to 0, any commands provided on the new channels will be dropped before mixing, making mixer rows 6-9 ineffective. If u[6..9] are intended for direct/pass-through control, copy them from command.u[...] (or define how they should be generated) before returning.
  Controller::Output out;

  // ROLL
  if (command.u[3].type == RATE) {
    out.u[3] = roll_rate_.run(dt, state.angular_velocity.x, command.u[3].value, update_integrators);
  } else if (command.u[3].type == ANGLE) {
    out.u[3] =
      roll_.run(dt, state.roll, command.u[3].value, update_integrators, state.angular_velocity.x);
  } else {
    out.u[3] = command.u[3].value;
  }

  // PITCH
  if (command.u[4].type == RATE) {
    out.u[4] = pitch_rate_.run(dt, state.angular_velocity.y, command.u[4].value, update_integrators);
  } else if (command.u[4].type == ANGLE) {
    out.u[4] =
      pitch_.run(dt, state.pitch, command.u[4].value, update_integrators, state.angular_velocity.y);
  } else {
    out.u[4] = command.u[4].value;
  }

  // YAW
  if (command.u[5].type == RATE) {
    out.u[5] = yaw_rate_.run(dt, state.angular_velocity.z, command.u[5].value, update_integrators);
  } else {
    out.u[5] = command.u[5].value;
  }

  // Fx
  if (command.u[0].type == THROTTLE) {
    // Scales the saturation limit by RC_MAX_THROTTLE to maintain controllability 
    // during aggressive maneuvers.
    out.u[0] = command.u[0].value * RF_.params_.get_param_float(PARAM_RC_MAX_THROTTLE);

    if (RF_.params_.get_param_int(PARAM_USE_MOTOR_PARAMETERS)) {
      out.u[0] *= max_thrust_;
    }
  } else {
    // If it is not a throttle setting then pass directly to the mixer.
    out.u[0] = command.u[0].value;
  }

  // Fy
  if (command.u[1].type == THROTTLE) {
    // Scales the saturation limit by RC_MAX_THROTTLE to maintain controllability 
    // during aggressive maneuvers.
    out.u[1] = command.u[1].value * RF_.params_.get_param_float(PARAM_RC_MAX_THROTTLE);

    if (RF_.params_.get_param_int(PARAM_USE_MOTOR_PARAMETERS)) {
      out.u[1] *= max_thrust_;
    }
  } else {
    // If it is not a throttle setting then pass directly to the mixer.
    out.u[1] = command.u[1].value;
  }

  // Fz
  if (command.u[2].type == THROTTLE) {
    // Scales the saturation limit by RC_MAX_THROTTLE to maintain controllability 
    // during aggressive maneuvers.
    // Also note the negative sign. Since the mixer assumes the inputs are in the NED
    // frame, a throttle command corresponds to a thrust command in the negative direction.
    // Note that this also assumes that a high throttle means fly "up" (negative down)
    out.u[2] = -command.u[2].value * RF_.params_.get_param_float(PARAM_RC_MAX_THROTTLE);

    if (RF_.params_.get_param_int(PARAM_USE_MOTOR_PARAMETERS)) {
      out.u[2] *= max_thrust_;
    }
  } else {
    // If it is not a throttle setting then pass directly to the mixer.
    out.u[2] = command.u[2].value;
  }

  return out;
}

src/mixer.cpp:97

  • When mirroring the primary mixer into the secondary, the param-id computation still uses param_id_col*6 + param_id_row. With NUM_MIXER_OUTPUTS = 10, this will write to the wrong parameter ids and desynchronize the secondary mixer params. Use NUM_MIXER_OUTPUTS instead of the hard-coded 6.
      // Write the value to params -- otherwise, the secondary mixer gets out of sync
      uint16_t secondary_mixer_param_id = PARAM_SECONDARY_MIXER_0_0 + param_id_col*6 + param_id_row;
      RF_.params_.set_param_float(secondary_mixer_param_id, param_value);

💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.

Copy link

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

Copilot reviewed 19 out of 19 changed files in this pull request and generated 2 comments.

Comments suppressed due to low confidence (2)

src/command_manager.cpp:274

  • The second loop calls do_channel_muxing() for channels [NUM_MUX_CHANNELS, Mixer::NUM_MIXER_OUTPUTS), but do_channel_muxing indexes channel_override_[channel]. Since channel_override_ is sized to NUM_MUX_CHANNELS (6), this will read out of bounds for channels 6–9 and can crash/corrupt state. Consider either (a) handling u[6..9] in a separate code path that doesn’t consult channel_override_, or (b) extending the MuxChannel enum + channel_override_ to cover all 10 channels (with override_mask=0 for the extra ones).
  for (uint8_t channel{NUM_MUX_CHANNELS}; channel < Mixer::NUM_MIXER_OUTPUTS; ++channel) {
    do_channel_muxing(static_cast<MuxChannel>(channel), 0);
  }
}

void CommandManager::do_channel_muxing(MuxChannel channel, uint16_t rc_override )
{
  bool override_this_channel = (rc_override & channel_override_[channel].override_mask);
  // set the combined channel output depending on whether RC is overriding for this channel or not
  *muxes_[channel].combined = override_this_channel ? *muxes_[channel].rc : *muxes_[channel].onboard;
}

src/mixer.cpp:86

  • When mirroring primary->secondary mixer params, the secondary parameter index computation still uses a hard-coded row stride of 6 (param_id_col*6). With NUM_MIXER_OUTPUTS=10, this writes the wrong secondary mixer parameter IDs and will desynchronize/corrupt the secondary mixer. Use NUM_MIXER_OUTPUTS as the stride (and keep the row/col ordering consistent with the param enum).
      // Write the value to params -- otherwise, the secondary mixer gets out of sync
      uint16_t secondary_mixer_param_id = PARAM_SECONDARY_MIXER_0_0 + param_id_col*6 + param_id_row;
      RF_.params_.set_param_float(secondary_mixer_param_id, param_value);

💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.

Copy link

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

Copilot reviewed 19 out of 19 changed files in this pull request and generated 4 comments.


💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.

Copy link

Copilot AI left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Pull request overview

Copilot reviewed 19 out of 19 changed files in this pull request and generated 1 comment.


💡 Add Copilot custom instructions for smarter, more guided reviews. Learn how to get started.

@JMoore5353 JMoore5353 force-pushed the jacob/finalize-command-vector-changes branch from 06ac25a to eb28683 Compare January 27, 2026 18:40
@JMoore5353 JMoore5353 force-pushed the jacob/finalize-command-vector-changes branch from eb28683 to 36ba9e6 Compare January 27, 2026 19:02
@JMoore5353 JMoore5353 marked this pull request as ready for review January 27, 2026 19:08
@JMoore5353 JMoore5353 merged commit 71ca9f6 into main Jan 27, 2026
2 checks passed
@JMoore5353 JMoore5353 deleted the jacob/finalize-command-vector-changes branch January 27, 2026 19:10
@JMoore5353 JMoore5353 restored the jacob/finalize-command-vector-changes branch January 31, 2026 03:45
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

4 participants