Class WPI_Pigeon2
- All Implemented Interfaces:
edu.wpi.first.util.sendable.Sendable,edu.wpi.first.wpilibj.interfaces.Gyro,AutoCloseable
-
Constructor Summary
ConstructorsConstructorDescriptionWPI_Pigeon2(int deviceNumber) Constructor for Pigeon 2.WPI_Pigeon2(int deviceNumber, String canbus) Constructor for Pigeon 2. -
Method Summary
Modifier and TypeMethodDescriptionvoidThis function does nothing, it exists to satisfy the WPILib Gyro interface.voidclose()doublegetAngle()Return the heading of the robot in degrees.doublegetRate()Return the rate of rotation of the gyro.edu.wpi.first.math.geometry.Rotation2dReturn the heading of the robot as aRotation2d.voidinitSendable(edu.wpi.first.util.sendable.SendableBuilder builder) Initializes thisSendableobject.voidreset()Reset the gyro.Methods inherited from class com.ctre.phoenix.sensors.Pigeon2
configAllSettings, configAllSettings, configDisableNoMotionCalibration, configDisableNoMotionCalibration, configDisableTemperatureCompensation, configDisableTemperatureCompensation, configEnableCompass, configEnableCompass, configMountPose, configMountPose, configMountPosePitch, configMountPosePitch, configMountPoseRoll, configMountPoseRoll, configMountPoseYaw, configMountPoseYaw, getAllConfigs, getAllConfigs, getFaults, getGravityVector, getStickyFaults, zeroGyroBiasNow, zeroGyroBiasNowMethods inherited from class com.ctre.phoenix.sensors.BasePigeon
addYaw, addYaw, clearStickyFaults, clearStickyFaults, configAllSettings, configAllSettings, configFactoryDefault, configFactoryDefault, configGetCustomParam, configGetCustomParam, configGetParameter, configGetParameter, configGetParameter, configGetParameter, configSetCustomParam, configSetCustomParam, configSetParameter, configSetParameter, configSetParameter, configSetParameter, DestroyObject, get6dQuaternion, getAbsoluteCompassHeading, getAccumGyro, getAllConfigs, getAllConfigs, getBiasedAccelerometer, getBiasedMagnetometer, getCompassFieldStrength, getCompassHeading, getDeviceID, getFirmwareVersion, getHandle, getLastError, getPitch, getRawGyro, getRawMagnetometer, getResetCount, getResetFlags, getRoll, getSimCollection, getStatusFramePeriod, getStatusFramePeriod, getTemp, getUpTime, getYaw, getYawPitchRoll, hasResetOccurred, setAccumZAngle, setAccumZAngle, setControlFramePeriod, setControlFramePeriod, setStatusFramePeriod, setStatusFramePeriod, setStatusFramePeriod, setStatusFramePeriod, setYaw, setYaw, setYawToCompass, setYawToCompass
-
Constructor Details
-
WPI_Pigeon2
Constructor for Pigeon 2.- Parameters:
deviceNumber- device ID of Pigeon 2canbus- Name of the CANbus; can be a CANivore device name or serial number. Pass in nothing or "rio" to use the roboRIO.
-
WPI_Pigeon2
Constructor for Pigeon 2.- Parameters:
deviceNumber- device ID of Pigeon 2
-
-
Method Details
-
close
- Specified by:
closein interfaceAutoCloseable
-
calibrate
This function does nothing, it exists to satisfy the WPILib Gyro interface. Pigeon does calibration on boot and any one-time calibrations (like temperature) are done via Phoenix Tuner.- Specified by:
calibratein interfaceedu.wpi.first.wpilibj.interfaces.Gyro
-
reset
Description copied from interface:edu.wpi.first.wpilibj.interfaces.GyroReset the gyro. Resets the gyro 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.- Specified by:
resetin interfaceedu.wpi.first.wpilibj.interfaces.Gyro
-
getAngle
Description copied from interface:edu.wpi.first.wpilibj.interfaces.GyroReturn the heading of the robot in degrees.The angle is continuous, that is it will continue from 360 to 361 degrees. This allows algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from 360 to 0 on the second time around.
The angle is expected to increase as the gyro turns clockwise when looked at from the top. It needs to follow the NED axis convention.
This heading is based on integration of the returned rate from the gyro.
- Specified by:
getAnglein interfaceedu.wpi.first.wpilibj.interfaces.Gyro- Returns:
- the current heading of the robot in degrees.
-
getRate
Description copied from interface:edu.wpi.first.wpilibj.interfaces.GyroReturn the rate of rotation of the gyro.The rate is based on the most recent reading of the gyro analog value
The rate is expected to be positive as the gyro turns clockwise when looked at from the top. It needs to follow the NED axis convention.
- Specified by:
getRatein interfaceedu.wpi.first.wpilibj.interfaces.Gyro- Returns:
- the current rate in degrees per second
-
getRotation2d
Description copied from interface:edu.wpi.first.wpilibj.interfaces.GyroReturn the heading of the robot as aRotation2d.The angle is continuous, that is it will continue from 360 to 361 degrees. This allows algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps past from 360 to 0 on the second time around.
The angle is expected to increase as the gyro turns counterclockwise when looked at from the top. It needs to follow the NWU axis convention.
This heading is based on integration of the returned rate from the gyro.
- Specified by:
getRotation2din interfaceedu.wpi.first.wpilibj.interfaces.Gyro- Returns:
- the current heading of the robot as a
Rotation2d.
-
initSendable
Description copied from interface:edu.wpi.first.util.sendable.SendableInitializes thisSendableobject.- Specified by:
initSendablein interfaceedu.wpi.first.util.sendable.Sendable- Parameters:
builder- sendable builder
-