LightLib
PROS library for VEX V5: EKF/MCL localization, RAMSETE path following, high-level chassis API
Loading...
Searching...
No Matches
light Namespace Reference

Initialize once via init(); poll getPose/setPose from any task. More...

Namespaces

namespace  ekf
 
namespace  field
 
namespace  lightcast
 
namespace  paths
 
namespace  sensor_aux
 
namespace  units
 Single source of truth for unit conversions.
 
namespace  util
 Misc math, geometry, and unit-conversion helpers.
 

Classes

struct  Auton
 One registered autonomous routine. More...
 
class  AutonSelector
 On-brain auton picker UI. More...
 
class  Drive
 Tank-drive chassis class. More...
 
struct  DriveFF
 Per-wheel feedforward + simple velocity-loop gains. More...
 
class  HDrive
 Tank drive with a single center-mounted strafe wheel (H-drive layout). More...
 
struct  HermiteSegment
 One segment of a quintic Hermite spline. More...
 
class  HoloDrive
 4-motor holonomic drive — supports X-Drive and Mecanum configurations. More...
 
struct  HoloPID
 Internal PID used by HoloDrive / HDrive. More...
 
struct  odom
 One waypoint of an odom-mode movement. More...
 
struct  PathEvent
 Mid-path action fired once when the trajectory passes its resolved time. More...
 
class  PID
 Discrete PID controller with rich exit-condition support. More...
 
struct  PidConstants
 Container for one PID's four editable gain values. More...
 
class  PidTuner
 Live PID tuner UI driven by LVGL. More...
 
class  Piston
 Stateful 3-wire pneumatic piston with toggle helpers. More...
 
struct  pose
 2D pose: position (in) and heading (deg). More...
 
struct  PurePursuitConfig
 Pure Pursuit controller config — only knob is the carrot lookahead. More...
 
struct  RamseteConfig
 RAMSETE controller and chassis-geometry config. More...
 
class  RotationalSnap
 Manual-then-snap controller for a motor + rotation-sensor pair. More...
 
class  slew
 Slew-rate limiter that ramps speed up linearly over a configurable distance. More...
 
class  Spline
 Concatenated quintic Hermite spline with arc-length parameterization. More...
 
struct  SplineSample
 Pose / velocity / acceleration sample produced by spline evaluation. More...
 
class  tracking_wheel
 Single tracking wheel for odometry. More...
 
struct  TrajConstraints
 Kinematic limits used by the trajectory generator. More...
 
class  Trajectory
 Time-parameterized trajectory: dense state table + total duration. More...
 
struct  TrajState
 One sample of a time-parameterized trajectory. More...
 
struct  united_odom
 One waypoint of an odom-mode movement, with okapi units. More...
 
struct  united_pose
 2D pose with okapi units. More...
 
struct  Waypoint
 Single 2-D waypoint with optional heading and per-point speed cap. More...
 

Typedefs

using PoseGetterFn = pose(*)()
 External pose getter used by register_pose_source().
 
using PoseSetterFn = void(*)(pose)
 External pose setter used by register_pose_source().
 

Enumerations

enum  PidType {
  PID_DRIVE = 0 , PID_TURN , PID_SWING , PID_HEADING ,
  PID_EKF , PID_COUNT
}
 PID controller categories selectable in the tuner. More...
 
enum  ConstSlot {
  KP = 0 , KI , KD , START_I ,
  CONST_COUNT
}
 Index into a PidConstants slot. More...
 
enum class  Follower { RAMSETE , PURE_PURSUIT }
 Path-following controller selector. More...
 

Functions

void register_pose_source (PoseGetterFn getter, PoseSetterFn setter)
 Register an external pose source.
 
double wrap180 (double a)
 Normalize an angle in degrees to the half-open interval (-180, 180] so PID always takes the shortest path.
 
void reset ()
 Reset all internal pose state to (0, 0, 0).
 
