phoenix6.hardware.pigeon2
#
Module Contents#
- class phoenix6.hardware.pigeon2.Pigeon2(device_id: int, canbus: str | phoenix6.canbus.CANBus = '')#
Bases:
phoenix6.hardware.core.core_pigeon2.CorePigeon2
,wpiutil.Sendable
Constructs a new Pigeon 2 sensor object.
- Parameters:
device_id (int) – ID of the device, as configured in Phoenix Tuner.
canbus (str | CANBus, optional) –
Name of the CAN bus this device is on. Possible CAN bus strings are:
”rio” for the native roboRIO CAN bus
CANivore name or serial number
SocketCAN interface (non-FRC Linux only)
”*” for any CANivore seen by the program
empty string (default) to select the default for the system:
”rio” on roboRIO
”can0” on Linux
”*” on Windows
- close()#
- reset()#
Resets the Pigeon 2 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.
- getRotation2d() wpimath.geometry.Rotation2d #
Returns the heading of the robot as a Rotation2d.
The angle increases as the Pigeon 2 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 Rotation2d
- Return type:
- getRotation3d() wpimath.geometry.Rotation3d #
Returns the orientation of the robot as a Rotation3d created from the quaternion signals.
- Returns:
The current orientation of the robot as a Rotation3d
- Return type:
Rotation3d
- initSendable(builder: wpiutil.SendableBuilder)#