robotpy_ext.common_drivers.navx package¶
NavX Extension Pins¶
-
robotpy_ext.common_drivers.navx.pins.getNavxDigitalChannel(pin)[source]¶ Get the WPILib channel number for a digital input on a NavX MXP
Parameters: pin (int) – The NavX pin number (0-9) Returns: RoboRIO channel number
-
robotpy_ext.common_drivers.navx.pins.getNavxPWMChannel(pin)[source]¶ Get the WPILib channel number for a PWM on a NavX MXP
Parameters: pin (int) – The NavX pin number (0-9) Returns: RoboRIO channel number
-
robotpy_ext.common_drivers.navx.pins.getNavxAnalogInChannel(pin)[source]¶ Get the WPILib channel number for an Analog Input on a NavX MXP
Parameters: pin (int) – The NavX pin number (0-3) Returns: RoboRIO channel number
-
robotpy_ext.common_drivers.navx.pins.getNavxAnalogOutChannel(pin)[source]¶ Get the WPILib channel number for an Analog Output on a NavX MXP
Parameters: pin (int) – The NavX pin number (0-1) Returns: RoboRIO channel number
NavX AHRS Interface¶
-
class
robotpy_ext.common_drivers.navx.ahrs.AHRS(io, update_rate_hz=None)[source]¶ The AHRS class provides an interface to AHRS capabilities of the KauaiLabs navX Robotics Navigation Sensor via SPI and I2C communications interfaces on the RoboRIO.
The AHRS class enables access to basic connectivity and state information, as well as key 6-axis and 9-axis orientation information (yaw, pitch, roll, compass heading, fused (9-axis) heading and magnetic disturbance detection.
Additionally, the ARHS class also provides access to extended information including linear acceleration, motion detection, rotation detection and sensor temperature.
If used with the navX Aero, the AHRS class also provides access to altitude, barometric pressure and pressure sensor temperature data
Note
This implementation does not provide access to the NavX via a serial port
Don’t use the constructor, use the
create_spi()orcreate_i2c()class methods instead-
DEFAULT_ACCEL_FSR_G= 2¶
-
DEFAULT_GYRO_FSR_DPS= 2000¶
-
NAVX_DEFAULT_UPDATE_RATE_HZ= 60¶
-
class
PIDSourceType¶ A description for the type of output value to provide to a
PIDController-
kDisplacement= 0¶
-
kRate= 1¶
-
-
AHRS.YAW_HISTORY_LENGTH= 10¶
-
AHRS.altitude_valid¶
-
classmethod
AHRS.create_i2c(port=1, update_rate_hz=None)[source]¶ Constructs the AHRS class using I2C communication, overriding the default update rate with a custom rate which may be from 4 to 60, representing the number of updates per second sent by the sensor.
This constructor should be used if communicating via I2C.
Note
Increasing the update rate may increase the CPU utilization.
Parameters: - port (
I2C.Port) – I2C Port to use - update_rate_hz – Custom Update Rate (Hz)
- port (
-
classmethod
AHRS.create_spi(port=4, spi_bitrate=None, update_rate_hz=None)[source]¶ Constructs the AHRS class using SPI communication, overriding the default update rate with a custom rate which may be from 4 to 60, representing the number of updates per second sent by the sensor.
This constructor allows the specification of a custom SPI bitrate, in bits/second.
Note
Increasing the update rate may increase the CPU utilization.
Parameters: - port (
SPI.Port) – SPI Port to use - spi_bitrate – SPI bitrate (Maximum: 2,000,000)
- update_rate_hz – Custom Update Rate (Hz)
- port (
-
AHRS.getAltitude()[source]¶ Returns the current altitude, based upon calibrated readings from a barometric pressure sensor, and the currently-configured sea-level barometric pressure [navX Aero only]. This value is in units of meters.
Note
This value is only valid sensors including a pressure sensor. To determine whether this value is valid, see
isAltitudeValid().Returns: Returns current altitude in meters (as long as the sensor includes an installed on-board pressure sensor).
-
AHRS.getAngle()[source]¶ Returns the total accumulated yaw angle (Z Axis, in degrees) reported by the sensor.
Note
The angle is continuous, meaning it’s range is beyond 360 degrees. This ensures that algorithms that wouldn’t want to see a discontinuity in the gyro output as it sweeps past 0 on the second time around.
Note that the returned yaw value will be offset by a user-specified offset value this user-specified offset value is set by invoking the zeroYaw() method.
Returns: The current total accumulated yaw angle (Z axis) of the robot in degrees. This heading is based on integration of the returned rate from the Z-axis (yaw) gyro.
-
AHRS.getBarometricPressure()[source]¶ Returns the current barometric pressure, based upon calibrated readings from the onboard pressure sensor. This value is in units of millibar.
Note
This value is only valid for a navX Aero. To determine whether this value is valid, see
isAltitudeValid().Returns: Returns current barometric pressure (navX Aero only).
-
AHRS.getBoardYawAxis()[source]¶ Returns information regarding which sensor board axis (X,Y or Z) and direction (up/down) is currently configured to report Yaw (Z) angle values. NOTE: If the board firmware supports Omnimount, the board yaw axis/direction are configurable.
For more information on Omnimount, please see:
http://navx-mxp.kauailabs.com/navx-mxp/installation/omnimount/
Returns: The currently-configured board yaw axis/direction as a tuple of (up, axis). Up can be True/False, axis is ‘x’, ‘y’, or ‘z’)
-
AHRS.getByteCount()[source]¶ Returns the count in bytes of data received from the sensor. This could can be useful for diagnosing connectivity issues.
If the byte count is increasing, but the update count (see
getUpdateCount()) is not, this indicates a software misconfiguration.Returns: The number of bytes received from the sensor.
-
AHRS.getCompassHeading()[source]¶ Returns the current tilt-compensated compass heading value (in degrees, from 0 to 360) reported by the sensor.
Note that this value is sensed by a magnetometer, which can be affected by nearby magnetic fields (e.g., the magnetic fields generated by nearby motors).
Before using this value, ensure that (a) the magnetometer has been calibrated and (b) that a magnetic disturbance is not taking place at the instant when the compass heading was generated. :returns: The current tilt-compensated compass heading, in degrees (0-360).
-
AHRS.getDisplacementX()[source]¶ Returns the displacement (in meters) of the X axis since resetDisplacement() was last invoked [Experimental].
Note
This feature is experimental. Displacement measures rely on double-integration of acceleration values from MEMS accelerometers which yield “noisy” values. The resulting displacement are not known to be very accurate, and the amount of error increases quickly as time progresses.
Returns: Displacement since last reset (in meters).
-
AHRS.getDisplacementY()[source]¶ Returns the displacement (in meters) of the Y axis since resetDisplacement() was last invoked [Experimental].
Note
This feature is experimental. Displacement measures rely on double-integration of acceleration values from MEMS accelerometers which yield “noisy” values. The resulting displacement are not known to be very accurate, and the amount of error increases quickly as time progresses.
Returns: Displacement since last reset (in meters).
-
AHRS.getDisplacementZ()[source]¶ Returns the displacement (in meters) of the Z axis since resetDisplacement() was last invoked [Experimental].
Note
This feature is experimental. Displacement measures rely on double-integration of acceleration values from MEMS accelerometers which yield “noisy” values. The resulting displacement are not known to be very accurate, and the amount of error increases quickly as time progresses.
Returns: Displacement since last reset (in meters).
-
AHRS.getFirmwareVersion()[source]¶ Returns the version number of the firmware currently executing on the sensor.
To update the firmware to the latest version, please see:
http://navx-mxp.kauailabs.com/navx-mxp/support/updating-firmware/
Returns: The firmware version in the format [MajorVersion].[MinorVersion]
-
AHRS.getFusedHeading()[source]¶ Returns the “fused” (9-axis) heading.
The 9-axis heading is the fusion of the yaw angle, the tilt-corrected compass heading, and magnetic disturbance detection. Note that the magnetometer calibration procedure is required in order to achieve valid 9-axis headings.
The 9-axis Heading represents the sensor’s best estimate of current heading, based upon the last known valid Compass Angle, and updated by the change in the Yaw Angle since the last known valid Compass Angle. The last known valid Compass Angle is updated whenever a Calibrated Compass Angle is read and the sensor has recently rotated less than the Compass Noise Bandwidth (~2 degrees).
Returns: Fused Heading in Degrees (range 0-360)
-
AHRS.getPitch()[source]¶ Returns the current pitch value (in degrees, from -180 to 180) reported by the sensor. Pitch is a measure of rotation around the X Axis.
Returns: The current pitch value in degrees (-180 to 180).
-
AHRS.getPressure()[source]¶ Returns the current barometric pressure (in millibar) [navX Aero only].
This value is valid only if a barometric pressure sensor is onboard.
Returns: Returns the current barometric pressure (in millibar).
-
AHRS.getQuaternionW()[source]¶ Returns the imaginary portion (W) of the Orientation Quaternion which fully describes the current sensor orientation with respect to the reference angle defined as the angle at which the yaw was last “zeroed”.
Each quaternion value (W,X,Y,Z) is expressed as a value ranging from -2 to 2. This total range (4) can be associated with a unit circle, since each circle is comprised of 4 PI Radians.
For more information on Quaternions and their use, please see this <a href=https://en.wikipedia.org/wiki/Quaternions_and_spatial_rotation>definition</a>.
Returns: Returns the imaginary portion (W) of the quaternion.
-
AHRS.getQuaternionX()[source]¶ Returns the real portion (X axis) of the Orientation Quaternion which fully describes the current sensor orientation with respect to the reference angle defined as the angle at which the yaw was last “zeroed”.
Each quaternion value (W,X,Y,Z) is expressed as a value ranging from -2 to 2. This total range (4) can be associated with a unit circle, since each circle is comprised of 4 PI Radians.
For more information on Quaternions and their use, please see this <a href=https://en.wikipedia.org/wiki/Quaternions_and_spatial_rotation>description</a>.
Returns: Returns the real portion (X) of the quaternion.
-
AHRS.getQuaternionY()[source]¶ Returns the real portion (Y axis) of the Orientation Quaternion which fully describes the current sensor orientation with respect to the reference angle defined as the angle at which the yaw was last “zeroed”.
Each quaternion value (W,X,Y,Z) is expressed as a value ranging from -2 to 2. This total range (4) can be associated with a unit circle, since each circle is comprised of 4 PI Radians.
For more information on Quaternions and their use, please see:
https://en.wikipedia.org/wiki/Quaternions_and_spatial_rotation
Returns: Returns the real portion (X) of the quaternion.
-
AHRS.getQuaternionZ()[source]¶ Returns the real portion (Z axis) of the Orientation Quaternion which fully describes the current sensor orientation with respect to the reference angle defined as the angle at which the yaw was last “zeroed”.
Each quaternion value (W,X,Y,Z) is expressed as a value ranging from -2 to 2. This total range (4) can be associated with a unit circle, since each circle is comprised of 4 PI Radians.
For more information on Quaternions and their use, please see:
https://en.wikipedia.org/wiki/Quaternions_and_spatial_rotation
Returns: Returns the real portion (X) of the quaternion.
-
AHRS.getRate()[source]¶ Return the rate of rotation of the yaw (Z-axis) gyro, in degrees per second.
The rate is based on the most recent reading of the yaw gyro angle.
Returns: The current rate of change in yaw angle (in degrees per second)
-
AHRS.getRawAccelX()[source]¶ Returns the current raw (unprocessed) X-axis acceleration rate (in G).
Note
this value is unprocessed, and should only be accessed by advanced users. This raw value has not had acceleration due to gravity removed from it, and has not been rotated to the world reference frame. Gravity-corrected, world reference frame-corrected X axis acceleration data is accessible via the
getWorldLinearAccelX()method.Returns: Returns the current acceleration rate (in G).
-
AHRS.getRawAccelY()[source]¶ Returns the current raw (unprocessed) Y-axis acceleration rate (in G).
Note
this value is unprocessed, and should only be accessed by advanced users. This raw value has not had acceleration due to gravity removed from it, and has not been rotated to the world reference frame. Gravity-corrected, world reference frame-corrected Y axis acceleration data is accessible via the
getWorldLinearAccelY()method.Returns: Returns the current acceleration rate (in G).
-
AHRS.getRawAccelZ()[source]¶ Returns the current raw (unprocessed) Z-axis acceleration rate (in G).
Note
this value is unprocessed, and should only be accessed by advanced users. This raw value has not had acceleration due to gravity removed from it, and has not been rotated to the world reference frame. Gravity-corrected, world reference frame-corrected Z axis acceleration data is accessible via the
getWorldLinearAccelZ()method.Returns: Returns the current acceleration rate (in G).
-
AHRS.getRawGyroX()[source]¶ Returns the current raw (unprocessed) X-axis gyro rotation rate (in degrees/sec).
Note
This value is un-processed, and should only be accessed by advanced users. Typically, rotation about the X Axis is referred to as “Pitch”. Calibrated and Integrated Pitch data is accessible via the
getPitch()method.Returns: Returns the current rotation rate (in degrees/sec).
-
AHRS.getRawGyroY()[source]¶ Returns the current raw (unprocessed) Y-axis gyro rotation rate (in degrees/sec).
Note
This value is un-processed, and should only be accessed by advanced users. Typically, rotation about the T Axis is referred to as “Roll”. Calibrated and Integrated Pitch data is accessible via the
getRoll()method.Returns: Returns the current rotation rate (in degrees/sec).
-
AHRS.getRawGyroZ()[source]¶ Returns the current raw (unprocessed) Z-axis gyro rotation rate (in degrees/sec).
Note
This value is un-processed, and should only be accessed by advanced users. Typically, rotation about the T Axis is referred to as “Yaw”. Calibrated and Integrated Pitch data is accessible via the
getYaw()method.Returns: Returns the current rotation rate (in degrees/sec).
-
AHRS.getRawMagX()[source]¶ Returns the current raw (unprocessed) X-axis magnetometer reading (in uTesla).
Note
this value is unprocessed, and should only be accessed by advanced users. This raw value has not been tilt-corrected, and has not been combined with the other magnetometer axis data to yield a compass heading. Tilt-corrected compass heading data is accessible via the
getCompassHeading()method.Returns: Returns the mag field strength (in uTesla).
-
AHRS.getRawMagY()[source]¶ Returns the current raw (unprocessed) Y-axis magnetometer reading (in uTesla).
Note
this value is unprocessed, and should only be accessed by advanced users. This raw value has not been tilt-corrected, and has not been combined with the other magnetometer axis data to yield a compass heading. Tilt-corrected compass heading data is accessible via the
getCompassHeading()method.Returns: Returns the mag field strength (in uTesla).
-
AHRS.getRawMagZ()[source]¶ Returns the current raw (unprocessed) Z-axis magnetometer reading (in uTesla).
Note
this value is unprocessed, and should only be accessed by advanced users. This raw value has not been tilt-corrected, and has not been combined with the other magnetometer axis data to yield a compass heading. Tilt-corrected compass heading data is accessible via the
getCompassHeading()method.Returns: Returns the mag field strength (in uTesla).
-
AHRS.getRoll()[source]¶ Returns the current roll value (in degrees, from -180 to 180) reported by the sensor. Roll is a measure of rotation around the X Axis.
Returns: The current roll value in degrees (-180 to 180).
-
AHRS.getTempC()[source]¶ Returns the current temperature (in degrees centigrade) reported by the sensor’s gyro/accelerometer circuit.
This value may be useful in order to perform advanced temperature- correction of raw gyroscope and accelerometer values.
Returns: The current temperature (in degrees centigrade).
-
AHRS.getUpdateCount()[source]¶ Returns the count of valid updates which have been received from the sensor. This count should increase at the same rate indicated by the configured update rate.
Returns: The number of valid updates received from the sensor.
-
AHRS.getVelocityX()[source]¶ Returns the velocity (in meters/sec) of the X axis [Experimental].
Note
This feature is experimental. Velocity measures rely on integration of acceleration values from MEMS accelerometers which yield “noisy” values. The resulting velocities are not known to be very accurate.
Returns: Current Velocity (in meters/squared).
-
AHRS.getVelocityY()[source]¶ Returns the velocity (in meters/sec) of the Y axis [Experimental].
Note
This feature is experimental. Velocity measures rely on integration of acceleration values from MEMS accelerometers which yield “noisy” values. The resulting velocities are not known to be very accurate.
Returns: Current Velocity (in meters/squared).
-
AHRS.getVelocityZ()[source]¶ Returns the velocity (in meters/sec) of the X axis [Experimental].
Note
This feature is experimental. Velocity measures rely on integration of acceleration values from MEMS accelerometers which yield “noisy” values. The resulting velocities are not known to be very accurate.
Returns: Current Velocity (in meters/squared).
-
AHRS.getWorldLinearAccelX()[source]¶ Returns the current linear acceleration in the X-axis (in G).
World linear acceleration refers to raw acceleration data, which has had the gravity component removed, and which has been rotated to the same reference frame as the current yaw value. The resulting value represents the current acceleration in the x-axis of the body (e.g., the robot) on which the sensor is mounted.
Returns: Current world linear acceleration in the X-axis (in G).
-
AHRS.getWorldLinearAccelY()[source]¶ Returns the current linear acceleration in the Y-axis (in G).
World linear acceleration refers to raw acceleration data, which has had the gravity component removed, and which has been rotated to the same reference frame as the current yaw value. The resulting value represents the current acceleration in the Y-axis of the body (e.g., the robot) on which the sensor is mounted.
Returns: Current world linear acceleration in the Y-axis (in G).
-
AHRS.getWorldLinearAccelZ()[source]¶ Returns the current linear acceleration in the Z-axis (in G).
World linear acceleration refers to raw acceleration data, which has had the gravity component removed, and which has been rotated to the same reference frame as the current yaw value. The resulting value represents the current acceleration in the Z-axis of the body (e.g., the robot) on which the sensor is mounted.
Returns: Current world linear acceleration in the Z-axis (in G).
-
AHRS.getYaw()[source]¶ Returns the current yaw value (in degrees, from -180 to 180) reported by the sensor. Yaw is a measure of rotation around the Z Axis (which is perpendicular to the earth).
Note that the returned yaw value will be offset by a user-specified offset value this user-specified offset value is set by invoking the zeroYaw() method.
Returns: The current yaw value in degrees (-180 to 180).
-
AHRS.isAltitudeValid()[source]¶ Indicates whether the current altitude (and barometric pressure) data is valid. This value will only be true for a sensor with an onboard pressure sensor installed.
If this value is false for a board with an installed pressure sensor, this indicates a malfunction of the onboard pressure sensor.
Returns: Returns true if a working pressure sensor is installed.
-
AHRS.isCalibrating()[source]¶ Returns true if the sensor is currently performing automatic gyro/accelerometer calibration. Automatic calibration occurs when the sensor is initially powered on, during which time the sensor should be held still, with the Z-axis pointing up (perpendicular to the earth).
Note
During this automatic calibration, the yaw, pitch and roll values returned may not be accurate.
Once calibration is complete, the sensor will automatically remove an internal yaw offset value from all reported values.
Returns: Returns true if the sensor is currently automatically calibrating the gyro and accelerometer sensors.
-
AHRS.isConnected()[source]¶ Indicates whether the sensor is currently connected to the host computer. A connection is considered established whenever communication with the sensor has occurred recently.
Returns: Returns true if a valid update has been recently received from the sensor.
-
AHRS.isMagneticDisturbance()[source]¶ Indicates whether the current magnetic field strength diverges from the calibrated value for the earth’s magnetic field by more than the currently- configured Magnetic Disturbance Ratio.
This function will always return false if the sensor’s magnetometer has not yet been calibrated (see
isMagnetometerCalibrated()).Returns: true if a magnetic disturbance is detected (or the magnetometer is uncalibrated).
-
AHRS.isMagnetometerCalibrated()[source]¶ Indicates whether the magnetometer has been calibrated.
Magnetometer Calibration must be performed by the user.
Note that if this function does indicate the magnetometer is calibrated, this does not necessarily mean that the calibration quality is sufficient to yield valid compass headings.
Returns: Returns true if magnetometer calibration has been performed.
-
AHRS.isMoving()[source]¶ Indicates if the sensor is currently detecting motion, based upon the X and Y-axis world linear acceleration values. If the sum of the absolute values of the X and Y axis exceed a “motion threshold”, the motion state is indicated.
Returns: Returns true if the sensor is currently detecting motion.
-
AHRS.isRotating()[source]¶ Indicates if the sensor is currently detecting motion, based upon the X and Y-axis world linear acceleration values. If the sum of the absolute values of the X and Y axis exceed a “motion threshold”, the motion state is indicated.
Returns: Returns true if the sensor is currently detecting motion.
-
AHRS.is_magnetometer_calibrated¶
-
AHRS.is_moving¶
-
AHRS.is_rotating¶
-
AHRS.magnetic_disturbance¶
-
AHRS.pidGet()[source]¶ Returns the current value to use for PID, based on the PIDSourceType.
If the PIDSourceType is kDisplacement, this returns the Yaw Angle in degrees (-180 to 180). See
getYaw().If the PIDSourceType is kRate, this returns the rate of rotation in degrees per seconds. See
getRate().Returns: The current yaw angle or rate.
-
AHRS.reset()[source]¶ Reset the Yaw gyro.
Resets the Gyro Z (Yaw) axis to a heading of zero. This can be used if there is significant drift in the gyro and it needs to be recalibrated after it has been running.
-