CTRE Phoenix C++ 5.33.0
ctre::phoenix::sensors::WPI_PigeonIMU Class Reference

#include <ctre/phoenix/sensors/WPI_PigeonIMU.h>

Inheritance diagram for ctre::phoenix::sensors::WPI_PigeonIMU:
ctre::phoenix::sensors::PigeonIMU ctre::phoenix::sensors::BasePigeon ctre::phoenix::CANBusAddressable

Public Member Functions

 WPI_PigeonIMU (int deviceNumber)
 Construtor for WPI_PigeonIMU. More...
 
 WPI_PigeonIMU (ctre::phoenix::motorcontrol::can::TalonSRX &talon)
 Construtor for WPI_PigeonIMU. More...
 
 ~WPI_PigeonIMU ()
 
 WPI_PigeonIMU ()=delete
 
 WPI_PigeonIMU (WPI_PigeonIMU const &)=delete
 
WPI_PigeonIMUoperator= (WPI_PigeonIMU const &)=delete
 
void InitSendable (wpi::SendableBuilder &builder) override
 
void Reset ()
 Resets the Pigeon IMU to a heading of zero. More...
 
double GetAngle () const
 Returns the heading of the robot in degrees. More...
 
double GetRate () const
 Returns the rate of rotation of the Pigeon IMU. More...
 
frc::Rotation2d GetRotation2d () const
 Returns the heading of the robot as a frc::Rotation2d. More...
 
- Public Member Functions inherited from ctre::phoenix::sensors::PigeonIMU
 PigeonIMU (int deviceNumber)
 Create a Pigeon object that communicates with Pigeon on CAN Bus. More...
 
 PigeonIMU (ctre::phoenix::motorcontrol::can::TalonSRX *talonSrx)
 Create a Pigeon object that communciates with Pigeon through the Gadgeteer ribbon cable connected to a Talon on CAN Bus. More...
 
 PigeonIMU (ctre::phoenix::motorcontrol::can::TalonSRX &talonSrx)
 Create a Pigeon object that communciates with Pigeon through the Gadgeteer ribbon cable connected to a Talon on CAN Bus. More...
 
int SetFusedHeading (double angleDeg, int timeoutMs=0)
 Sets the Fused Heading to the specified value. More...
 
int AddFusedHeading (double angleDeg, int timeoutMs=0)
 Atomically add to the Fused Heading register. More...
 
int SetFusedHeadingToCompass (int timeoutMs=0)
 Sets the Fused Heading register to match the current compass value. More...
 
int SetTemperatureCompensationDisable (bool bTempCompDisable, int timeoutMs=0)
 Disable/Enable Temp compensation. More...
 
int SetCompassDeclination (double angleDegOffset, int timeoutMs=0)
 Set the declination for compass. More...
 
int SetCompassAngle (double angleDeg, int timeoutMs=0)
 Sets the compass angle. More...
 
int EnterCalibrationMode (CalibrationMode calMode, int timeoutMs=0)
 Enters the Calbration mode. More...
 
int GetGeneralStatus (PigeonIMU::GeneralStatus &statusToFill)
 Get the status of the current (or previousley complete) calibration. More...
 
PigeonState GetState ()
 Gets the current Pigeon state. More...
 
int GetAccelerometerAngles (double tiltAngles[3])
 Get Accelerometer tilt angles. More...
 
double GetFusedHeading (FusionStatus &status)
 Get the current Fusion Status (including fused heading) More...
 
double GetFusedHeading () const
 Gets the Fused Heading. More...
 
uint32_t GetResetCount ()
 
uint32_t GetResetFlags ()
 
ErrorCode ConfigSetCustomParam (int newValue, int paramIndex, int timeoutMs=0)
 Sets the value of a custom parameter. More...
 
int ConfigGetCustomParam (int paramIndex, int timeoutMs=0)
 Gets the value of a custom parameter. More...
 
ErrorCode SetStatusFramePeriod (PigeonIMU_StatusFrame statusFrame, uint8_t periodMs, int timeoutMs=0)
 Sets the period of the given status frame. More...
 
int GetStatusFramePeriod (PigeonIMU_StatusFrame frame, int timeoutMs=0)
 Gets the period of the given status frame. More...
 
ErrorCode SetControlFramePeriod (PigeonIMU_ControlFrame frame, int periodMs)
 Sets the period of the given control frame. More...
 
int GetFirmwareVersion ()
 Gets the firmware version of the device. More...
 
ErrorCode GetFaults (PigeonIMU_Faults &toFill)
 Gets the fault status. More...
 
