Add ids to flatbuffer fields in y2012, y2016, frc971, and aos

Change-Id: I9ed9006ce6224e2df0459df47771786b928164a1
diff --git a/frc971/control_loops/control_loops.fbs b/frc971/control_loops/control_loops.fbs
index f510085..243e2cb 100644
--- a/frc971/control_loops/control_loops.fbs
+++ b/frc971/control_loops/control_loops.fbs
@@ -8,11 +8,11 @@
 // position which varies with each robot.
 table IndexPosition {
   // Current position read from the encoder.
-  encoder:double;
+  encoder:double (id: 0);
   // Position from the encoder latched at the last index pulse.
-  latched_encoder:double;
+  latched_encoder:double (id: 1);
   // How many index pulses we've seen since startup. Starts at 0.
-  index_pulses:uint;
+  index_pulses:uint (id: 2);
 }
 
 // Represents all of the data for a single potentiometer and indexed encoder
@@ -23,17 +23,17 @@
 // position which varies with each robot.
 table PotAndIndexPosition {
   // Current position read from the encoder.
-  encoder:double;
+  encoder:double (id: 0);
   // Current position read from the potentiometer.
-  pot:double;
+  pot:double (id: 1);
 
   // Position from the encoder latched at the last index pulse.
-  latched_encoder:double;
+  latched_encoder:double (id: 2);
   // Position from the potentiometer latched at the last index pulse.
-  latched_pot:double;
+  latched_pot:double (id: 3);
 
   // How many index pulses we've seen since startup. Starts at 0.
-  index_pulses:uint;
+  index_pulses:uint (id: 4);
 }
 
 // Represents all of the data for a single potentiometer with an absolute and
@@ -44,11 +44,11 @@
 // arbitrary 0 position which varies with each robot.
 table PotAndAbsolutePosition {
   // Current position read from each encoder.
-  encoder:double;
-  absolute_encoder:double;
+  encoder:double (id: 0);
+  absolute_encoder:double (id: 1);
 
   // Current position read from the potentiometer.
-  pot:double;
+  pot:double (id: 2);
 }
 
 // Represents all of the data for an absolute and relative encoder pair.
@@ -57,8 +57,8 @@
 // arbitrary point in time.
 table AbsolutePosition {
   // Current position read from each encoder.
-  encoder:double;
-  absolute_encoder:double;
+  encoder:double (id: 0);
+  absolute_encoder:double (id: 1);
 }
 
 // Represents all of the data for an absolute and relative encoder pair,
@@ -70,12 +70,12 @@
 // arbitrary point in time.
 table AbsoluteAndAbsolutePosition {
   // Current position read from each encoder.
-  encoder:double;
-  absolute_encoder:double;
+  encoder:double (id: 0);
+  absolute_encoder:double (id: 1);
 
   // Current position read from the single turn absolute encoder.
   // This can not turn more than one rotation.
-  single_turn_absolute_encoder:double;
+  single_turn_absolute_encoder:double (id: 2);
 }
 
 // Represents all of the data for a single encoder.
@@ -83,51 +83,51 @@
 // arbitrary point in time.
 table RelativePosition {
   // Current position read from the encoder.
-  encoder:double;
+  encoder:double (id: 0);
 }
 
 // The internal state of a zeroing estimator.
 table EstimatorState {
   // If true, there has been a fatal error for the estimator.
-  error:bool;
+  error:bool (id: 0);
   // If the joint has seen an index pulse and is zeroed.
-  zeroed:bool;
+  zeroed:bool (id: 1);
   // The estimated position of the joint.
-  position:double;
+  position:double (id: 2);
 
   // The estimated position not using the index pulse.
-  pot_position:double;
+  pot_position:double (id: 3);
 }
 
 // The internal state of a zeroing estimator.
 table PotAndAbsoluteEncoderEstimatorState {
   // If true, there has been a fatal error for the estimator.
-  error:bool;
+  error:bool (id: 0);
   // If the joint has seen an index pulse and is zeroed.
-  zeroed:bool;
+  zeroed:bool (id: 1);
   // The estimated position of the joint.
-  position:double;
+  position:double (id: 2);
 
   // The estimated position not using the index pulse.
-  pot_position:double;
+  pot_position:double (id: 3);
 
   // The estimated absolute position of the encoder.  This is filtered, so it
   // can be easily used when zeroing.
-  absolute_position:double;
+  absolute_position:double (id: 4);
 }
 
 // The internal state of a zeroing estimator.
 table AbsoluteEncoderEstimatorState {
   // If true, there has been a fatal error for the estimator.
-  error:bool;
+  error:bool (id: 0);
   // If the joint has seen an index pulse and is zeroed.
-  zeroed:bool;
+  zeroed:bool (id: 1);
   // The estimated position of the joint.
-  position:double;
+  position:double (id: 2);
 
   // The estimated absolute position of the encoder.  This is filtered, so it
   // can be easily used when zeroing.
-  absolute_position:double;
+  absolute_position:double (id: 3);
 }
 
 // The internal state of a zeroing estimator.
