WPI_Pigeon2
- class phoenix5.sensors.WPI_Pigeon2(deviceNumber: int, canbus: str = '')
Bases:
Pigeon2
,Sendable
Pigeon 2 Class. Class supports communicating over CANbus.
If the Phoenix 5 API must be used for this device, the device must have 22.X firmware. This firmware is available in Tuner X after selecting Phoenix 5 in the firmware year dropdown.
- Deprecated:
This device’s Phoenix 5 API is deprecated for removal in the 2025 season. Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API. A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html.
Construtor for WPI_Pigeon2.
- Parameters:
deviceNumber – CAN Device ID of the Pigeon 2.
canbus – Name of the CANbus; can be a CANivore device name or serial number. Pass in nothing or “rio” to use the roboRIO.
- getAngle() float
Returns the heading of the robot in degrees.
The angle increases as the Pigeon 2 turns clockwise when looked at from the top. This follows the NED axis convention.
details 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 in degrees
- getRate() float
Returns the rate of rotation of the Pigeon 2.
The rate is positive as the Pigeon 2 turns clockwise when looked at from the top.
- Returns:
The current rate in degrees per second
- getRotation2d() wpimath.geometry._geometry.Rotation2d
Returns the heading of the robot as a frc#Rotation2d.
The angle increases as the Pigeon 2 turns counterclockwise when looked at from the top. This follows the NWU axis convention.
details 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 frc#Rotation2d
- initSendable(builder: wpiutil._wpiutil.SendableBuilder) None
- reset() None
Resets the Pigeon 2 to a heading of zero.
details This can be used if there is significant drift in the gyro, and it needs to be recalibrated after it has been running.