CTRE_Phoenix 5.20.2
|
#include <Pigeon2.h>
Inherits ctre::phoenix::sensors::BasePigeon.
Inherited by ctre::phoenix::sensors::WPI_Pigeon2.
Public Member Functions | |
Pigeon2 (int deviceNumber, std::string const &canbus="") | |
ErrorCode | GetFaults (Pigeon2_Faults &toFill) |
ErrorCode | GetStickyFaults (Pigeon2_StickyFaults &toFill) |
ErrorCode | ConfigMountPose (double yaw, double pitch, double roll, int timeoutMs=0) |
ErrorCode | ConfigMountPoseYaw (double yaw, int timeoutMs=0) |
ErrorCode | ConfigMountPosePitch (double pitch, int timeoutMs=0) |
ErrorCode | ConfigMountPoseRoll (double roll, int timeoutMs=0) |
ErrorCode | ConfigEnableCompass (bool enable, int timeoutMs=0) |
ErrorCode | ConfigDisableTemperatureCompensation (bool disable, int timeoutMs=0) |
ErrorCode | ConfigDisableNoMotionCalibration (bool disable, int timeoutMs=0) |
ErrorCode | ZeroGyroBiasNow (int timeoutMs=0) |
ErrorCode | GetGravityVector (double gravVector[3]) const |
ErrorCode | ConfigAllSettings (Pigeon2Configuration &settings, int timeoutMs=50) |
void | GetAllConfigs (Pigeon2Configuration &allConfigs, 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 | |
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) | |
Pigeon 2 Class. Class supports communicating over CANbus.
// Example usage of a Pigeon 2
Pigeon2 pigeon{0}; // creates a new Pigeon2 with ID 0
Pigeon2Configuration config;
// set mount pose as rolled 90 degrees counter-clockwise
config.MountPoseYaw = 0;
config.MountPosePitch = 0;
config.MountPoseRoll = 90;
pigeon.ConfigAllSettings(config);
std::cout << pigeon.GetYaw() << std::endl; // prints the yaw of the Pigeon
std::cout << pigeon.GetPitch() << std::endl; // prints the pitch of the Pigeon
std::cout << pigeon.GetRoll() << std::endl; // prints the roll of the Pigeon
double gravityVec[3];
pigeon.GetGravityVector(gravityVec); // gets the gravity vector of the Pigeon 2
ErrorCode error = pigeon.GetLastError(); // gets the last error generated by the Pigeon
Pigeon2_Faults faults;
ErrorCode faultsError = pigeon.GetFaults(faults); // fills faults with the current Pigeon 2 faults; returns the last error generated
ctre::phoenix::sensors::Pigeon2::Pigeon2 | ( | int | deviceNumber, |
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 |
ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigAllSettings | ( | Pigeon2Configuration & | settings, |
int | timeoutMs = 50 |
||
) |
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. |
ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigDisableNoMotionCalibration | ( | bool | disable, |
int | timeoutMs = 0 |
||
) |
Disables the no-motion calibration from Pigeon2
disable | Boolean to disable/enable no-motion calibration |
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::Pigeon2::ConfigDisableTemperatureCompensation | ( | bool | disable, |
int | timeoutMs = 0 |
||
) |
Disables temperature compensation from Pigeon2.
disable | Boolean to disable/enable temperature compensation |
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::Pigeon2::ConfigEnableCompass | ( | bool | enable, |
int | timeoutMs = 0 |
||
) |
Enables the magnetometer fusion for Pigeon2. This is not recommended for FRC use
enable | Boolean to enable/disable magnetometer fusion |
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::Pigeon2::ConfigMountPose | ( | double | yaw, |
double | pitch, | ||
double | roll, | ||
int | timeoutMs = 0 |
||
) |
Configure the mounting pose of the Pigeon2.
This is the Yaw-Pitch-Roll the Pigeon2 underwent to get to its current orientation, referenced from the robot's point of view.
This is only necessary if the Pigeon2 is mounted at an exotic angle near the gimbal lock point or not forward.
If the pigeon is relatively flat and pointed forward, this is not needed.
Examples:
If the Pigeon2 is pointed directly right, that corresponds to a -90 yaw, 0 pitch, and 0 roll, as it yaw'd 90 degrees clockwise.
If the Pigeon2 points upwards, that's a 0 yaw, -90 pitch, 0 roll, as it pitched 90 degrees clockwise.
yaw | Yaw angle needed to reach the current orientation in degrees. |
pitch | Pitch angle needed to reach the current orientation in degrees. |
roll | Roll angle needed to reach the current orientation in degrees. |
timeoutMs | Config timeout in milliseconds. |
ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigMountPosePitch | ( | double | pitch, |
int | timeoutMs = 0 |
||
) |
Configure the mounting pose Pitch of the Pigeon2. See configMountPose(double, double, double, int)
pitch | Pitch angle needed to reach the current orientation in degrees. |
timeoutMs | Config timeout in milliseconds. |
ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigMountPoseRoll | ( | double | roll, |
int | timeoutMs = 0 |
||
) |
Configure the mounting pose Roll of the Pigeon2. See configMountPose(double, double, double, int)
roll | Roll angle needed to reach the current orientation in degrees. |
timeoutMs | Config timeout in milliseconds. |
ErrorCode ctre::phoenix::sensors::Pigeon2::ConfigMountPoseYaw | ( | double | yaw, |
int | timeoutMs = 0 |
||
) |
Configure the mounting pose Yaw of the Pigeon2. See configMountPose(double, double, double, int)
yaw | Yaw angle needed to reach the current orientation in degrees. |
timeoutMs | Config timeout in milliseconds. |
void ctre::phoenix::sensors::Pigeon2::GetAllConfigs | ( | Pigeon2Configuration & | allConfigs, |
int | timeoutMs = 50 |
||
) |
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. |
ErrorCode ctre::phoenix::sensors::Pigeon2::GetFaults | ( | Pigeon2_Faults & | toFill | ) |
Gets the fault status
toFill | Container for fault statuses. |
ErrorCode ctre::phoenix::sensors::Pigeon2::GetGravityVector | ( | double | gravVector[3] | ) | const |
Get the Gravity Vector.
This provides a vector that points toward ground. This is useful for applications like an arm, where the z-value of the gravity vector corresponds to the feed-forward needed to hold the arm steady. The gravity vector is calculated after the mount pose, so if the pigeon is where it was mounted, the gravity vector is {0, 0, 1}.
gravVector | Pass in a double array of size 3 to get the gravity vector |
ErrorCode ctre::phoenix::sensors::Pigeon2::GetStickyFaults | ( | Pigeon2_StickyFaults & | toFill | ) |
Gets the sticky fault status
toFill | Container for sticky fault statuses. |
ErrorCode ctre::phoenix::sensors::Pigeon2::ZeroGyroBiasNow | ( | int | timeoutMs = 0 | ) |
Performs an offset calibration on gyro bias
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. |