@@ -149,94 +149,94 @@
 
 table RelativeEncoderEstimatorState {
   // If true, there has been a fatal error for the estimator.
-  error:bool;
+  error:bool (id: 0);
 
   // The estimated position of the joint.
-  position:double;
+  position:double (id: 1);
 }
 
 // The internal state of a zeroing estimator.
 table IndexEstimatorState {
   // If true, there has been a fatal error for the estimator.
-  error:bool;
+  error:bool (id: 0);
   // If the joint has seen an index pulse and is zeroed.
-  zeroed:bool;
+  zeroed:bool (id: 1);
   // The estimated position of the joint. This is just the position relative to
   // where we started if we're not zeroed yet.
-  position:double;
+  position:double (id: 2);
 
   // The positions of the extreme index pulses we've seen.
-  min_index_position:double;
-  max_index_position:double;
+  min_index_position:double (id: 3);
+  max_index_position:double (id: 4);
   // The number of index pulses we've seen.
-  index_pulses_seen:int;
+  index_pulses_seen:int (id: 5);
 }
 
 table HallEffectAndPositionEstimatorState {
   // If error.
-  error:bool;
+  error:bool (id: 0);
   // If we've found a positive edge while moving backwards and is zeroed.
-  zeroed:bool;
+  zeroed:bool (id: 1);
   // Encoder angle relative to where we started.
-  encoder:double;
+  encoder:double (id: 2);
   // The positions of the extreme posedges we've seen.
   // If we've gotten enough samples where the hall effect is high before can be
   // certain it is not a false positive.
-  high_long_enough:bool;
-  offset:double;
+  high_long_enough:bool (id: 3);
+  offset:double (id: 4);
 }
 
 // A left/right pair of PotAndIndexPositions.
 table PotAndIndexPair {
-  left:PotAndIndexPosition;
-  right:PotAndIndexPosition;
+  left:PotAndIndexPosition (id: 0);
+  right:PotAndIndexPosition (id: 1);
 }
 
 // Records edges captured on a single hall effect sensor.
 table HallEffectStruct {
-  current:bool;
-  posedge_count:int;
-  negedge_count:int;
-  posedge_value:double;
-  negedge_value:double;
+  current:bool (id: 0);
+  posedge_count:int (id: 1);
+  negedge_count:int (id: 2);
+  posedge_value:double (id: 3);
+  negedge_value:double (id: 4);
 }
 
 // Records the hall effect sensor and encoder values.
 table HallEffectAndPosition {
   // The current hall effect state.
-  current:bool;
+  current:bool (id: 0);
   // The current encoder position.
-  encoder:double;
+  encoder:double (id: 1);
   // The number of positive and negative edges we've seen on the hall effect
   // sensor.
-  posedge_count:int;
-  negedge_count:int;
+  posedge_count:int (id: 2);
+  negedge_count:int (id: 3);
   // The values corresponding to the last hall effect sensor reading.
-  posedge_value:double;
-  negedge_value:double;
+  posedge_value:double (id: 4);
+  negedge_value:double (id: 5);
 }
 
 // Records the positions for a mechanism with edge-capturing sensors on it.
 table HallEventPositions {
-  current:double;
-  posedge:double;
-  negedge:double;
+  current:double (id: 0);
+  posedge:double (id: 1);
+  negedge:double (id: 2);
 }
 
 // Records edges captured on a single hall effect sensor.
 table PosedgeOnlyCountedHallEffectStruct {
-  current:bool;
-  posedge_count:int;
-  negedge_count:int;
-  posedge_value:double;
+  current:bool (id: 0);
+  posedge_count:int (id: 1);
+  negedge_count:int (id: 2);
+  posedge_value:double (id: 3);
 }
 
 // Parameters for the motion profiles.
 table ProfileParameters {
   // Maximum velocity for the profile.
-  max_velocity:float;
+  max_velocity:float (id: 0);
   // Maximum acceleration for the profile.
-  max_acceleration:float;
+  max_acceleration:float (id: 1);
 }
 
 enum ConstraintType : byte {
@@ -249,13 +249,13 @@
 
 // Definition of a constraint on a trajectory
 table Constraint {
-  constraint_type:ConstraintType;
+  constraint_type:ConstraintType (id: 0);
 
-  value:float;
+  value:float (id: 1);
 
   // start and end distance are only checked for velocity limits.
-  start_distance:float;
-  end_distance:float;
+  start_distance:float (id: 2);
+  end_distance:float (id: 3);
 }
 
 // Parameters for computing a trajectory using a chain of splines and
@@ -264,11 +264,11 @@
   // Number of splines. The spline point arrays will be expected to have
   // 6 + 5 * (n - 1) points in them. The endpoints are shared between
   // neighboring splines.
-  spline_count:byte;
+  spline_count:byte (id: 0);
   // Maximum of 36 spline points (7 splines).
-  spline_x:[float];
-  spline_y:[float];
+  spline_x:[float] (id: 1);
+  spline_y:[float] (id: 2);
 
   // Maximum of 6 constraints;
-  constraints:[Constraint];
+  constraints:[Constraint] (id: 3);
 }