void init (OdomSensors sensors, MCLConfig cfg={})
 Initialize the estimator.
 
void stop ()
 Stop the background odometry task.
 
void moveToPoint (float targetX, float targetY, int timeout, float maxSpeed, bool reversed)
 Drive to a field-relative point (legacy).
 
Pose getPose (bool radians=false)
 
void setPose (Pose pose, bool radians=false)
 Overwrite the current pose.
 
Pose getSpeed (bool radians=false)
 
Pose getLocalSpeed (bool radians=false)
 
Pose estimatePose (float time, bool radians=false)
 Linear extrapolation of pose time seconds ahead at current velocity.
 
void update ()
 Force one update (normally called by the background task).
 
Pose getPoseRad ()
 Radian-only accessor; trajectory code MUST use this to avoid deg/rad bugs.
 
bool runPath (const char *name, bool reversed=false, int timeoutMs=-1, float poseErrBailIn=8.0f, Follower follower=Follower::PURE_PURSUIT)
 Run a registered path by name.
 
bool runPath (const char *name, std::vector< PathEvent > events, bool reversed=false, int timeoutMs=-1, float poseErrBailIn=8.0f, Follower follower=Follower::PURE_PURSUIT)
 Variant accepting mid-path event triggers.
 
void pure_pursuit_configure (PurePursuitConfig cfg)
 Configure the Pure Pursuit follower.
 
void ramsete_configure (RamseteConfig rc, DriveFF ff, TrajConstraints defaultCons)
 Configure the RAMSETE follower.
 
bool followTrajectory (const Trajectory &traj, int timeoutMs=-1, float poseErrBailIn=8.0f, Follower follower=Follower::PURE_PURSUIT)
 Follow a pre-generated Trajectory.
 
bool followTrajectory (const std::vector< Waypoint > &wps, const TrajConstraints &cons, bool reversed=false, int timeoutMs=-1, float poseErrBailIn=8.0f, Follower follower=Follower::PURE_PURSUIT)
 Generate and follow a trajectory from waypoints.
 
bool followTrajectory (const std::vector< Waypoint > &wps, const TrajConstraints &cons, std::vector< PathEvent > events, bool reversed=false, int timeoutMs=-1, float poseErrBailIn=8.0f, Follower follower=Follower::PURE_PURSUIT)
 Generate-and-follow variant with mid-path event triggers.
 
bool followTrajectory (const std::vector< Waypoint > &wps, bool reversed=false, int timeoutMs=-1, float poseErrBailIn=8.0f, Follower follower=Follower::PURE_PURSUIT)
 Generate and follow a trajectory from waypoints, using the default TrajConstraints registered via ramsete_configure().
 
bool followTrajectory (const std::vector< Waypoint > &wps, std::vector< PathEvent > events, bool reversed=false, int timeoutMs=-1, float poseErrBailIn=8.0f, Follower follower=Follower::PURE_PURSUIT)
 Same as above, with mid-path events.
 
bool runJerryioPath (const char *csv, bool reversed=false, int timeoutMs=-1, float poseErrBailIn=8.0f, Follower follower=Follower::PURE_PURSUIT)
 Run a waypoint CSV (path.jerryio.com export or hand-written).
 
bool runJerryioPath (const char *csv, std::vector< PathEvent > events, bool reversed=false, int timeoutMs=-1, float poseErrBailIn=8.0f, Follower follower=Follower::PURE_PURSUIT)
 Variant with mid-path event triggers.
 