ErrorCode GetStickyFaults (PigeonIMU_StickyFaults &toFill)
 Gets the sticky fault status. More...
 
ErrorCode ClearStickyFaults (int timeoutMs=0)
 Clears the Sticky Faults. More...
 
virtual ctre::phoenix::ErrorCode ConfigAllSettings (const PigeonIMUConfiguration &allConfigs, int timeoutMs=50)
 Configures all persistent settings. More...
 
virtual void GetAllConfigs (PigeonIMUConfiguration &allConfigs, int timeoutMs=50)
 Gets all persistant settings. More...
 
virtual ErrorCode ConfigFactoryDefault (int timeoutMs=50)
 Configures all persistent settings to defaults. More...
 
- Public Member Functions inherited from ctre::phoenix::sensors::BasePigeon
 BasePigeon (int deviceNumber, std::string const &version, std::string const &canbus="")
 Create a Pigeon object that communicates with Pigeon on CAN Bus. More...
 
 ~BasePigeon ()
 
int SetYaw (double angleDeg, int timeoutMs=0)
 Sets the Yaw register to the specified value. More...
 
int AddYaw (double angleDeg, int timeoutMs=0)
 Atomically add to the Yaw register. More...
 
int SetYawToCompass (int timeoutMs=0)
 Sets the Yaw register to match the current compass value. More...
 
int SetAccumZAngle (double angleDeg, int timeoutMs=0)
 Sets the AccumZAngle. More...
 
ErrorCode GetLastError () const
 Call GetLastError() generated by this object. More...
 
ErrorCode Get6dQuaternion (double wxyz[4]) const
 Get 6d Quaternion data. More...
 
ErrorCode GetYawPitchRoll (double ypr[3]) const
 Get Yaw, Pitch, and Roll data. More...
 
double GetYaw () const
 Get the yaw from the Pigeon. More...
 
double GetPitch () const
 Get the pitch from the Pigeon. More...
 
double GetRoll () const
 Get the roll from the Pigeon. More...
 
int GetAccumGyro (double xyz_deg[3]) const
 Get AccumGyro data. More...
 
double GetAbsoluteCompassHeading () const
 Get the absolute compass heading. More...
 
double GetCompassHeading () const
 Get the continuous compass heading. More...
 
double GetCompassFieldStrength () const
 Gets the compass' measured magnetic field strength. More...
 
double GetTemp () const
 Gets the temperature of the pigeon. More...
 
uint32_t GetUpTime () const
 Gets the current Pigeon uptime. More...
 
int GetRawMagnetometer (int16_t rm_xyz[3]) const
 Get Raw Magnetometer data. More...
 
int GetBiasedMagnetometer (int16_t bm_xyz[3]) const
 Get Biased Magnetometer data. More...
 
int GetBiasedAccelerometer (int16_t ba_xyz[3]) const
 Get Biased Accelerometer data. More...
 
int GetRawGyro (double xyz_dps[3]) const
 Get Raw Gyro data. More...
 
uint32_t GetResetCount () const
 
uint32_t GetResetFlags () const
 
uint32_t GetFirmVers () const
 
bool HasResetOccurred () const
 
ErrorCode ConfigSetCustomParam (int newValue, int paramIndex, int timeoutMs=0)
 Sets the value of a custom parameter. More...
 
int ConfigGetCustomParam (int paramIndex, int timeoutMs=0)
 Gets the value of a custom parameter. More...
 
ErrorCode ConfigSetParameter (ParamEnum param, double value, uint8_t subValue, int ordinal, int timeoutMs=0)
 Sets a parameter. More...
 
double ConfigGetParameter (ctre::phoenix::ParamEnum param, int ordinal, int timeoutMs=0)
 Gets a parameter. More...
 
ErrorCode ConfigGetParameter (ParamEnum param, int32_t valueToSend, int32_t &valueReceived, uint8_t &subValue, int32_t ordinal, int32_t timeoutMs)
 Gets a parameter by passing an int by reference. More...
 
ErrorCode SetStatusFramePeriod (PigeonIMU_StatusFrame statusFrame, uint8_t periodMs, int timeoutMs=0)
 Sets the period of the given status frame. More...
 
int GetStatusFramePeriod (PigeonIMU_StatusFrame frame, int timeoutMs=0)
 Gets the period of the given status frame. More...
 
ErrorCode SetControlFramePeriod (PigeonIMU_ControlFrame frame, int periodMs)
 Sets the period of the given control frame. More...
 
int GetFirmwareVersion ()
 Gets the firmware version of the device. More...
 
