Skip to content

Instantly share code, notes, and snippets.

View kauailabs's full-sized avatar

Kauai Labs kauailabs

View GitHub Profile
package org.usfirst.frc.team2465.robot;
import com.kauailabs.navx.frc.AHRS;
import com.kauailabs.sf2.frc.navXSensor;
import com.kauailabs.sf2.orientation.OrientationHistory;
import com.kauailabs.sf2.orientation.Quaternion;
import com.kauailabs.sf2.time.TimestampedValue;
import edu.wpi.first.wpilibj.SPI;
import edu.wpi.first.wpilibj.SampleRobot;
#include "WPILib.h"
#include "AHRS.h"
#include "orientation/OrientationHistory.h"
#include "navXSensor.h"
/**
* This SF2 Example Robot Application demonstrates using an Orientation Time History,
* based upon a navX-MXP or navX-Micro sensor.
*
* The number of samples in the history is based upon the currently-configured
@kauailabs
kauailabs / gist:4e5462c555d8c8de7cce9d96bd5293a3
Last active September 29, 2021 01:38
navXMicroAutoBalance
package org.firstinspires.ftc.teamcode;
import com.qualcomm.hardware.kauailabs.NavxMicroNavigationSensor;
import com.kauailabs.navx.ftc.AHRS;
import com.kauailabs.navx.ftc.navXPIDController;
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.util.ElapsedTime;
@kauailabs
kauailabs / VMX-pi-HAL-RTC
Last active July 13, 2025 05:34
VMX-pi C++ HAL: Real-time Clock Example
#include "VMXPi.h"
int main(int argc, char *argv[])
{
bool realtime = false;
uint8_t update_rate_hz = 50;
VMXPi vmx(realtime, update_rate_hz);
if(vmx.IsOpen()) {
/* Acquire Real-Time Clock and OS Clock values */
@kauailabs
kauailabs / VMX-pi-HAL-AnalogIO
Last active October 30, 2017 18:18
VMX-pi-HAL-AnalogIO
#include "VMXPi.h"
int main(int argc, char *argv[])
{
bool realtime = false;
uint8_t update_rate_hz = 50;
VMXPi vmx(realtime, update_rate_hz);
if(vmx.IsOpen()) {
@kauailabs
kauailabs / VMX-pi-HAL-CANBusMonitor
Last active December 22, 2022 07:32
VMX-pi-HAL-CANBusMonitor
#include <stdio.h> /* printf() */
#include "VMXPi.h"
int main(int argc, char *argv[])
{
bool realtime = false;
uint8_t update_rate_hz = 50;
VMXPi vmx(realtime, update_rate_hz);
if(vmx.IsOpen()) {
#include <stdio.h> /* printf() */
#include "VMXPi.h"
int main(int argc, char *argv[])
{
bool realtime = false;
uint8_t update_rate_hz = 50;
VMXPi vmx(realtime, update_rate_hz);
if(vmx.IsOpen()) {
#include <stdio.h> /* printf() */
#include "VMXPi.h"
#define ARRAY_SIZE(a) (sizeof(a)/sizeof(a[0]))
int main(int argc, char *argv[])
{
bool realtime = false;
uint8_t update_rate_hz = 50;
VMXPi vmx(realtime, update_rate_hz);
#include <stdio.h> /* printf() */
#include "VMXPi.h"
#define ARRAY_SIZE(a) (sizeof(a)/sizeof(a[0]))
int main(int argc, char *argv[])
{
bool realtime = false;
uint8_t update_rate_hz = 50;
VMXPi vmx(realtime, update_rate_hz);
/#include <stdio.h> /* printf() */
#include "VMXPi.h"
#define ARRAY_SIZE(a) (sizeof(a)/sizeof(a[0]))
int main(int argc, char *argv[])
{
bool realtime = false;
uint8_t update_rate_hz = 50;
VMXPi vmx(realtime, update_rate_hz);