CTRE_Phoenix 5.20.2
|
Inherits ctre::phoenix::sensors::PigeonIMU, frc::Gyro, wpi::Sendable, and wpi::SendableHelper< WPI_PigeonIMU >.
Public Member Functions | |
WPI_PigeonIMU (int deviceNumber) | |
WPI_PigeonIMU (ctre::phoenix::motorcontrol::can::TalonSRX &talon) | |
WPI_PigeonIMU (WPI_PigeonIMU const &)=delete | |
WPI_PigeonIMU & | operator= (WPI_PigeonIMU const &)=delete |
void | InitSendable (wpi::SendableBuilder &builder) override |
void | Calibrate () final |
void | Reset () final |
double | GetAngle () const override |
double | GetRate () const override |
frc::Rotation2d | GetRotation2d () const override |
Public Member Functions inherited from ctre::phoenix::sensors::PigeonIMU | |
PigeonIMU (int deviceNumber) | |
PigeonIMU (ctre::phoenix::motorcontrol::can::TalonSRX *talonSrx) | |
PigeonIMU (ctre::phoenix::motorcontrol::can::TalonSRX &talonSrx) | |
int | SetFusedHeading (double angleDeg, int timeoutMs=0) |
int | AddFusedHeading (double angleDeg, int timeoutMs=0) |
int | SetFusedHeadingToCompass (int timeoutMs=0) |
int | SetTemperatureCompensationDisable (bool bTempCompDisable, int timeoutMs=0) |
int | SetCompassDeclination (double angleDegOffset, int timeoutMs=0) |
int | SetCompassAngle (double angleDeg, int timeoutMs=0) |
int | EnterCalibrationMode (CalibrationMode calMode, int timeoutMs=0) |
int | GetGeneralStatus (PigeonIMU::GeneralStatus &statusToFill) |
PigeonState | GetState () |
int | GetAccelerometerAngles (double tiltAngles[3]) |
double | GetFusedHeading (FusionStatus &status) |
double | GetFusedHeading () const |
uint32_t | GetResetCount () |
uint32_t | GetResetFlags () |
ErrorCode | ConfigSetCustomParam (int newValue, int paramIndex, int timeoutMs=0) |
int | ConfigGetCustomParam (int paramIndex, int timeoutMs=0) |
ErrorCode | SetStatusFramePeriod (PigeonIMU_StatusFrame statusFrame, uint8_t periodMs, int timeoutMs=0) |
int | GetStatusFramePeriod (PigeonIMU_StatusFrame frame, int timeoutMs=0) |
ErrorCode | SetControlFramePeriod (PigeonIMU_ControlFrame frame, int periodMs) |
int | GetFirmwareVersion () |
ErrorCode | GetFaults (PigeonIMU_Faults &toFill) |
ErrorCode | GetStickyFaults (PigeonIMU_StickyFaults &toFill) |
ErrorCode | ClearStickyFaults (int timeoutMs=0) |
virtual ctre::phoenix::ErrorCode | ConfigAllSettings (const PigeonIMUConfiguration &allConfigs, int timeoutMs=50) |
virtual void | GetAllConfigs (PigeonIMUConfiguration &allConfigs, int timeoutMs=50) |
virtual ErrorCode | ConfigFactoryDefault (int timeoutMs=50) |
Public Member Functions inherited from ctre::phoenix::sensors::BasePigeon | |
BasePigeon (int deviceNumber, std::string const &version, std::string const &canbus="") | |
int | SetYaw (double angleDeg, int timeoutMs=0) |
int | AddYaw (double angleDeg, int timeoutMs=0) |
int | SetYawToCompass (int timeoutMs=0) |
int | SetAccumZAngle (double angleDeg, int timeoutMs=0) |
ErrorCode | GetLastError () const |
ErrorCode | Get6dQuaternion (double wxyz[4]) const |
ErrorCode | GetYawPitchRoll (double ypr[3]) const |
double | GetYaw () const |
double | GetPitch () const |
double | GetRoll () const |
int | GetAccumGyro (double xyz_deg[3]) const |
double | GetAbsoluteCompassHeading () const |
double | GetCompassHeading () const |
double | GetCompassFieldStrength () const |
double | GetTemp () const |
uint32_t | GetUpTime () const |
int | GetRawMagnetometer (int16_t rm_xyz[3]) const |
int | GetBiasedMagnetometer (int16_t bm_xyz[3]) const |
int | GetBiasedAccelerometer (int16_t ba_xyz[3]) const |
int | GetRawGyro (double xyz_dps[3]) const |
uint32_t | GetResetCount () const |
uint32_t | GetResetFlags () const |
uint32_t | GetFirmVers () const |
bool | HasResetOccurred () const |
ErrorCode | ConfigSetCustomParam (int newValue, int paramIndex, int timeoutMs=0) |
int | ConfigGetCustomParam (int paramIndex, int timeoutMs=0) |
ErrorCode | ConfigSetParameter (ParamEnum param, double value, uint8_t subValue, int ordinal, int timeoutMs=0) |
double | ConfigGetParameter (ctre::phoenix::ParamEnum param, int ordinal, int timeoutMs=0) |
ErrorCode | ConfigGetParameter (ParamEnum param, int32_t valueToSend, int32_t &valueReceived, uint8_t &subValue, int32_t ordinal, int32_t timeoutMs) |
ErrorCode | SetStatusFramePeriod (PigeonIMU_StatusFrame statusFrame, uint8_t periodMs, int timeoutMs=0) |
int | GetStatusFramePeriod (PigeonIMU_StatusFrame frame, int timeoutMs=0) |
ErrorCode | SetControlFramePeriod (PigeonIMU_ControlFrame frame, int periodMs) |
int | GetFirmwareVersion () |
ErrorCode | ClearStickyFaults (int timeoutMs=0) |
void * | GetLowLevelHandle () const |
virtual ctre::phoenix::ErrorCode | ConfigAllSettings (const BasePigeonConfiguration &allConfigs, int timeoutMs=50) |
virtual void | GetAllConfigs (BasePigeonConfiguration &allConfigs, int timeoutMs=50) |
virtual ErrorCode | ConfigFactoryDefault (int timeoutMs=50) |
virtual BasePigeonSimCollection & | GetSimCollection () |
Public Member Functions inherited from ctre::phoenix::CANBusAddressable | |
CANBusAddressable (int deviceNumber) | |
int | GetDeviceNumber () |
Additional Inherited Members | |
Public Types inherited from ctre::phoenix::sensors::PigeonIMU | |
enum | CalibrationMode { BootTareGyroAccel = 0 , Temperature = 1 , Magnetometer12Pt = 2 , Magnetometer360 = 3 , Accelerometer = 5 } |
enum | PigeonState { NoComm , Initializing , Ready , UserCalibration } |
Static Public Member Functions inherited from ctre::phoenix::sensors::PigeonIMU | |
static std::string | ToString (PigeonIMU::PigeonState state) |
static std::string | ToString (CalibrationMode cm) |
Static Public Member Functions inherited from ctre::phoenix::sensors::BasePigeon | |
static void | DestroyAllBasePigeons () |
Protected Member Functions inherited from ctre::phoenix::sensors::BasePigeon | |
BasePigeon (ctre::phoenix::motorcontrol::can::TalonSRX &talonSrx) | |
ctre::phoenix::sensors::WPI_PigeonIMU::WPI_PigeonIMU | ( | int | deviceNumber | ) |
Construtor for WPI_PigeonIMU.
deviceNumber | CAN Device ID of the Pigeon IMU. |
ctre::phoenix::sensors::WPI_PigeonIMU::WPI_PigeonIMU | ( | ctre::phoenix::motorcontrol::can::TalonSRX & | talon | ) |
Construtor for WPI_PigeonIMU.
talon | The Talon SRX ribbon-cabled to Pigeon. |