diff --git a/frc971/control_loops/drivetrain/drivetrain_goal.fbs b/frc971/control_loops/drivetrain/drivetrain_goal.fbs
index 8a67849..3df5210 100644
--- a/frc971/control_loops/drivetrain/drivetrain_goal.fbs
+++ b/frc971/control_loops/drivetrain/drivetrain_goal.fbs
@@ -11,55 +11,55 @@
 
 table SplineGoal {
   // index of the spline. Zero indicates the spline should not be computed.
-  spline_idx:int;
+  spline_idx:int (id: 0);
 
   // Acutal spline.
-  spline:frc971.MultiSpline;
+  spline:frc971.MultiSpline (id: 1);
 
   // Whether to follow the spline driving forwards or backwards.
-  drive_spline_backwards:bool;
+  drive_spline_backwards:bool (id: 2);
 }
 
 table Goal {
   // Position of the steering wheel (positive = turning left when going
   // forwards).
-  wheel:float;
-  wheel_velocity:float;
-  wheel_torque:float;
+  wheel:float (id: 0);
+  wheel_velocity:float (id: 1);
+  wheel_torque:float (id: 2);
 
   // Position of the throttle (positive forwards).
-  throttle:float;
-  throttle_velocity:float;
-  throttle_torque:float;
+  throttle:float (id: 3);
+  throttle_velocity:float (id: 4);
+  throttle_torque:float (id: 5);
 
   // True to shift into high, false to shift into low.
-  highgear:bool;
+  highgear:bool (id: 6);
 
   // True to activate quickturn.
-  quickturn:bool;
+  quickturn:bool (id: 7);
 
   // Type of controller in charge of the drivetrain.
-  controller_type:ControllerType;
+  controller_type:ControllerType (id: 8);
 
   // Position goals for each drivetrain side (in meters) when the
   // closed-loop controller is active.
-  left_goal:double;
-  right_goal:double;
+  left_goal:double (id: 9);
+  right_goal:double (id: 10);
 
-  max_ss_voltage:float;
+  max_ss_voltage:float (id: 11);
 
   // Motion profile parameters.
   // The control loop will profile if these are all non-zero.
-  linear:ProfileParameters;
-  angular:ProfileParameters;
+  linear:ProfileParameters (id: 12);
+  angular:ProfileParameters (id: 13);
 
   // Parameters for a spline to follow. This just contains info on a spline to
   // compute. Each time this is sent, spline drivetrain will compute a new
   // spline.
-  spline:SplineGoal;
+  spline:SplineGoal (id: 14);
 
   // Which spline to follow.
-  spline_handle:int;
+  spline_handle:int (id: 15);
 }
 
 root_type Goal;
diff --git a/frc971/control_loops/drivetrain/drivetrain_output.fbs b/frc971/control_loops/drivetrain/drivetrain_output.fbs
index da8c889..dba178a 100644
--- a/frc971/control_loops/drivetrain/drivetrain_output.fbs
+++ b/frc971/control_loops/drivetrain/drivetrain_output.fbs
@@ -2,12 +2,12 @@
 
 table Output {
   // Voltage to send to motor(s) on either side of the drivetrain.
-  left_voltage:double;
-  right_voltage:double;
+  left_voltage:double (id: 0);
+  right_voltage:double (id: 1);
 
   // Whether to set each shifter piston to high gear.
-  left_high:bool;
-  right_high:bool;
+  left_high:bool (id: 2);
+  right_high:bool (id: 3);
 }
 
 root_type Output;
diff --git a/frc971/control_loops/drivetrain/drivetrain_position.fbs b/frc971/control_loops/drivetrain/drivetrain_position.fbs
index 900c036..3ada998 100644
--- a/frc971/control_loops/drivetrain/drivetrain_position.fbs
+++ b/frc971/control_loops/drivetrain/drivetrain_position.fbs
@@ -2,24 +2,24 @@
 
 table Position {
   // Relative position of each drivetrain side (in meters).
-  left_encoder:double;
-  right_encoder:double;
+  left_encoder:double (id: 0);
+  right_encoder:double (id: 1);
 
   // The speed in m/s of each drivetrain side from the most recent encoder
   // pulse, or 0 if there was no edge within the last 5ms.
-  left_speed:double;
-  right_speed:double;
+  left_speed:double (id: 2);
+  right_speed:double (id: 3);
 
   // Position of each drivetrain shifter, scaled from 0.0 to 1.0 where smaller
   // is towards low gear.
-  left_shifter_position:double;
-  right_shifter_position:double;
+  left_shifter_position:double (id: 4);
+  right_shifter_position:double (id: 5);
 
   // Raw analog voltages of each shifter hall effect for logging purposes.
-  low_left_hall:double;
-  high_left_hall:double;
-  low_right_hall:double;
-  high_right_hall:double;
+  low_left_hall:double (id: 6);
+  high_left_hall:double (id: 7);
+  low_right_hall:double (id: 8);
+  high_right_hall:double (id: 9);
 }
 
 root_type Position;