bool runJerryioPathFromSD (const char *filePath, bool reversed=false, int timeoutMs=-1, float poseErrBailIn=8.0f, Follower follower=Follower::PURE_PURSUIT)
 Read the CSV from the V5 SD card (e.g.
 
bool runJerryioPathFromSD (const char *filePath, std::vector< PathEvent > events, bool reversed=false, int timeoutMs=-1, float poseErrBailIn=8.0f, Follower follower=Follower::PURE_PURSUIT)
 SD-card variant with mid-path event triggers.
 
Trajectory generateTrajectory (const std::vector< Waypoint > &wps, const TrajConstraints &cons, bool reversed=false)
 Generate a time-parameterized trajectory from waypoints.
 
uint32_t auton_elapsed ()
 
void wait_until_auton (uint32_t ms)
 Block until ms milliseconds have elapsed since auton started.
 
void extras_init (light::Drive *chassis, pros::MotorGroup *leftMotors, pros::MotorGroup *rightMotors)
 Register the user's drivetrain objects with LightLib.
 
void getDriveMotorGroups (pros::MotorGroup **leftOut, pros::MotorGroup **rightOut)
 Look up the registered drivetrain motor groups.
 
light::DrivegetChassis ()
 
void ez_template_print ()
 Prints our branding all over your pros terminal.
 
void screen_print (std::string text, int line=0)
 Prints to the brain screen in one string.
 
std::string exit_to_string (exit_output input)
 Returns a human-readable name for an exit_output code.
 
Stationary noise calibration
void autotune_ekf_noise (int sampleMs=10, int durationMs=5000, int warmupMs=500)
 Stationary EKF process-noise calibration.
 
void autotune_mcl_noise (int sampleMs=20, int durationMs=4000, int warmupMs=300)
 Stationary MCL distance-sensor noise calibration.
 
Bracket-and-bisect PID auto-tune (drive / turn / swing / heading)

Three-phase tuner with kI=0.

Phase 1 doubles kP until the robot oscillates (≥3 zero-crossings of pos − target), then bisects between the last stable and oscillating values. Phase 2 boosts that kP, doubles kD until the oscillation damps, then bisects to find the smallest sufficient kD. Phase 3 then pushes kP higher in +15% steps — bumping kD when oscillation returns — until settle time stops improving (best-of-2 confirmed), and writes the fastest-settling stable (kP, kD) pair. Final values are applied live via pid_*_constants_set; transcribe the printed FINAL line into default_constants() to persist across reboots. Heading scores on the |L−R| motor voltage differential (the heading PID's own controller effort) instead of IMU error, so its oscillation read isn't masked by drive PID dynamics. Space: turn/swing ~3 ft²; drive ≥6 ft straight; heading ≥10 ft straight.

void autotune_turn_pid (float turnAngleDeg=180.0f, float overshootThreshDeg=3.0f, int maxIters=20)
 
void autotune_drive_pid (float driveDistIn=24.0f, float overshootThreshIn=0.5f, int maxIters=20)
 
void autotune_swing_pid (float swingAngleDeg=90.0f, float overshootThreshDeg=3.0f, int maxIters=20)
 
void autotune_heading_pid (float driveDistIn=48.0f, float peakDiffMv=3000.0f, int maxIters=20)
 
Characterization routines

Each is meant to be run as its own selectable auton.

void characterize_kV_kA_kS (float maxVoltage=10.0f, float rampVps=0.25f)
 Identify kV / kA / kS by ramping voltage and recording velocity.
 
float characterize_track_width (int rotations=10)
 Identify the effective track width by spinning in place.
 
float characterize_a_lat_max ()
 Identify the maximum sustainable lateral acceleration.
 
void characterize_friction (float maxVoltage=10.0f, float stepV=0.5f)
 Friction-FF auto-ID for non-trajectory PIDs.
 

Variables

PidTuner pid_tuner
 Process-wide singleton tuner instance.
 
int DRIVE_SPEED
 Default speeds used when a pid_drive_set / pid_turn_set / pid_swing_set call omits the speed argument.
 
int TURN_SPEED
 
int SWING_SPEED
 
AutonSelector auton_selector
 Process-wide singleton selector instance.
 
uint32_t auton_start_ms
 Millisecond timestamp captured right before the selected auton routine runs.
 

Public types and enums

enum  e_type { SINGLE = 0 , SPLIT = 1 }
 Arcade joystick layout. More...
 
enum  e_swing { LEFT_SWING = 0 , RIGHT_SWING = 1 }
 Direction for swing-turn motions. More...
 
enum  exit_output {
  RUNNING = 1 , SMALL_EXIT = 2 , BIG_EXIT = 3 , VELOCITY_EXIT = 4 ,
  mA_EXIT = 5 , ERROR_NO_CONSTANTS = 6
}
 Result codes returned by PID::exit_condition. More...
 
enum  e_mode {
  DISABLE = 0 , SWING = 1 , TURN = 2 , TURN_TO_POINT = 3 ,
  DRIVE = 4 , POINT_TO_POINT = 5 , PURE_PURSUIT = 6
}
 Active chassis motion mode. More...
 
enum  drive_directions {
  FWD = 0 , FORWARD = FWD , fwd = FWD , forward = FWD ,
  REV = 1 , REVERSE = REV , rev = REV , reverse = REV
}
 Drive direction with multiple spelling aliases. More...
 
enum  e_angle_behavior {
  raw = 0 , left_turn = 1 , LEFT_TURN = 1 , counterclockwise = 1 ,
  ccw = 1 , right_turn = 2 , RIGHT_TURN = 2 , clockwise = 2 ,
  cw = 2 , shortest = 3 , longest = 4
}
 How to choose a turn direction when reaching an absolute heading. More...
 
typedef struct light::pose pose
 2D pose: position (in) and heading (deg).
 
typedef struct light::united_pose united_pose
 2D pose with okapi units.
 
typedef struct light::odom odom
 One waypoint of an odom-mode movement.
 
typedef struct light::united_odom united_odom
 One waypoint of an odom-mode movement, with okapi units.
 
const double ANGLE_NOT_SET = 0.0000000000000000000001
 Sentinel value indicating "no angle specified".
 
const okapi::QAngle p_ANGLE_NOT_SET = 0.0000000000000000000001_deg
 Sentinel value indicating "no angle specified" (united).
 

Detailed Description

Initialize once via init(); poll getPose/setPose from any task.

10 ms tick.

Typedef Documentation

◆ odom

typedef struct light::odom light::odom

One waypoint of an odom-mode movement.

◆ pose

typedef struct light::pose light::pose

2D pose: position (in) and heading (deg).

◆ PoseGetterFn

using light::PoseGetterFn = typedef pose (*)()

External pose getter used by register_pose_source().

Definition at line 37 of file drive.hpp.

◆ PoseSetterFn

using light::PoseSetterFn = typedef void (*)(pose)

External pose setter used by register_pose_source().

Definition at line 39 of file drive.hpp.

◆ united_odom

One waypoint of an odom-mode movement, with okapi units.

◆ united_pose

2D pose with okapi units.

Enumeration Type Documentation

◆ ConstSlot

Index into a PidConstants slot.

Enumerator
KP 

Proportional gain.

KI 

Integral gain.

KD 

Derivative gain.

START_I 

Integral activation threshold.

CONST_COUNT 

Definition at line 26 of file pid_tuner.hpp.

◆ drive_directions

Drive direction with multiple spelling aliases.

Enumerator
FWD 
FORWARD 
fwd 
forward 
REV 
REVERSE 
rev 
reverse 

Definition at line 88 of file util.hpp.

◆ e_angle_behavior

How to choose a turn direction when reaching an absolute heading.

Enumerator
raw 

Use signed delta as-is (no wrap).

left_turn 

Always turn counterclockwise.

LEFT_TURN 
counterclockwise 
ccw 
right_turn 

Always turn clockwise.

RIGHT_TURN 
clockwise 
cw 
shortest 

Pick the smaller of CW/CCW.

longest 

Definition at line 98 of file util.hpp.

◆ e_mode

Active chassis motion mode.

Enumerator
DISABLE 

No motion active.

SWING 

Swing turn.

TURN 

Turn-in-place to absolute heading.

TURN_TO_POINT 

Turn to face a field point.

DRIVE 

Straight-line drive.

POINT_TO_POINT 

Drive to a field point.

PURE_PURSUIT 

Definition at line 79 of file util.hpp.

◆ e_swing

Direction for swing-turn motions.

Enumerator
LEFT_SWING 

Left side stationary, right side drives.

RIGHT_SWING 

Definition at line 67 of file util.hpp.

◆ e_type

Arcade joystick layout.

Enumerator
SINGLE 

Single-stick arcade (one stick = throttle + turn).

SPLIT 

Definition at line 63 of file util.hpp.

◆ exit_output

Result codes returned by PID::exit_condition.

Enumerator
RUNNING 

Still inside the motion.

SMALL_EXIT 

Small-error timer expired.

BIG_EXIT 

Big-error timer expired.

VELOCITY_EXIT 

Stopped moving long enough.

mA_EXIT 

Motor current limit hit.

ERROR_NO_CONSTANTS 

Definition at line 71 of file util.hpp.

◆ Follower

enum class light::Follower
strong

Path-following controller selector.

Public entry points default to PURE_PURSUIT.

Enumerator
RAMSETE 
PURE_PURSUIT 

Definition at line 18 of file ramsete.hpp.

◆ PidType

PID controller categories selectable in the tuner.

Enumerator
PID_DRIVE 

Linear drive PID.

PID_TURN 

Heading/turn-in-place PID.

PID_SWING 

Single-side swing PID.

PID_HEADING 

Heading correction during drive moves.

PID_EKF 

EKF heading-fusion PID.

PID_COUNT 

Definition at line 18 of file pid_tuner.hpp.

Function Documentation

◆ auton_elapsed()

uint32_t light::auton_elapsed ( )
Returns
Milliseconds since the selected auton routine began executing.

◆ autotune_drive_pid()

void light::autotune_drive_pid ( float  driveDistIn = 24.0f,
float  overshootThreshIn = 0.5f,
int  maxIters = 20 
)

◆ autotune_ekf_noise()

void light::autotune_ekf_noise ( int  sampleMs = 10,
int  durationMs = 5000,
int  warmupMs = 500 
)

Stationary EKF process-noise calibration.

Robot parked. Per-tick var(x,y,θ) → Q values, pushed live via setConfig().

◆ autotune_heading_pid()

void light::autotune_heading_pid ( float  driveDistIn = 48.0f,
float  peakDiffMv = 3000.0f,
int  maxIters = 20 
)

◆ autotune_mcl_noise()

void light::autotune_mcl_noise ( int  sampleMs = 20,
int  durationMs = 4000,
int  warmupMs = 300 
)

Stationary MCL distance-sensor noise calibration.

Robot parked with each sensor pointed at a wall in range. Mean per-sensor stddev → sensorSigmaIn; outlierGapIn = ~3·sigma. Pushed live via setConfig().

◆ autotune_swing_pid()

void light::autotune_swing_pid ( float  swingAngleDeg = 90.0f,
float  overshootThreshDeg = 3.0f,
int  maxIters = 20 
)

◆ autotune_turn_pid()

void light::autotune_turn_pid ( float  turnAngleDeg = 180.0f,
float  overshootThreshDeg = 3.0f,
int  maxIters = 20 
)

◆ characterize_a_lat_max()

float light::characterize_a_lat_max ( )

Identify the maximum sustainable lateral acceleration.

◆ characterize_friction()

void light::characterize_friction ( float  maxVoltage = 10.0f,
float  stepV = 0.5f 
)

Friction-FF auto-ID for non-trajectory PIDs.

Fits V = kS·sgn(v) + kV·v + kQ·v·|v| (motor-cmd units) and applies via chassis.friction_constants_set(). Dumps to /usd/friction_id.csv if SD present.

◆ characterize_kV_kA_kS()

void light::characterize_kV_kA_kS ( float  maxVoltage = 10.0f,
float  rampVps = 0.25f 
)

Identify kV / kA / kS by ramping voltage and recording velocity.

◆ characterize_track_width()

float light::characterize_track_width ( int  rotations = 10)

Identify the effective track width by spinning in place.

◆ estimatePose()

Pose light::estimatePose ( float  time,
bool  radians = false 
)

Linear extrapolation of pose time seconds ahead at current velocity.

◆ exit_to_string()

std::string light::exit_to_string ( exit_output  input)

Returns a human-readable name for an exit_output code.

Parameters
inputthe exit_output value

◆ extras_init()

void light::extras_init ( light::Drive chassis,
pros::MotorGroup *  leftMotors,
pros::MotorGroup *  rightMotors 
)

Register the user's drivetrain objects with LightLib.

Must be called once in initialize() before screen_task / lib_extras / moveToPoint are used.

Takes pointers rather than externing globals so LightLib can live in the PROS cold package without linker errors.

Parameters
chassisthe user's Drive instance
leftMotorsleft-side motor group
rightMotorsright-side motor group

◆ ez_template_print()

void light::ez_template_print ( )

Prints our branding all over your pros terminal.

◆ followTrajectory() [1/5]

bool light::followTrajectory ( const std::vector< Waypoint > &  wps,
bool  reversed = false,
int  timeoutMs = -1,
float  poseErrBailIn = 8.0f,
Follower  follower = Follower::PURE_PURSUIT 
)

Generate and follow a trajectory from waypoints, using the default TrajConstraints registered via ramsete_configure().

◆ followTrajectory() [2/5]

bool light::followTrajectory ( const std::vector< Waypoint > &  wps,
const TrajConstraints cons,
bool  reversed = false,
int  timeoutMs = -1,
float  poseErrBailIn = 8.0f,
Follower  follower = Follower::PURE_PURSUIT 
)

Generate and follow a trajectory from waypoints.

Parameters
wpswaypoint list
conskinematic limits
reverseddrive the path in reverse
timeoutMswall-time bail in ms (-1 = no timeout)
poseErrBailInbail if the pose error grows above this many inches
followerwhich controller to use (defaults to PURE_PURSUIT)

◆ followTrajectory() [3/5]

bool light::followTrajectory ( const std::vector< Waypoint > &  wps,
const TrajConstraints cons,
std::vector< PathEvent events,
bool  reversed = false,
int  timeoutMs = -1,
float  poseErrBailIn = 8.0f,
Follower  follower = Follower::PURE_PURSUIT 
)

Generate-and-follow variant with mid-path event triggers.

Events whose index is out of range are skipped (with a printf warning); the path still runs.

◆ followTrajectory() [4/5]

bool light::followTrajectory ( const std::vector< Waypoint > &  wps,
std::vector< PathEvent events,
bool  reversed = false,
int  timeoutMs = -1,
float  poseErrBailIn = 8.0f,
Follower  follower = Follower::PURE_PURSUIT 
)

Same as above, with mid-path events.

Uses the default TrajConstraints from ramsete_configure().

◆ followTrajectory() [5/5]

bool light::followTrajectory ( const Trajectory traj,
int  timeoutMs = -1,
float  poseErrBailIn = 8.0f,
Follower  follower = Follower::PURE_PURSUIT 
)

Follow a pre-generated Trajectory.

Parameters
trajthe trajectory to follow
timeoutMswall-time bail in ms (-1 = no timeout)
poseErrBailInbail if the pose error grows above this many inches
Returns
true on completion, false on bail/timeout

◆ generateTrajectory()

Trajectory light::generateTrajectory ( const std::vector< Waypoint > &  wps,
const TrajConstraints cons,
bool  reversed = false 
)

Generate a time-parameterized trajectory from waypoints.

Parameters
wpsordered waypoint list
conskinematic limits
reversedtrue if the robot should drive the path in reverse
Returns
the generated Trajectory; empty on failure

◆ getChassis()

light::Drive * light::getChassis ( )
Returns
Pointer to the registered chassis, or nullptr if not registered.

◆ getDriveMotorGroups()

void light::getDriveMotorGroups ( pros::MotorGroup **  leftOut,
pros::MotorGroup **  rightOut 
)

Look up the registered drivetrain motor groups.

Used by RAMSETE / characterization so they command the same motor groups the user registered via extras_init().

Parameters
leftOutout: pointer to the registered left motor group, or nullptr
rightOutout: pointer to the registered right motor group, or nullptr

◆ getLocalSpeed()

Pose light::getLocalSpeed ( bool  radians = false)
Returns
Robot-frame velocities (forward / strafe / yaw).

◆ getPose()

Pose light::getPose ( bool  radians = false)
Returns
Current fused pose.
Parameters
radianstrue for radians, false for degrees.

◆ getPoseRad()

Pose light::getPoseRad ( )
inline

Radian-only accessor; trajectory code MUST use this to avoid deg/rad bugs.

Definition at line 182 of file odometry.hpp.

◆ getSpeed()

Pose light::getSpeed ( bool  radians = false)
Returns
Field-frame velocities (in/s, deg/s by default).

◆ init()

void light::init ( OdomSensors  sensors,
MCLConfig  cfg = {} 
)

Initialize the estimator.

Parameters
sensorssensor bundle (copied)
cfgMCL configuration; defaults are usually fine

◆ moveToPoint()

void light::moveToPoint ( float  targetX,
float  targetY,
int  timeout,
float  maxSpeed,
bool  reversed 
)

Drive to a field-relative point (legacy).

Inches; speed cap 0..127.

◆ pure_pursuit_configure()

void light::pure_pursuit_configure ( PurePursuitConfig  cfg)

Configure the Pure Pursuit follower.

Call once in initialize() (after ramsete_configure(), since PP reuses RamseteConfig + DriveFF).

◆ ramsete_configure()

void light::ramsete_configure ( RamseteConfig  rc,
DriveFF  ff,
TrajConstraints  defaultCons 
)

Configure the RAMSETE follower.

Call once in initialize() before any followTrajectory / runJerryioPath call.

Parameters
rccontroller and chassis geometry
ffwheel feedforward gains
defaultConsdefault kinematic limits used when none are passed explicitly

◆ register_pose_source()

void light::register_pose_source ( PoseGetterFn  getter,
PoseSetterFn  setter 
)

Register an external pose source.

When registered, all odom_*_get() reads return the externally-supplied pose instead of LightLib's wheel integrator, and odom_*_set() calls forward to the supplied setter. Used internally to route the legacy pid_odom_* motion through the fused EKF / MCL pose estimate.

Parameters
getterfunction returning the current pose
setterfunction applying a new pose

◆ reset()

void light::reset ( )

Reset all internal pose state to (0, 0, 0).

◆ runJerryioPath() [1/2]

bool light::runJerryioPath ( const char *  csv,
bool  reversed = false,
int  timeoutMs = -1,
float  poseErrBailIn = 8.0f,
Follower  follower = Follower::PURE_PURSUIT 
)

Run a waypoint CSV (path.jerryio.com export or hand-written).

Lines are "x,y" or "x,y,heading_rad"; extra columns ignored. Inches/radians, LightLib convention (+Y forward, CW+). Uses TrajConstraints from ramsete_configure().

◆ runJerryioPath() [2/2]

bool light::runJerryioPath ( const char *  csv,
std::vector< PathEvent events,
bool  reversed = false,
int  timeoutMs = -1,
float  poseErrBailIn = 8.0f,
Follower  follower = Follower::PURE_PURSUIT 
)

Variant with mid-path event triggers.

See PathEvent for index semantics.

◆ runJerryioPathFromSD() [1/2]

bool light::runJerryioPathFromSD ( const char *  filePath,
bool  reversed = false,
int  timeoutMs = -1,
float  poseErrBailIn = 8.0f,
Follower  follower = Follower::PURE_PURSUIT 
)

Read the CSV from the V5 SD card (e.g.

"/usd/paths/red_left.csv").

◆ runJerryioPathFromSD() [2/2]

bool light::runJerryioPathFromSD ( const char *  filePath,
std::vector< PathEvent events,
bool  reversed = false,
int  timeoutMs = -1,
float  poseErrBailIn = 8.0f,
Follower  follower = Follower::PURE_PURSUIT 
)

SD-card variant with mid-path event triggers.

◆ runPath() [1/2]

bool light::runPath ( const char *  name,
bool  reversed = false,
int  timeoutMs = -1,
float  poseErrBailIn = 8.0f,
Follower  follower = Follower::PURE_PURSUIT 
)

Run a registered path by name.

Parameters
namepath name (must match a row in kAll[])
reverseddrive the path in reverse
timeoutMswall-time bail in ms (-1 = no timeout)
poseErrBailInbail if pose error exceeds this many inches
Returns
true on completion, false on bail/timeout/unknown name

◆ runPath() [2/2]

bool light::runPath ( const char *  name,
std::vector< PathEvent events,
bool  reversed = false,
int  timeoutMs = -1,
float  poseErrBailIn = 8.0f,
Follower  follower = Follower::PURE_PURSUIT 
)

Variant accepting mid-path event triggers.

See PathEvent.

◆ screen_print()

void light::screen_print ( std::string  text,
int  line = 0 
)

Prints to the brain screen in one string.

Splits input between lines with '
' or when text longer then 32 characters.

Parameters
textinput string
linestarting line to print on, defaults to 0

◆ setPose()

void light::setPose ( Pose  pose,
bool  radians = false 
)

Overwrite the current pose.

◆ stop()

void light::stop ( )

Stop the background odometry task.

◆ update()

void light::update ( )

Force one update (normally called by the background task).

◆ wait_until_auton()

void light::wait_until_auton ( uint32_t  ms)

Block until ms milliseconds have elapsed since auton started.

If that point is already in the past, returns immediately.

Parameters
mswall-clock target, in ms since auton start

◆ wrap180()

double light::wrap180 ( double  a)

Normalize an angle in degrees to the half-open interval (-180, 180] so PID always takes the shortest path.

Parameters
ainput angle in degrees

Variable Documentation

◆ ANGLE_NOT_SET

const double light::ANGLE_NOT_SET = 0.0000000000000000000001

Sentinel value indicating "no angle specified".

Definition at line 111 of file util.hpp.

◆ auton_selector

AutonSelector light::auton_selector
extern

Process-wide singleton selector instance.

◆ auton_start_ms

uint32_t light::auton_start_ms
extern

Millisecond timestamp captured right before the selected auton routine runs.

Set by LightLib in autonomous(); read by the helpers below.

◆ DRIVE_SPEED

int light::DRIVE_SPEED
extern

Default speeds used when a pid_drive_set / pid_turn_set / pid_swing_set call omits the speed argument.

Defined in src/autons.cpp — edit there.

◆ p_ANGLE_NOT_SET

const okapi::QAngle light::p_ANGLE_NOT_SET = 0.0000000000000000000001_deg

Sentinel value indicating "no angle specified" (united).

Definition at line 113 of file util.hpp.

◆ pid_tuner

PidTuner light::pid_tuner
extern

Process-wide singleton tuner instance.

◆ SWING_SPEED

int light::SWING_SPEED
extern

◆ TURN_SPEED

int light::TURN_SPEED
extern