CTRE_Phoenix 5.20.2
|
Inherited by com.ctre.phoenix.sensors.Pigeon2, and com.ctre.phoenix.sensors.PigeonIMU.
Public Member Functions | |
BasePigeon (int deviceNumber, String version, String canbus) | |
BasePigeon (int deviceNumber, String version) | |
ErrorCode | DestroyObject () |
BasePigeonSimCollection | getSimCollection () |
ErrorCode | setYaw (double angleDeg, int timeoutMs) |
ErrorCode | setYaw (double angleDeg) |
ErrorCode | addYaw (double angleDeg, int timeoutMs) |
ErrorCode | addYaw (double angleDeg) |
ErrorCode | setYawToCompass (int timeoutMs) |
ErrorCode | setYawToCompass () |
ErrorCode | setAccumZAngle (double angleDeg, int timeoutMs) |
ErrorCode | setAccumZAngle (double angleDeg) |
ErrorCode | getLastError () |
ErrorCode | get6dQuaternion (double[] wxyz) |
ErrorCode | getYawPitchRoll (double[] ypr_deg) |
double | getYaw () |
double | getPitch () |
double | getRoll () |
ErrorCode | getAccumGyro (double[] xyz_deg) |
double | getAbsoluteCompassHeading () |
double | getCompassHeading () |
double | getCompassFieldStrength () |
double | getTemp () |
int | getUpTime () |
ErrorCode | getRawMagnetometer (short[] rm_xyz) |
ErrorCode | getBiasedMagnetometer (short[] bm_xyz) |
ErrorCode | getBiasedAccelerometer (short[] ba_xyz) |
ErrorCode | getRawGyro (double[] xyz_dps) |
int | getResetCount () |
int | getResetFlags () |
int | getFirmwareVersion () |
boolean | hasResetOccurred () |
ErrorCode | configSetCustomParam (int newValue, int paramIndex, int timeoutMs) |
ErrorCode | configSetCustomParam (int newValue, int paramIndex) |
int | configGetCustomParam (int paramIndex, int timoutMs) |
int | configGetCustomParam (int paramIndex) |
ErrorCode | configSetParameter (ParamEnum param, double value, int subValue, int ordinal, int timeoutMs) |
ErrorCode | configSetParameter (ParamEnum param, double value, int subValue, int ordinal) |
ErrorCode | configSetParameter (int param, double value, int subValue, int ordinal, int timeoutMs) |
ErrorCode | configSetParameter (int param, double value, int subValue, int ordinal) |
double | configGetParameter (ParamEnum param, int ordinal, int timeoutMs) |
double | configGetParameter (ParamEnum param, int ordinal) |
double | configGetParameter (int param, int ordinal, int timeoutMs) |
double | configGetParameter (int param, int ordinal) |
ErrorCode | setStatusFramePeriod (PigeonIMU_StatusFrame statusFrame, int periodMs, int timeoutMs) |
ErrorCode | setStatusFramePeriod (PigeonIMU_StatusFrame statusFrame, int periodMs) |
ErrorCode | setStatusFramePeriod (int statusFrame, int periodMs, int timeoutMs) |
ErrorCode | setStatusFramePeriod (int statusFrame, int periodMs) |
int | getStatusFramePeriod (PigeonIMU_StatusFrame frame, int timeoutMs) |
int | getStatusFramePeriod (PigeonIMU_StatusFrame frame) |
ErrorCode | setControlFramePeriod (PigeonIMU_ControlFrame frame, int periodMs) |
ErrorCode | setControlFramePeriod (int frame, int periodMs) |
ErrorCode | clearStickyFaults (int timeoutMs) |
ErrorCode | clearStickyFaults () |
int | getDeviceID () |
ErrorCode | configAllSettings (PigeonIMUConfiguration allConfigs, int timeoutMs) |
ErrorCode | configAllSettings (PigeonIMUConfiguration allConfigs) |
void | getAllConfigs (PigeonIMUConfiguration allConfigs, int timeoutMs) |
void | getAllConfigs (PigeonIMUConfiguration allConfigs) |
ErrorCode | configFactoryDefault (int timeoutMs) |
ErrorCode | configFactoryDefault () |
long | getHandle () |
Protected Member Functions | |
BasePigeon (long handle) | |
Pigeon IMU Class. Class supports communicating over CANbus and over ribbon-cable (CAN Talon SRX).
|
inline |
Create a Pigeon object that communicates with Pigeon on CAN Bus.
deviceNumber | CAN Device Id of Pigeon [0,62] |
version | Version of the PigeonIMU |
canbus | Name of the CANbus; can be a SocketCAN interface (on Linux), or a CANivore device name or serial number |
|
inline |
Create a Pigeon object that communicates with Pigeon on CAN Bus.
deviceNumber | CAN Device Id of Pigeon [0,62] |
version | Version of the PigeonIMU |
|
inline |
Atomically add to the Yaw register.
angleDeg | Degrees to add to the Yaw register. |
|
inline |
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. |
|
inline |
Clears the Sticky Faults
|
inline |
Clears the Sticky Faults
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. |
|
inline |
Configures all persistent settings (overloaded so timeoutMs is 50 ms).
allConfigs | Object with all of the persistant settings |
Reimplemented in com.ctre.phoenix.sensors.PigeonIMU.
|
inline |
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. |
Reimplemented in com.ctre.phoenix.sensors.PigeonIMU.
|
inline |
Configures all persistent settings to defaults (overloaded so timeoutMs is 50 ms).
Reimplemented in com.ctre.phoenix.sensors.PigeonIMU.
|
inline |
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 com.ctre.phoenix.sensors.PigeonIMU.
|
inline |
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] |
|
inline |
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] |
timoutMs | 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. |
|
inline |
Gets a parameter.
param | Parameter enumeration. |
ordinal | Ordinal of parameter. |
|
inline |
Gets a parameter.
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. |
|
inline |
Gets a parameter. Generally this is not used. This can be utilized in
param | Parameter enumeration. |
ordinal | Ordinal of parameter. |
|
inline |
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. |
|
inline |
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] |
|
inline |
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. |
|
inline |
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. |
|
inline |
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. |
|
inline |
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. |
|
inline |
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. |
|
inline |
Destructor for Pigeon
|
inline |
Get 6d Quaternion data.
wxyz | Array to fill with quaternion data w[0], x[1], y[2], z[3] |
|
inline |
Get the absolute compass heading.
|
inline |
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 |
|
inline |
Gets all persistant settings (overloaded so timeoutMs is 50 ms).
allConfigs | Object with all of the persistant settings |
Reimplemented in com.ctre.phoenix.sensors.PigeonIMU.
|
inline |
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. |
Reimplemented in com.ctre.phoenix.sensors.PigeonIMU.
|
inline |
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 |
|
inline |
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. |
|
inline |
Gets the compass' measured magnetic field strength.
|
inline |
Get the continuous compass heading.
|
inline |
|
inline |
Gets the firmware version of the device.
|
inline |
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 |
Get the pitch from the Pigeon
|
inline |
Get Raw Gyro data.
xyz_dps | Array to fill with x[0], y[1], and z[2] data in degrees per second. |
|
inline |
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. |
|
inline |
|
inline |
|
inline |
Get the roll from the Pigeon
|
inline |
|
inline |
Gets the period of the given status frame.
frame | Frame to get the period of. |
|
inline |
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. |
|
inline |
Gets the temperature of the pigeon.
|
inline |
Gets the current Pigeon uptime.
|
inline |
Get the yaw from the Pigeon
|
inline |
Get Yaw, Pitch, and Roll data.
ypr_deg | 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. |
|
inline |
|
inline |
Sets the AccumZAngle.
angleDeg | Degrees to set AccumZAngle to. |
|
inline |
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. |
|
inline |
Sets the period of the given control frame.
frame | Frame whose period is to be changed. |
periodMs | Period in ms for the given frame. |
|
inline |
Sets the period of the given control frame.
frame | Frame whose period is to be changed. |
periodMs | Period in ms for the given frame. |
|
inline |
Sets the period of the given status frame.
statusFrame | Frame whose period is to be changed. |
periodMs | Period in ms for the given frame. |
|
inline |
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. |
|
inline |
Sets the period of the given status frame.
statusFrame | Frame whose period is to be changed. |
periodMs | Period in ms for the given frame. |
|
inline |
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. |
|
inline |
Sets the Yaw register to the specified value.
angleDeg | New yaw in degrees [+/- 368,640 degrees] |
|
inline |
Sets the Yaw register to the specified value.
angleDeg | New yaw in degrees [+/- 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. |
|
inline |
Sets the Yaw register to match the current compass value.
|
inline |
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. |