|
CTRE Phoenix C++ 5.35.1
|
Pigeon IMU Class. More...
#include <ctre/phoenix/sensors/BasePigeon.h>
Public Member Functions | |
| BasePigeon (int deviceNumber, std::string const &version, std::string const &canbus="") | |
| Create a Pigeon object that communicates with Pigeon on CAN Bus. | |
| ~BasePigeon () | |
| int | SetYaw (double angleDeg, int timeoutMs=0) |
| Sets the Yaw register to the specified value. | |
| int | AddYaw (double angleDeg, int timeoutMs=0) |
| Atomically add to the Yaw register. | |
| int | SetYawToCompass (int timeoutMs=0) |
| Sets the Yaw register to match the current compass value. | |
| int | SetAccumZAngle (double angleDeg, int timeoutMs=0) |
| Sets the AccumZAngle. | |
| ErrorCode | GetLastError () const |
| Call GetLastError() generated by this object. | |
| ErrorCode | Get6dQuaternion (double wxyz[4]) const |
| Get 6d Quaternion data. | |
| ErrorCode | GetYawPitchRoll (double ypr[3]) const |
| Get Yaw, Pitch, and Roll data. | |
| double | GetYaw () const |
| Get the yaw from the Pigeon. | |
| double | GetPitch () const |
| Get the pitch from the Pigeon. | |
| double | GetRoll () const |
| Get the roll from the Pigeon. | |
| int | GetAccumGyro (double xyz_deg[3]) const |
| Get AccumGyro data. | |
| double | GetAbsoluteCompassHeading () const |
| Get the absolute compass heading. | |
| double | GetCompassHeading () const |
| Get the continuous compass heading. | |
| double | GetCompassFieldStrength () const |
| Gets the compass' measured magnetic field strength. | |
| double | GetTemp () const |
| Gets the temperature of the pigeon. | |
| uint32_t | GetUpTime () const |
| Gets the current Pigeon uptime. | |
| int | GetRawMagnetometer (int16_t rm_xyz[3]) const |
| Get Raw Magnetometer data. | |
| int | GetBiasedMagnetometer (int16_t bm_xyz[3]) const |
| Get Biased Magnetometer data. | |
| int | GetBiasedAccelerometer (int16_t ba_xyz[3]) const |
| Get Biased Accelerometer data. | |
| int | GetRawGyro (double xyz_dps[3]) const |
| Get Raw Gyro data. | |
| 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. | |
| int | ConfigGetCustomParam (int paramIndex, int timeoutMs=0) |
| Gets the value of a custom parameter. | |
| ErrorCode | ConfigSetParameter (ParamEnum param, double value, uint8_t subValue, int ordinal, int timeoutMs=0) |
| Sets a parameter. | |
| double | ConfigGetParameter (ctre::phoenix::ParamEnum param, int ordinal, int timeoutMs=0) |
| Gets a parameter. | |
| 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. | |
| ErrorCode | SetStatusFramePeriod (PigeonIMU_StatusFrame statusFrame, uint8_t periodMs, int timeoutMs=0) |
| Sets the period of the given status frame. | |
| int | GetStatusFramePeriod (PigeonIMU_StatusFrame frame, int timeoutMs=0) |
| Gets the period of the given status frame. | |
| ErrorCode | SetControlFramePeriod (PigeonIMU_ControlFrame frame, int periodMs) |
| Sets the period of the given control frame. | |
| int | GetFirmwareVersion () |
| Gets the firmware version of the device. | |
| ErrorCode | ClearStickyFaults (int timeoutMs=0) |
| Clears the Sticky Faults. | |
| void * | GetLowLevelHandle () const |
| virtual ctre::phoenix::ErrorCode | ConfigAllSettings (const BasePigeonConfiguration &allConfigs, int timeoutMs=50) |
| Configures all persistent settings. | |
| virtual void | GetAllConfigs (BasePigeonConfiguration &allConfigs, int timeoutMs=50) |
| Gets all persistant settings. | |
| virtual ErrorCode | ConfigFactoryDefault (int timeoutMs=50) |
| Configures all persistent settings to defaults. | |
| virtual BasePigeonSimCollection & | GetSimCollection () |
Public Member Functions inherited from ctre::phoenix::CANBusAddressable | |
| CANBusAddressable (int deviceNumber) | |
| Constructor for a CANBusAddressable device. | |
| int | GetDeviceNumber () |
Static Public Member Functions | |
| static void | DestroyAllBasePigeons () |
| Destructs all pigeon objects. | |
Protected Member Functions | |
| BasePigeon (ctre::phoenix::motorcontrol::can::TalonSRX &talonSrx) | |
Pigeon IMU Class.
Class supports communicating over CANbus and over ribbon-cable (CAN Talon SRX).
| 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.
| deviceNumber | CAN Device Id of Pigeon [0,62] |
| canbus | Name of the CANbus; can be a SocketCAN interface (on Linux), or a CANivore device name or serial number |
| ctre::phoenix::sensors::BasePigeon::~BasePigeon | ( | ) |
|
protected |
| int ctre::phoenix::sensors::BasePigeon::AddYaw | ( | double | angleDeg, |
| int | timeoutMs = 0 ) |
Atomically add to the Yaw register.
| angleDeg | Degrees to add to the Yaw register. |
| timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
| ErrorCode ctre::phoenix::sensors::BasePigeon::ClearStickyFaults | ( | int | timeoutMs = 0 | ) |
Clears the Sticky Faults.
|
virtual |
Configures all persistent settings.
| allConfigs | Object with all of the persistant settings |
| timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
|
virtual |
Configures all persistent settings to defaults.
| timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
Reimplemented in ctre::phoenix::sensors::PigeonIMU.
| int ctre::phoenix::sensors::BasePigeon::ConfigGetCustomParam | ( | int | paramIndex, |
| int | timeoutMs = 0 ) |
Gets the value of a custom parameter.
This is for arbitrary use.
Sometimes it is necessary to save calibration/declination/offset information in the device. Particularly if the device is part of a subsystem that can be replaced.
| paramIndex | Index of custom parameter. [0-1] |
| timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
| double ctre::phoenix::sensors::BasePigeon::ConfigGetParameter | ( | ctre::phoenix::ParamEnum | param, |
| int | ordinal, | ||
| int | timeoutMs = 0 ) |
Gets a parameter.
Generally this is not used. This can be utilized in
| param | Parameter enumeration. |
| ordinal | Ordinal of parameter. |
| timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
| ErrorCode ctre::phoenix::sensors::BasePigeon::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.
| param | Parameter enumeration |
| valueToSend | Value to send to parameter |
| valueReceived | Reference to integer to receive |
| subValue | SubValue of parameter |
| ordinal | Ordinal of parameter |
| timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
| ErrorCode ctre::phoenix::sensors::BasePigeon::ConfigSetCustomParam | ( | int | newValue, |
| int | paramIndex, | ||
| int | timeoutMs = 0 ) |
Sets the value of a custom parameter.
This is for arbitrary use.
Sometimes it is necessary to save calibration/declination/offset information in the device. Particularly if the device is part of a subsystem that can be replaced.
| newValue | Value for custom parameter. |
| paramIndex | Index of custom parameter. [0-1] |
| timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
| ErrorCode ctre::phoenix::sensors::BasePigeon::ConfigSetParameter | ( | ParamEnum | param, |
| double | value, | ||
| uint8_t | subValue, | ||
| int | ordinal, | ||
| int | timeoutMs = 0 ) |
Sets a parameter.
Generally this is not used. This can be utilized in
| param | Parameter enumeration. |
| value | Value of parameter. |
| subValue | Subvalue for parameter. Maximum value of 255. |
| ordinal | Ordinal of parameter. |
| timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
|
static |
Destructs all pigeon objects.
| ErrorCode ctre::phoenix::sensors::BasePigeon::Get6dQuaternion | ( | double | wxyz[4] | ) | const |
Get 6d Quaternion data.
| wxyz | Array to fill with quaternion data w[0], x[1], y[2], z[3] |
| double ctre::phoenix::sensors::BasePigeon::GetAbsoluteCompassHeading | ( | ) | const |
Get the absolute compass heading.
| int ctre::phoenix::sensors::BasePigeon::GetAccumGyro | ( | double | xyz_deg[3] | ) | const |
Get AccumGyro data.
AccumGyro is the integrated gyro value on each axis.
| xyz_deg | Array to fill with x[0], y[1], and z[2] AccumGyro data |
|
virtual |
Gets all persistant settings.
| allConfigs | Object with all of the persistant settings |
| timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
| int ctre::phoenix::sensors::BasePigeon::GetBiasedAccelerometer | ( | int16_t | ba_xyz[3] | ) | const |
Get Biased Accelerometer data.
| ba_xyz | Array to fill with x[0], y[1], and z[2] data. These are in fixed point notation Q2.14. eg. 16384 = 1G |
| int ctre::phoenix::sensors::BasePigeon::GetBiasedMagnetometer | ( | int16_t | bm_xyz[3] | ) | const |
Get Biased Magnetometer data.
| bm_xyz | Array to fill with x[0], y[1], and z[2] data Number is equal to 0.6 microTeslas per unit. |
| double ctre::phoenix::sensors::BasePigeon::GetCompassFieldStrength | ( | ) | const |
Gets the compass' measured magnetic field strength.
| double ctre::phoenix::sensors::BasePigeon::GetCompassHeading | ( | ) | const |
Get the continuous compass heading.
| uint32_t ctre::phoenix::sensors::BasePigeon::GetFirmVers | ( | ) | const |
| int ctre::phoenix::sensors::BasePigeon::GetFirmwareVersion | ( | ) |
Gets the firmware version of the device.
| ErrorCode ctre::phoenix::sensors::BasePigeon::GetLastError | ( | ) | const |
Call GetLastError() generated by this object.
Not all functions return an error code but can potentially report errors.
This function can be used to retrieve those error codes.
|
inline |
| double ctre::phoenix::sensors::BasePigeon::GetPitch | ( | ) | const |
Get the pitch from the Pigeon.
| int ctre::phoenix::sensors::BasePigeon::GetRawGyro | ( | double | xyz_dps[3] | ) | const |
Get Raw Gyro data.
| xyz_dps | Array to fill with x[0], y[1], and z[2] data in degrees per second. |
| int ctre::phoenix::sensors::BasePigeon::GetRawMagnetometer | ( | int16_t | rm_xyz[3] | ) | const |
Get Raw Magnetometer data.
| rm_xyz | Array to fill with x[0], y[1], and z[2] data Number is equal to 0.6 microTeslas per unit. |
| uint32_t ctre::phoenix::sensors::BasePigeon::GetResetCount | ( | ) | const |
| uint32_t ctre::phoenix::sensors::BasePigeon::GetResetFlags | ( | ) | const |
| double ctre::phoenix::sensors::BasePigeon::GetRoll | ( | ) | const |
Get the roll from the Pigeon.
|
virtual |
| int ctre::phoenix::sensors::BasePigeon::GetStatusFramePeriod | ( | PigeonIMU_StatusFrame | frame, |
| int | timeoutMs = 0 ) |
Gets the period of the given status frame.
| frame | Frame to get the period of. |
| timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
| double ctre::phoenix::sensors::BasePigeon::GetTemp | ( | ) | const |
Gets the temperature of the pigeon.
| uint32_t ctre::phoenix::sensors::BasePigeon::GetUpTime | ( | ) | const |
Gets the current Pigeon uptime.
| double ctre::phoenix::sensors::BasePigeon::GetYaw | ( | ) | const |
Get the yaw from the Pigeon.
| ErrorCode ctre::phoenix::sensors::BasePigeon::GetYawPitchRoll | ( | double | ypr[3] | ) | const |
Get Yaw, Pitch, and Roll data.
| ypr | Array to fill with yaw[0], pitch[1], and roll[2] data. Yaw is within [-368,640, +368,640] degrees. Pitch is within [-90,+90] degrees. Roll is within [-90,+90] degrees. |
| bool ctre::phoenix::sensors::BasePigeon::HasResetOccurred | ( | ) | const |
| int ctre::phoenix::sensors::BasePigeon::SetAccumZAngle | ( | double | angleDeg, |
| int | timeoutMs = 0 ) |
Sets the AccumZAngle.
| angleDeg | Degrees to set AccumZAngle to. |
| timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
| ErrorCode ctre::phoenix::sensors::BasePigeon::SetControlFramePeriod | ( | PigeonIMU_ControlFrame | frame, |
| int | periodMs ) |
Sets the period of the given control frame.
| frame | Frame whose period is to be changed. |
| periodMs | Period in ms for the given frame. |
| ErrorCode ctre::phoenix::sensors::BasePigeon::SetStatusFramePeriod | ( | PigeonIMU_StatusFrame | statusFrame, |
| uint8_t | periodMs, | ||
| int | timeoutMs = 0 ) |
Sets the period of the given status frame.
| statusFrame | Frame whose period is to be changed. |
| periodMs | Period in ms for the given frame. |
| timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
| int ctre::phoenix::sensors::BasePigeon::SetYaw | ( | double | angleDeg, |
| int | timeoutMs = 0 ) |
Sets the Yaw register to the specified value.
| angleDeg | Degree of Yaw [+/- 368,640 degrees] |
| timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |
| int ctre::phoenix::sensors::BasePigeon::SetYawToCompass | ( | int | timeoutMs = 0 | ) |
Sets the Yaw register to match the current compass value.
| timeoutMs | Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed. |