ErrorCode ClearStickyFaults (int timeoutMs=0)
 Clears the Sticky Faults. More...
 
void * GetLowLevelHandle () const
 
virtual ctre::phoenix::ErrorCode ConfigAllSettings (const BasePigeonConfiguration &allConfigs, int timeoutMs=50)
 Configures all persistent settings. More...
 
virtual void GetAllConfigs (BasePigeonConfiguration &allConfigs, int timeoutMs=50)
 Gets all persistant settings. More...
 
virtual ErrorCode ConfigFactoryDefault (int timeoutMs=50)
 Configures all persistent settings to defaults. More...
 
virtual BasePigeonSimCollectionGetSimCollection ()
 
- Public Member Functions inherited from ctre::phoenix::CANBusAddressable
 CANBusAddressable (int deviceNumber)
 Constructor for a CANBusAddressable device. More...
 
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
}
 Various calibration modes supported by Pigeon. More...
 
enum  PigeonState { NoComm , Initializing , Ready , UserCalibration }
 Overall state of the Pigeon. More...
 
- Static Public Member Functions inherited from ctre::phoenix::sensors::PigeonIMU
static std::string ToString (PigeonIMU::PigeonState state)
 Gets the string representation of a PigeonState. More...
 
static std::string ToString (CalibrationMode cm)
 Gets the string representation of a CalibrationMode. More...
 
- Static Public Member Functions inherited from ctre::phoenix::sensors::BasePigeon
static void DestroyAllBasePigeons ()
 Destructs all pigeon objects. More...
 
- Protected Member Functions inherited from ctre::phoenix::sensors::BasePigeon
 BasePigeon (ctre::phoenix::motorcontrol::can::TalonSRX &talonSrx)
 

Constructor & Destructor Documentation

◆ WPI_PigeonIMU() [1/4]

ctre::phoenix::sensors::WPI_PigeonIMU::WPI_PigeonIMU ( int  deviceNumber)

Construtor for WPI_PigeonIMU.

Parameters
deviceNumberCAN Device ID of the Pigeon IMU.

◆ WPI_PigeonIMU() [2/4]

ctre::phoenix::sensors::WPI_PigeonIMU::WPI_PigeonIMU ( ctre::phoenix::motorcontrol::can::TalonSRX talon)

Construtor for WPI_PigeonIMU.

Parameters
talonThe Talon SRX ribbon-cabled to Pigeon.

◆ ~WPI_PigeonIMU()

ctre::phoenix::sensors::WPI_PigeonIMU::~WPI_PigeonIMU ( )

◆ WPI_PigeonIMU() [3/4]

ctre::phoenix::sensors::WPI_PigeonIMU::WPI_PigeonIMU ( )
delete

◆ WPI_PigeonIMU() [4/4]

ctre::phoenix::sensors::WPI_PigeonIMU::WPI_PigeonIMU ( WPI_PigeonIMU const &  )
delete

Member Function Documentation

◆ GetAngle()

double ctre::phoenix::sensors::WPI_PigeonIMU::GetAngle ( ) const

Returns the heading of the robot in degrees.

The angle increases as the Pigeon IMU turns clockwise when looked at from the top. This follows the NED axis convention.

The angle is continuous; that is, it will continue from 360 to 361 degrees. This allows for 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.

Returns
The current heading of the robot in degrees

◆ GetRate()

double ctre::phoenix::sensors::WPI_PigeonIMU::GetRate ( ) const

Returns the rate of rotation of the Pigeon IMU.

The rate is positive as the Pigeon IMU turns clockwise when looked at from the top.

Returns
The current rate in degrees per second

◆ GetRotation2d()

frc::Rotation2d ctre::phoenix::sensors::WPI_PigeonIMU::GetRotation2d ( ) const

Returns the heading of the robot as a frc::Rotation2d.

The angle increases as the Pigeon IMU turns counterclockwise when looked at from the top. This follows the NWU axis convention.

The angle is continuous; that is, it will continue from 360 to 361 degrees. This allows for 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.

Returns
The current heading of the robot as a frc::Rotation2d

◆ InitSendable()

void ctre::phoenix::sensors::WPI_PigeonIMU::InitSendable ( wpi::SendableBuilder &  builder)
override

◆ operator=()

WPI_PigeonIMU & ctre::phoenix::sensors::WPI_PigeonIMU::operator= ( WPI_PigeonIMU const &  )
delete

◆ Reset()

void ctre::phoenix::sensors::WPI_PigeonIMU::Reset ( )

Resets the Pigeon IMU 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.


The documentation for this class was generated from the following file: