pros/imu.h file

Contains prototypes for functions related to the VEX Inertial sensor.

This file should not be modified by users, since it gets replaced whenever a kernel upgrade occurs.

This Source Code Form is subject to the terms of the Mozilla Public License, v. 2.0. If a copy of the MPL was not distributed with this file, You can obtain one at http://mozilla.org/MPL/2.0/.

Namespaces

namespace pros
LLEMU Conditional Include
namespace pros::c

Functions

struct __attribute__((__packed__)) gps_position_s
int32_t imu_reset(uint8_t port)
Calibrate IMU.
int32_t imu_reset_blocking(uint8_t port)
Calibrate IMU and Blocks while Calibrating.
int32_t imu_set_data_rate(uint8_t port, uint32_t rate)
Set the Inertial Sensor's refresh interval in milliseconds.
double imu_get_rotation(uint8_t port)
Get the total number of degrees the Inertial Sensor has spun about the z-axis.
double imu_get_heading(uint8_t port)
Get the Inertial Sensor's heading relative to the initial direction of its x-axis.
quaternion_s_t imu_get_quaternion(uint8_t port)
Get a quaternion representing the Inertial Sensor's orientation.
euler_s_t imu_get_euler(uint8_t port)
Get the Euler angles representing the Inertial Sensor's orientation.
imu_gyro_s_t imu_get_gyro_rate(uint8_t port)
Get the Inertial Sensor's raw gyroscope values.
imu_accel_s_t imu_get_accel(uint8_t port)
Get the Inertial Sensor's raw acceleroneter values.
imu_status_e_t imu_get_status(uint8_t port)
Get the Inertial Sensor's status.
double imu_get_pitch(uint8_t port)
Get the Inertial Sensor's pitch angle bounded by (-180,180)
double imu_get_roll(uint8_t port)
Get the Inertial Sensor's roll angle bounded by (-180,180)
double imu_get_yaw(uint8_t port)
Get the Inertial Sensor's yaw angle bounded by (-180,180)

Value Reset Functions

int32_t imu_tare_heading(uint8_t port)
Resets the current reading of the Inertial Sensor's heading to zero.
int32_t imu_tare_rotation(uint8_t port)
Resets the current reading of the Inertial Sensor's rotation to zero.
int32_t imu_tare_pitch(uint8_t port)
Resets the current reading of the Inertial Sensor's pitch to zero.
int32_t imu_tare_roll(uint8_t port)
Resets the current reading of the Inertial Sensor's roll to zero.
int32_t imu_tare_yaw(uint8_t port)
Resets the current reading of the Inertial Sensor's yaw to zero.
int32_t imu_tare_euler(uint8_t port)
Reset all 3 euler values of the Inertial Sensor to 0.
int32_t imu_tare(uint8_t port)
Resets all 5 values of the Inertial Sensor to 0.

Value Set Functions

int32_t imu_set_euler(uint8_t port, euler_s_t target)
Sets the current reading of the Inertial Sensor's euler values to target euler values.
int32_t imu_set_rotation(uint8_t port, double target)
Sets the current reading of the Inertial Sensor's rotation to target value.
int32_t imu_set_heading(uint8_t port, double target)
Sets the current reading of the Inertial Sensor's heading to target value Target will default to 360 if above 360 and default to 0 if below 0.
int32_t imu_set_pitch(uint8_t port, double target)
Sets the current reading of the Inertial Sensor's pitch to target value Will default to +/- 180 if target exceeds +/- 180.
int32_t imu_set_roll(uint8_t port, double target)
Sets the current reading of the Inertial Sensor's roll to target value Will default to +/- 180 if target exceeds +/- 180.
int32_t imu_set_yaw(uint8_t port, double target)
Sets the current reading of the Inertial Sensor's yaw to target value Will default to +/- 180 if target exceeds +/- 180.
imu_orientation_e_t imu_get_physical_orientation(uint8_t port)
Returns the physical orientation of the IMU.

Enums

enum imu_status_e { E_IMU_STATUS_READY = 0, E_IMU_STATUS_CALIBRATING = 1, E_IMU_STATUS_ERROR = 0xFF }
enum imu_orientation_e { E_IMU_Z_UP = 0, E_IMU_Z_DOWN = 1, E_IMU_X_UP = 2, E_IMU_X_DOWN = 3, E_IMU_Y_UP = 4, E_IMU_Y_DOWN = 5, E_IMU_ORIENTATION_ERROR = 0xFF }

Typedefs

using imu_gyro_s_t = struct imu_raw_s
using imu_accel_s_t = struct imu_raw_s

Variables

quaternion_s_t
euler_s_t

Defines

#define IMU_MINIMUM_DATA_RATE