Package com.ctre.phoenix.sensors
Class BasePigeon
java.lang.Object
com.ctre.phoenix.sensors.BasePigeon
Pigeon IMU Class. Class supports communicating over CANbus and over
ribbon-cable (CAN Talon SRX).
-
Constructor Summary
ModifierConstructorDescriptionBasePigeon
(int deviceNumber, String version) Create a Pigeon object that communicates with Pigeon on CAN Bus.BasePigeon
(int deviceNumber, String version, String canbus) Create a Pigeon object that communicates with Pigeon on CAN Bus.protected
BasePigeon
(long handle) -
Method Summary
Modifier and TypeMethodDescriptionaddYaw
(double angleDeg) Atomically add to the Yaw register.addYaw
(double angleDeg, int timeoutMs) Atomically add to the Yaw register.Clears the Sticky FaultsclearStickyFaults
(int timeoutMs) Clears the Sticky FaultsconfigAllSettings
(PigeonIMUConfiguration allConfigs) Configures all persistent settings (overloaded so timeoutMs is 50 ms).configAllSettings
(PigeonIMUConfiguration allConfigs, int timeoutMs) Configures all persistent settings.Configures all persistent settings to defaults (overloaded so timeoutMs is 50 ms).configFactoryDefault
(int timeoutMs) Configures all persistent settings to defaults.int
configGetCustomParam
(int paramIndex) Gets the value of a custom parameter.int
configGetCustomParam
(int paramIndex, int timoutMs) Gets the value of a custom parameter.double
configGetParameter
(int param, int ordinal) Gets a parameter.double
configGetParameter
(int param, int ordinal, int timeoutMs) Gets a parameter.double
configGetParameter
(ParamEnum param, int ordinal) Gets a parameter.double
configGetParameter
(ParamEnum param, int ordinal, int timeoutMs) Gets a parameter.configSetCustomParam
(int newValue, int paramIndex) Sets the value of a custom parameter.configSetCustomParam
(int newValue, int paramIndex, int timeoutMs) Sets the value of a custom parameter.configSetParameter
(int param, double value, int subValue, int ordinal) Sets a parameter.configSetParameter
(int param, double value, int subValue, int ordinal, int timeoutMs) Sets a parameter.configSetParameter
(ParamEnum param, double value, int subValue, int ordinal) Sets a parameter.configSetParameter
(ParamEnum param, double value, int subValue, int ordinal, int timeoutMs) Sets a parameter.Destructor for Pigeonget6dQuaternion
(double[] wxyz) Get 6d Quaternion data.double
Get the absolute compass heading.getAccumGyro
(double[] xyz_deg) Get AccumGyro data.void
getAllConfigs
(PigeonIMUConfiguration allConfigs) Gets all persistant settings (overloaded so timeoutMs is 50 ms).void
getAllConfigs
(PigeonIMUConfiguration allConfigs, int timeoutMs) Gets all persistant settings.getBiasedAccelerometer
(short[] ba_xyz) Get Biased Accelerometer data.getBiasedMagnetometer
(short[] bm_xyz) Get Biased Magnetometer data.double
Gets the compass' measured magnetic field strength.double
Get the continuous compass heading.int
int
Gets the firmware version of the device.long
Call GetLastError() generated by this object.double
getPitch()
Get the pitch from the PigeongetRawGyro
(double[] xyz_dps) Get Raw Gyro data.getRawMagnetometer
(short[] rm_xyz) Get Raw Magnetometer data.int
int
double
getRoll()
Get the roll from the Pigeonint
Gets the period of the given status frame.int
getStatusFramePeriod
(PigeonIMU_StatusFrame frame, int timeoutMs) Gets the period of the given status frame.double
getTemp()
Gets the temperature of the pigeon.int
Gets the current Pigeon uptime.double
getYaw()
Get the yaw from the PigeongetYawPitchRoll
(double[] ypr_deg) Get Yaw, Pitch, and Roll data.boolean
setAccumZAngle
(double angleDeg) Sets the AccumZAngle.setAccumZAngle
(double angleDeg, int timeoutMs) Sets the AccumZAngle.setControlFramePeriod
(int frame, int periodMs) Sets the period of the given control frame.setControlFramePeriod
(PigeonIMU_ControlFrame frame, int periodMs) Sets the period of the given control frame.setStatusFramePeriod
(int statusFrame, int periodMs) Sets the period of the given status frame.setStatusFramePeriod
(int statusFrame, int periodMs, int timeoutMs) Sets the period of the given status frame.setStatusFramePeriod
(PigeonIMU_StatusFrame statusFrame, int periodMs) Sets the period of the given status frame.setStatusFramePeriod
(PigeonIMU_StatusFrame statusFrame, int periodMs, int timeoutMs) Sets the period of the given status frame.setYaw
(double angleDeg) Sets the Yaw register to the specified value.setYaw
(double angleDeg, int timeoutMs) Sets the Yaw register to the specified value.Sets the Yaw register to match the current compass value.setYawToCompass
(int timeoutMs) Sets the Yaw register to match the current compass value.
-
Constructor Details
-
BasePigeon
Create a Pigeon object that communicates with Pigeon on CAN Bus.- Parameters:
deviceNumber
- CAN Device Id of Pigeon [0,62]version
- Version of the PigeonIMUcanbus
- Name of the CANbus; can be a SocketCAN interface (on Linux), or a CANivore device name or serial number
-
BasePigeon
Create a Pigeon object that communicates with Pigeon on CAN Bus.- Parameters:
deviceNumber
- CAN Device Id of Pigeon [0,62]version
- Version of the PigeonIMU
-
BasePigeon
-
-
Method Details
-
DestroyObject
Destructor for Pigeon- Returns:
- Error Code generated by function. 0 indicates no error.
-
getSimCollection
- Returns:
- object that can set simulation inputs.
-
setYaw
Sets the Yaw register to the specified value.- Parameters:
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.- Returns:
- Error Code generated by function. 0 indicates no error.
-
setYaw
Sets the Yaw register to the specified value.- Parameters:
angleDeg
- New yaw in degrees [+/- 368,640 degrees]- Returns:
- Error Code generated by function. 0 indicates no error.
-
addYaw
Atomically add to the Yaw register.- Parameters:
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.- Returns:
- Error Code generated by function. 0 indicates no error.
-
addYaw
Atomically add to the Yaw register.- Parameters:
angleDeg
- Degrees to add to the Yaw register.- Returns:
- Error Code generated by function. 0 indicates no error.
-
setYawToCompass
Sets the Yaw register to match the current compass value.- Parameters:
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.- Returns:
- Error Code generated by function. 0 indicates no error.
-
setYawToCompass
Sets the Yaw register to match the current compass value.- Returns:
- Error Code generated by function. 0 indicates no error.
-
setAccumZAngle
Sets the AccumZAngle.- Parameters:
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.- Returns:
- Error Code generated by function. 0 indicates no error.
-
setAccumZAngle
Sets the AccumZAngle.- Parameters:
angleDeg
- Degrees to set AccumZAngle to.- Returns:
- Error Code generated by function. 0 indicates no error.
-
getLastError
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.- Returns:
- The last ErrorCode generated.
-
get6dQuaternion
Get 6d Quaternion data.- Parameters:
wxyz
- Array to fill with quaternion data w[0], x[1], y[2], z[3]- Returns:
- The last ErrorCode generated.
-
getYawPitchRoll
Get Yaw, Pitch, and Roll data.- Parameters:
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.- Returns:
- The last ErrorCode generated.
-
getYaw
Get the yaw from the Pigeon- Returns:
- Yaw
-
getPitch
Get the pitch from the Pigeon- Returns:
- Pitch
-
getRoll
Get the roll from the Pigeon- Returns:
- Roll
-
getAccumGyro
Get AccumGyro data. AccumGyro is the integrated gyro value on each axis.- Parameters:
xyz_deg
- Array to fill with x[0], y[1], and z[2] AccumGyro data- Returns:
- The last ErrorCode generated.
-
getAbsoluteCompassHeading
Get the absolute compass heading.- Returns:
- compass heading [0,360) degrees.
-
getCompassHeading
Get the continuous compass heading.- Returns:
- continuous compass heading [-23040, 23040) degrees. Use SetCompassHeading to modify the wrap-around portion.
-
getCompassFieldStrength
Gets the compass' measured magnetic field strength.- Returns:
- field strength in Microteslas (uT).
-
getTemp
Gets the temperature of the pigeon.- Returns:
- Temperature in ('C)
-
getUpTime
Gets the current Pigeon uptime.- Returns:
- How long has Pigeon been running in whole seconds. Value caps at 255.
-
getRawMagnetometer
Get Raw Magnetometer data.- Parameters:
rm_xyz
- Array to fill with x[0], y[1], and z[2] data Number is equal to 0.6 microTeslas per unit.- Returns:
- The last ErrorCode generated.
-
getBiasedMagnetometer
Get Biased Magnetometer data.- Parameters:
bm_xyz
- Array to fill with x[0], y[1], and z[2] data Number is equal to 0.6 microTeslas per unit.- Returns:
- The last ErrorCode generated.
-
getBiasedAccelerometer
Get Biased Accelerometer data.- Parameters:
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- Returns:
- The last ErrorCode generated.
-
getRawGyro
Get Raw Gyro data.- Parameters:
xyz_dps
- Array to fill with x[0], y[1], and z[2] data in degrees per second.- Returns:
- The last ErrorCode generated.
-
getResetCount
- Returns:
- number of times Pigeon Reset
-
getResetFlags
- Returns:
- Reset flags for Pigeon
-
getFirmwareVersion
Gets the firmware version of the device.- Returns:
- param holds the firmware version of the device. Device must be powered cycled at least once.
-
hasResetOccurred
- Returns:
- true iff a reset has occurred since last call.
-
configSetCustomParam
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.- Parameters:
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.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configSetCustomParam
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.- Parameters:
newValue
- Value for custom parameter.paramIndex
- Index of custom parameter. [0-1]- Returns:
- Error Code generated by function. 0 indicates no error.
-
configGetCustomParam
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.- Parameters:
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.- Returns:
- Value of the custom param.
-
configGetCustomParam
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.- Parameters:
paramIndex
- Index of custom parameter. [0-1]- Returns:
- Value of the custom param.
-
configSetParameter
public ErrorCode configSetParameter(ParamEnum param, double value, int subValue, int ordinal, int timeoutMs) Sets a parameter. Generally this is not used. This can be utilized in - Using new features without updating API installation. - Errata workarounds to circumvent API implementation. - Allows for rapid testing / unit testing of firmware.- Parameters:
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.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configSetParameter
Sets a parameter. Generally this is not used. This can be utilized in - Using new features without updating API installation. - Errata workarounds to circumvent API implementation. - Allows for rapid testing / unit testing of firmware.- Parameters:
param
- Parameter enumeration.value
- Value of parameter.subValue
- Subvalue for parameter. Maximum value of 255.ordinal
- Ordinal of parameter.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configSetParameter
public ErrorCode configSetParameter(int param, double value, int subValue, int ordinal, int timeoutMs) Sets a parameter. Generally this is not used. This can be utilized in - Using new features without updating API installation. - Errata workarounds to circumvent API implementation. - Allows for rapid testing / unit testing of firmware.- Parameters:
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.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configSetParameter
Sets a parameter. Generally this is not used. This can be utilized in - Using new features without updating API installation. - Errata workarounds to circumvent API implementation. - Allows for rapid testing / unit testing of firmware.- Parameters:
param
- Parameter enumeration.value
- Value of parameter.subValue
- Subvalue for parameter. Maximum value of 255.ordinal
- Ordinal of parameter.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configGetParameter
Gets a parameter. Generally this is not used. This can be utilized in - Using new features without updating API installation. - Errata workarounds to circumvent API implementation. - Allows for rapid testing / unit testing of firmware.- Parameters:
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.- Returns:
- Value of parameter.
-
configGetParameter
Gets a parameter. Generally this is not used. This can be utilized in - Using new features without updating API installation. - Errata workarounds to circumvent API implementation. - Allows for rapid testing / unit testing of firmware.- Parameters:
param
- Parameter enumeration.ordinal
- Ordinal of parameter.- Returns:
- Value of parameter.
-
configGetParameter
Gets a parameter.- Parameters:
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.- Returns:
- Value of parameter.
-
configGetParameter
Gets a parameter.- Parameters:
param
- Parameter enumeration.ordinal
- Ordinal of parameter.- Returns:
- Value of parameter.
-
setStatusFramePeriod
public ErrorCode setStatusFramePeriod(PigeonIMU_StatusFrame statusFrame, int periodMs, int timeoutMs) Sets the period of the given status frame.- Parameters:
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.- Returns:
- Error Code generated by function. 0 indicates no error.
-
setStatusFramePeriod
Sets the period of the given status frame.- Parameters:
statusFrame
- Frame whose period is to be changed.periodMs
- Period in ms for the given frame.- Returns:
- Error Code generated by function. 0 indicates no error.
-
setStatusFramePeriod
Sets the period of the given status frame.- Parameters:
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.- Returns:
- Error Code generated by function. 0 indicates no error.
-
setStatusFramePeriod
Sets the period of the given status frame.- Parameters:
statusFrame
- Frame whose period is to be changed.periodMs
- Period in ms for the given frame.- Returns:
- Error Code generated by function. 0 indicates no error.
-
getStatusFramePeriod
Gets the period of the given status frame.- Parameters:
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.- Returns:
- Period of the given status frame.
-
getStatusFramePeriod
Gets the period of the given status frame.- Parameters:
frame
- Frame to get the period of.- Returns:
- Period of the given status frame.
-
setControlFramePeriod
Sets the period of the given control frame.- Parameters:
frame
- Frame whose period is to be changed.periodMs
- Period in ms for the given frame.- Returns:
- Error Code generated by function. 0 indicates no error.
-
setControlFramePeriod
Sets the period of the given control frame.- Parameters:
frame
- Frame whose period is to be changed.periodMs
- Period in ms for the given frame.- Returns:
- Error Code generated by function. 0 indicates no error.
-
clearStickyFaults
Clears the Sticky Faults- Parameters:
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.- Returns:
- Error Code generated by function. 0 indicates no error.
-
clearStickyFaults
Clears the Sticky Faults- Returns:
- Error Code generated by function. 0 indicates no error.
-
getDeviceID
- Returns:
- The Device Number
-
configAllSettings
Configures all persistent settings.- Parameters:
allConfigs
- Object with all of the persistant settingstimeoutMs
- 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.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configAllSettings
Configures all persistent settings (overloaded so timeoutMs is 50 ms).- Parameters:
allConfigs
- Object with all of the persistant settings- Returns:
- Error Code generated by function. 0 indicates no error.
-
getAllConfigs
Gets all persistant settings.- Parameters:
allConfigs
- Object with all of the persistant settingstimeoutMs
- 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.
-
getAllConfigs
Gets all persistant settings (overloaded so timeoutMs is 50 ms).- Parameters:
allConfigs
- Object with all of the persistant settings
-
configFactoryDefault
Configures all persistent settings to defaults.- Parameters:
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.- Returns:
- Error Code generated by function. 0 indicates no error.
-
configFactoryDefault
Configures all persistent settings to defaults (overloaded so timeoutMs is 50 ms).- Returns:
- Error Code generated by function. 0 indicates no error.
-
getHandle
-