diff --git a/frc971/control_loops/drivetrain/drivetrain_status.fbs b/frc971/control_loops/drivetrain/drivetrain_status.fbs
index 3642131..5ce14e6 100644
--- a/frc971/control_loops/drivetrain/drivetrain_status.fbs
+++ b/frc971/control_loops/drivetrain/drivetrain_status.fbs
@@ -5,43 +5,43 @@
 // For logging information about what the code is doing with the shifters.
 table GearLogging {
   // Which controller is being used.
-  controller_index:byte;
+  controller_index:byte (id: 0);
 
   // Whether each loop for the drivetrain sides is the high-gear one.
-  left_loop_high:bool;
-  right_loop_high:bool;
+  left_loop_high:bool (id: 1);
+  right_loop_high:bool (id: 2);
 
   // The states of each drivetrain shifter.
-  left_state:byte;
-  right_state:byte;
+  left_state:byte (id: 3);
+  right_state:byte (id: 4);
 }
 
 // For logging information about the state of the shifters.
 table CIMLogging {
   // Whether the code thinks each drivetrain side is currently in gear.
-  left_in_gear:bool;
-  right_in_gear:bool;
+  left_in_gear:bool (id: 0);
+  right_in_gear:bool (id: 1);
 
   // The angular velocities (in rad/s, positive forward) the code thinks motors
   // on each side of the drivetrain are moving at.
-  left_motor_speed:double;
-  right_motor_speed:double;
+  left_motor_speed:double (id: 2);
+  right_motor_speed:double (id: 3);
 
   // The velocity estimates for each drivetrain side of the robot (in m/s,
   // positive forward) that can be used for shifting.
-  left_velocity:double;
-  right_velocity:double;
+  left_velocity:double (id: 4);
+  right_velocity:double (id: 5);
 }
 
 // Logging information for the polydrivetrain implementation.
 table PolyDriveLogging {
   // Calculated velocity goals for the left/right sides of the drivetrain, in
   // m/s.
-  goal_left_velocity:float;
-  goal_right_velocity:float;
+  goal_left_velocity:float (id: 0);
+  goal_right_velocity:float (id: 1);
   // Feedforward components of the left/right voltages.
-  ff_left_voltage:float;
-  ff_right_voltage:float;
+  ff_left_voltage:float (id: 2);
+  ff_right_voltage:float (id: 3);
 }
 
 enum PlanningState : byte {
@@ -54,84 +54,84 @@
 // For logging information about the state of the trajectory planning.
 table TrajectoryLogging {
   // state of planning the trajectory.
-  planning_state:PlanningState;
+  planning_state:PlanningState (id: 0);
 
   // State of the spline execution.
-  is_executing:bool;
+  is_executing:bool (id: 1);
   // Whether we have finished the spline specified by current_spline_idx.
-  is_executed:bool;
+  is_executed:bool (id: 2);
 
   // The handle of the goal spline.  0 means stop requested.
-  goal_spline_handle:int;
+  goal_spline_handle:int (id: 3);
   // Handle of the executing spline.  -1 means none requested.  If there was no
   // spline executing when a spline finished optimizing, it will become the
   // current spline even if we aren't ready to start yet.
-  current_spline_idx:int;
+  current_spline_idx:int (id: 4);
   // Handle of the spline that is being optimized and staged.
-  planning_spline_idx:int;
+  planning_spline_idx:int (id: 5);
 
   // Expected position and velocity on the spline
-  x:float;
-  y:float;
-  theta:float;
-  left_velocity:float;
-  right_velocity:float;
-  distance_remaining:float;
+  x:float (id: 6);
+  y:float (id: 7);
+  theta:float (id: 8);
+  left_velocity:float (id: 9);
+  right_velocity:float (id: 10);
+  distance_remaining:float (id: 11);
 }
 
 // For logging state of the line follower.
 table LineFollowLogging {
   // Whether we are currently freezing target choice.
-  frozen:bool;
+  frozen:bool (id: 0);
   // Whether we currently have a target.
-  have_target:bool;
+  have_target:bool (id: 1);
   // Absolute position of the current goal.
-  x:float;
-  y:float;
-  theta:float;
+  x:float (id: 2);
+  y:float (id: 3);
+  theta:float (id: 4);
   // Current lateral offset from line pointing straight out of the target.
-  offset:float;
+  offset:float (id: 5);
   // Current distance from the plane of the target, in meters.
-  distance_to_target:float;
+  distance_to_target:float (id: 6);
   // Current goal heading.
-  goal_theta:float;
+  goal_theta:float (id: 7);
   // Current relative heading.
-  rel_theta:float;
+  rel_theta:float (id: 8);
 }
 
 // Current states of the EKF. See hybrid_ekf.h for detailed comments.
 table LocalizerState {
   // X/Y field position, in meters.
-  x:float;
-  y:float;
+  x:float (id: 0);
+  y:float (id: 1);
   // Current heading, in radians.
-  theta:float;
+  theta:float (id: 2);
   // Current estimate of the left encoder position, in meters.
-  left_encoder:float;
+  left_encoder:float (id: 3);
   // Velocity of the left side of the robot.
-  left_velocity:float;
+  left_velocity:float (id: 4);
   // Current estimate of the right encoder position, in meters.
-  right_encoder:float;
+  right_encoder:float (id: 5);
   // Velocity of the right side of the robot.
-  right_velocity:float;
+  right_velocity:float (id: 6);
   // Current "voltage error" terms, in V.
-  left_voltage_error:float;
-  right_voltage_error:float;
+  left_voltage_error:float (id: 7);
+  right_voltage_error:float (id: 8);
   // Estimate of the offset between the encoder readings and true rotation of
   // the robot, in rad/sec.
-  angular_error:float;
+  angular_error:float (id: 9);
   // Current difference between the estimated longitudinal velocity of the robot
   // and that experienced by the wheels, in m/s.
-  longitudinal_velocity_offset:float;
+  longitudinal_velocity_offset:float (id: 10);
   // Lateral velocity of the robot, in m/s.
-  lateral_velocity:float;
+  lateral_velocity:float (id: 11);
 }
 
 table DownEstimatorState {
-  quaternion_x:double;
-  quaternion_y:double;
-  quaternion_z:double;
-  quaternion_w:double;
+  quaternion_x:double (id: 0);
+  quaternion_y:double (id: 1);
+  quaternion_z:double (id: 2);
+  quaternion_w:double (id: 3);
 
   // Side-to-side and forwards/backwards pitch numbers. Note that we do this
   // instead of standard roll/pitch/yaw euler angles because it was a pain to
@@ -141,116 +141,116 @@
   // the forwards to backwards pitch of the robot; longitudinal_pitch
   // corresponds with the traditional usage of "pitch".
   // All angles in radians.
-  lateral_pitch:float;
-  longitudinal_pitch:float;
+  lateral_pitch:float (id: 4);
+  longitudinal_pitch:float (id: 5);
   // Current yaw angle (heading) of the robot, as estimated solely by
   // integrating the Z-axis of the gyro (in rad).
-  yaw:float;
+  yaw:float (id: 6);
 
   // Current position of the robot, as determined solely from the
   // IMU/down-estimator, in meters.
-  position_x:float;
-  position_y:float;
-  position_z:float;
+  position_x:float (id: 7);
+  position_y:float (id: 8);
+  position_z:float (id: 9);
 
   // Current velocity of the robot, as determined solely from the
   // IMU/down-estimator, in meters / sec.
-  velocity_x:float;
-  velocity_y:float;
-  velocity_z:float;
+  velocity_x:float (id: 10);
+  velocity_y:float (id: 11);
+  velocity_z:float (id: 12);
 
   // Current acceleration of the robot, with pitch/roll (but not yaw)
   // compensated out, in meters / sec / sec.
-  accel_x:float;
-  accel_y:float;
-  accel_z:float;
+  accel_x:float (id: 13);
+  accel_y:float (id: 14);
+  accel_z:float (id: 15);
 
   // Current acceleration that we expect to see from the accelerometer, assuming
   // no acceleration other than that due to gravity, in g's.
-  expected_accel_x:float;
-  expected_accel_y:float;
-  expected_accel_z:float;
+  expected_accel_x:float (id: 16);
+  expected_accel_y:float (id: 17);
+  expected_accel_z:float (id: 18);
 
   // Current estimate of the overall acceleration due to gravity, in g's. Should
   // generally be within ~0.003 g's of 1.0.
-  gravity_magnitude:float;
+  gravity_magnitude:float (id: 19);
 
-  consecutive_still:int;
+  consecutive_still:int (id: 20);
 }
 
 table ImuZeroerState {
   // True if we have successfully zeroed the IMU.
-  zeroed:bool;
+  zeroed:bool (id: 0);
   // True if the zeroing code has observed some inconsistency in the IMU.
-  faulted:bool;
+  faulted:bool (id: 1);
   // Number of continuous zeroing measurements that we have accumulated for use
   // in the zeroing.
-  number_of_zeroes:int;
+  number_of_zeroes:int (id: 2);
 
   // Current zeroing values beind used for each gyro axis, in rad / sec.
-  gyro_x_average:float;
-  gyro_y_average:float;
-  gyro_z_average:float;
+  gyro_x_average:float (id: 3);
+  gyro_y_average:float (id: 4);
+  gyro_z_average:float (id: 5);
 }
 
 table Status {
   // Estimated speed of the center of the robot in m/s (positive forwards).
-  robot_speed:double;
+  robot_speed:double (id: 0);
 
   // Estimated relative position of each drivetrain side (in meters).
-  estimated_left_position:double;
-  estimated_right_position:double;
+  estimated_left_position:double (id: 1);
+  estimated_right_position:double (id: 2);
 
   // Estimated velocity of each drivetrain side (in m/s).
-  estimated_left_velocity:double;
-  estimated_right_velocity:double;
+  estimated_left_velocity:double (id: 3);
+  estimated_right_velocity:double (id: 4);
 
   // The voltage we wanted to send to each drivetrain side last cycle.
-  uncapped_left_voltage:double;
-  uncapped_right_voltage:double;
+  uncapped_left_voltage:double (id: 5);
+  uncapped_right_voltage:double (id: 6);
 
   // The voltage error for the left and right sides.
-  left_voltage_error:double;
-  right_voltage_error:double;
+  left_voltage_error:double (id: 7);
+  right_voltage_error:double (id: 8);
 
   // The profiled goal states.
-  profiled_left_position_goal:double;
-  profiled_right_position_goal:double;
-  profiled_left_velocity_goal:double;
-  profiled_right_velocity_goal:double;
+  profiled_left_position_goal:double (id: 9);
+  profiled_right_position_goal:double (id: 10);
+  profiled_left_velocity_goal:double (id: 11);
+  profiled_right_velocity_goal:double (id: 12);
 
   // The KF offset
-  estimated_angular_velocity_error:double;
+  estimated_angular_velocity_error:double (id: 13);
   // The KF estimated heading.
-  estimated_heading:double;
+  estimated_heading:double (id: 14);
 
   // xytheta of the robot.
-  x:double;
-  y:double;
-  theta:double;
+  x:double (id: 15);
+  y:double (id: 16);
+  theta:double (id: 17);
 
   // True if the output voltage was capped last cycle.
-  output_was_capped:bool;
+  output_was_capped:bool (id: 18);
 
   // The pitch of the robot relative to the ground--only includes
   // forwards/backwards rotation.
-  ground_angle:double;
+  ground_angle:double (id: 19);
 
   // Information about shifting logic and curent gear, for logging purposes
-  gear_logging:GearLogging;
-  cim_logging:CIMLogging;
+  gear_logging:GearLogging (id: 20);
+  cim_logging:CIMLogging (id: 21);
 
-  trajectory_logging:TrajectoryLogging;
+  trajectory_logging:TrajectoryLogging (id: 22);
 
-  line_follow_logging:LineFollowLogging;
+  line_follow_logging:LineFollowLogging (id: 23);
 
-  poly_drive_logging:PolyDriveLogging;
+  poly_drive_logging:PolyDriveLogging (id: 24);
 
-  down_estimator:DownEstimatorState;
+  down_estimator:DownEstimatorState (id: 25);
 
-  localizer:LocalizerState;
+  localizer:LocalizerState (id: 26);
 
-  zeroing:ImuZeroerState;
+  zeroing:ImuZeroerState (id: 27);
 }
 
 root_type Status;
diff --git a/frc971/control_loops/drivetrain/localizer.fbs b/frc971/control_loops/drivetrain/localizer.fbs
index 5450c08..31493e6 100644
--- a/frc971/control_loops/drivetrain/localizer.fbs
+++ b/frc971/control_loops/drivetrain/localizer.fbs
@@ -3,11 +3,11 @@
 // Allows you to reset the state of the localizer to a specific position on the
 // field.
 table LocalizerControl {
-  x:float;      // X position, meters
-  y:float;      // Y position, meters
-  theta:float;  // heading, radians
-  theta_uncertainty:double; // Uncertainty in theta.
-  keep_current_theta:bool; // Whether to keep the current theta value.
+  x:float (id: 0);      // X position, meters
+  y:float (id: 1);      // Y position, meters
+  theta:float (id: 2);  // heading, radians
+  theta_uncertainty:double (id: 3); // Uncertainty in theta.
+  keep_current_theta:bool (id: 4); // Whether to keep the current theta value.
 }
 
 root_type LocalizerControl;
diff --git a/frc971/control_loops/profiled_subsystem.fbs b/frc971/control_loops/profiled_subsystem.fbs
index 185133b..9ecb98c 100644
--- a/frc971/control_loops/profiled_subsystem.fbs
+++ b/frc971/control_loops/profiled_subsystem.fbs
@@ -4,244 +4,244 @@
 
 table ProfiledJointStatus {
   // Is the subsystem zeroed?
-  zeroed:bool;
+  zeroed:bool (id: 0);
 
   // The state of the subsystem, if applicable.  -1 otherwise.
   // TODO(alex): replace with enum.
-  state:int;
+  state:int (id: 1);
 
   // If true, we have aborted.
-  estopped:bool;
+  estopped:bool (id: 2);
 
   // Position of the joint.
-  position:float;
+  position:float (id: 3);
   // Velocity of the joint in units/second.
-  velocity:float;
+  velocity:float (id: 4);
   // Profiled goal position of the joint.
-  goal_position:float;
+  goal_position:float (id: 5);
   // Profiled goal velocity of the joint in units/second.
-  goal_velocity:float;
+  goal_velocity:float (id: 6);
   // Unprofiled goal position from absoulte zero  of the joint.
-  unprofiled_goal_position:float;
+  unprofiled_goal_position:float (id: 7);
   // Unprofiled goal velocity of the joint in units/second.
-  unprofiled_goal_velocity:float;
+  unprofiled_goal_velocity:float (id: 8);
 
   // The estimated voltage error.
-  voltage_error:float;
+  voltage_error:float (id: 9);
 
   // The calculated velocity with delta x/delta t
-  calculated_velocity:float;
+  calculated_velocity:float (id: 10);
 
   // Components of the control loop output
-  position_power:float;
-  velocity_power:float;
-  feedforwards_power:float;
+  position_power:float (id: 11);
+  velocity_power:float (id: 12);
+  feedforwards_power:float (id: 13);
 
   // State of the estimator.
-  estimator_state:frc971.EstimatorState;
+  estimator_state:frc971.EstimatorState (id: 14);
 }
 
 table HallProfiledJointStatus {
   // Is the subsystem zeroed?
-  zeroed:bool;
+  zeroed:bool (id: 0);
 
   // The state of the subsystem, if applicable.  -1 otherwise.
   // TODO(alex): replace with enum.
-  state:int;
+  state:int (id: 1);
 
   // If true, we have aborted.
-  estopped:bool;
+  estopped:bool (id: 2);
 
   // Position of the joint.
-  position:float;
+  position:float (id: 3);
   // Velocity of the joint in units/second.
-  velocity:float;
+  velocity:float (id: 4);
   // Profiled goal position of the joint.
-  goal_position:float;
+  goal_position:float (id: 5);
   // Profiled goal velocity of the joint in units/second.
-  goal_velocity:float;
+  goal_velocity:float (id: 6);
   // Unprofiled goal position from absoulte zero  of the joint.
-  unprofiled_goal_position:float;
+  unprofiled_goal_position:float (id: 7);
   // Unprofiled goal velocity of the joint in units/second.
-  unprofiled_goal_velocity:float;
+  unprofiled_goal_velocity:float (id: 8);
 
   // The estimated voltage error.
-  voltage_error:float;
+  voltage_error:float (id: 9);
 
   // The calculated velocity with delta x/delta t
-  calculated_velocity:float;
+  calculated_velocity:float (id: 10);
 
   // Components of the control loop output
-  position_power:float;
-  velocity_power:float;
-  feedforwards_power:float;
+  position_power:float (id: 11);
+  velocity_power:float (id: 12);
+  feedforwards_power:float (id: 13);
 
   // State of the estimator.
-  estimator_state:frc971.HallEffectAndPositionEstimatorState;
+  estimator_state:frc971.HallEffectAndPositionEstimatorState (id: 14);
 }
 
 table PotAndAbsoluteEncoderProfiledJointStatus {
   // Is the subsystem zeroed?
-  zeroed:bool;
+  zeroed:bool (id: 0);
 
   // The state of the subsystem, if applicable.  -1 otherwise.
   // TODO(alex): replace with enum.
-  state:int;
+  state:int (id: 1);
 
   // If true, we have aborted.
-  estopped:bool;
+  estopped:bool (id: 2);
 
   // Position of the joint.
-  position:float;
+  position:float (id: 3);
   // Velocity of the joint in units/second.
-  velocity:float;
+  velocity:float (id: 4);
   // Profiled goal position of the joint.
-  goal_position:float;
+  goal_position:float (id: 5);
   // Profiled goal velocity of the joint in units/second.
-  goal_velocity:float;
+  goal_velocity:float (id: 6);
   // Unprofiled goal position from absoulte zero  of the joint.
-  unprofiled_goal_position:float;
+  unprofiled_goal_position:float (id: 7);
   // Unprofiled goal velocity of the joint in units/second.
-  unprofiled_goal_velocity:float;
+  unprofiled_goal_velocity:float (id: 8);
 
   // The estimated voltage error.
-  voltage_error:float;
+  voltage_error:float (id: 9);
 
   // The calculated velocity with delta x/delta t
-  calculated_velocity:float;
+  calculated_velocity:float (id: 10);
 
   // Components of the control loop output
-  position_power:float;
-  velocity_power:float;
-  feedforwards_power:float;
+  position_power:float (id: 11);
+  velocity_power:float (id: 12);
+  feedforwards_power:float (id: 13);
 
   // State of the estimator.
-  estimator_state:frc971.PotAndAbsoluteEncoderEstimatorState;
+  estimator_state:frc971.PotAndAbsoluteEncoderEstimatorState (id: 14);
 }
 
 table IndexProfiledJointStatus {
   // Is the subsystem zeroed?
-  zeroed:bool;
+  zeroed:bool (id: 0);
 
   // The state of the subsystem, if applicable.  -1 otherwise.
   // TODO(alex): replace with enum.
-  state:int;
+  state:int (id: 1);
 
   // If true, we have aborted.
-  estopped:bool;
+  estopped:bool (id: 2);
 
   // Position of the joint.
-  position:float;
+  position:float (id: 3);
   // Velocity of the joint in units/second.
-  velocity:float;
+  velocity:float (id: 4);
   // Profiled goal position of the joint.
-  goal_position:float;
+  goal_position:float (id: 5);
   // Profiled goal velocity of the joint in units/second.
-  goal_velocity:float;
+  goal_velocity:float (id: 6);
   // Unprofiled goal position from absoulte zero  of the joint.
-  unprofiled_goal_position:float;
+  unprofiled_goal_position:float (id: 7);
   // Unprofiled goal velocity of the joint in units/second.
-  unprofiled_goal_velocity:float;
+  unprofiled_goal_velocity:float (id: 8);
 
   // The estimated voltage error.
-  voltage_error:float;
+  voltage_error:float (id: 9);
 
   // The calculated velocity with delta x/delta t
-  calculated_velocity:float;
+  calculated_velocity:float (id: 10);
 
   // Components of the control loop output
-  position_power:float;
-  velocity_power:float;
-  feedforwards_power:float;
+  position_power:float (id: 11);
+  velocity_power:float (id: 12);
+  feedforwards_power:float (id: 13);
 
   // State of the estimator.
-  estimator_state:frc971.IndexEstimatorState;
+  estimator_state:frc971.IndexEstimatorState (id: 14);
 }
 
 table AbsoluteEncoderProfiledJointStatus {
   // Is the subsystem zeroed?
-  zeroed:bool;
+  zeroed:bool (id: 0);
 
   // The state of the subsystem, if applicable.  -1 otherwise.
   // TODO(alex): replace with enum.
-  state:int;
+  state:int (id: 1);
 
   // If true, we have aborted.
-  estopped:bool;
+  estopped:bool (id: 2);
 
   // Position of the joint.
-  position:float;
+  position:float (id: 3);
   // Velocity of the joint in units/second.
-  velocity:float;
+  velocity:float (id: 4);
   // Profiled goal position of the joint.
-  goal_position:float;
+  goal_position:float (id: 5);
   // Profiled goal velocity of the joint in units/second.
-  goal_velocity:float;
+  goal_velocity:float (id: 6);
   // Unprofiled goal position from absoulte zero  of the joint.
-  unprofiled_goal_position:float;
+  unprofiled_goal_position:float (id: 7);
   // Unprofiled goal velocity of the joint in units/second.
-  unprofiled_goal_velocity:float;
+  unprofiled_goal_velocity:float (id: 8);
 
   // The estimated voltage error.
-  voltage_error:float;
+  voltage_error:float (id: 9);
 
   // The calculated velocity with delta x/delta t
-  calculated_velocity:float;
+  calculated_velocity:float (id: 10);
 
   // Components of the control loop output
-  position_power:float;
-  velocity_power:float;
-  feedforwards_power:float;
+  position_power:float (id: 11);
+  velocity_power:float (id: 12);
+  feedforwards_power:float (id: 13);
 
   // State of the estimator.
-  estimator_state:frc971.AbsoluteEncoderEstimatorState;
+  estimator_state:frc971.AbsoluteEncoderEstimatorState (id: 14);
 }
 
 table RelativeEncoderProfiledJointStatus {
   // The state of the subsystem, if applicable.  -1 otherwise.
   // TODO(alex): replace with enum.
-  state:int;
+  state:int (id: 0);
 
   // If true, we have aborted.
-  estopped:bool;
+  estopped:bool (id: 1);
 
   // Position of the joint.
-  position:float;
+  position:float (id: 2);
   // Velocity of the joint in units/second.
-  velocity:float;
+  velocity:float (id: 3);
   // Profiled goal position of the joint.
-  goal_position:float;
+  goal_position:float (id: 4);
   // Profiled goal velocity of the joint in units/second.
-  goal_velocity:float;
+  goal_velocity:float (id: 5);
   // Unprofiled goal position from absoulte zero  of the joint.
-  unprofiled_goal_position:float;
+  unprofiled_goal_position:float (id: 6);
   // Unprofiled goal velocity of the joint in units/second.
-  unprofiled_goal_velocity:float;
+  unprofiled_goal_velocity:float (id: 7);
 
   // The estimated voltage error.
-  voltage_error:float;
+  voltage_error:float (id: 8);
 
   // The calculated velocity with delta x/delta t
-  calculated_velocity:float;
+  calculated_velocity:float (id: 9);
 
   // Components of the control loop output
-  position_power:float;
-  velocity_power:float;
-  feedforwards_power:float;
+  position_power:float (id: 10);
+  velocity_power:float (id: 11);
+  feedforwards_power:float (id: 12);
 
   // State of the estimator.
-  estimator_state:frc971.RelativeEncoderEstimatorState;
+  estimator_state:frc971.RelativeEncoderEstimatorState (id: 13);
 }
 
 table StaticZeroingSingleDOFProfiledSubsystemGoal {
-  unsafe_goal:double;
+  unsafe_goal:double (id: 0);
 
-  profile_params:frc971.ProfileParameters;
+  profile_params:frc971.ProfileParameters (id: 1);
 
   // Sets the goal velocity of the subsystem.
-  goal_velocity:double;
+  goal_velocity:double (id: 2);
 
   // If set to true, then we will ignore the profiling on this joint and pass
   // the goal + goal velocity directly to the control loop.
-  ignore_profile:bool;
+  ignore_profile:bool (id: 3);
 }
diff --git a/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.fbs b/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.fbs
index da6e7ae..f824b3e 100644
--- a/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.fbs
+++ b/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.fbs
@@ -4,12 +4,12 @@
 namespace frc971.control_loops.zeroing.testing;
 
 table SubsystemGoal {
-  unsafe_goal:double;
-  profile_params:frc971.ProfileParameters;
-  goal_velocity:double;
-  ignore_profile:bool;
+  unsafe_goal:double (id: 0);
+  profile_params:frc971.ProfileParameters (id: 1);
+  goal_velocity:double (id: 2);
+  ignore_profile:bool (id: 3);
 }
 
 table SubsystemOutput {
-  output:double;
+  output:double (id: 0);
 }