WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
frc::XRPGyro Class Reference

Use a rate gyro to return the robots heading relative to a starting position. More...

#include <frc/xrp/XRPGyro.h>

Public Member Functions

 XRPGyro ()
 Constructs an XRPGyro.
 
units::radian_t GetAngle () const
 Return the actual angle in radians that the robot is currently facing.
 
frc::Rotation2d GetRotation2d () const
 Gets the angle the robot is facing.
 
units::radians_per_second_t GetRate () const
 Return the rate of rotation of the gyro.
 
units::radians_per_second_t GetRateX () const
 Gets the rate of turn in radians-per-second around the X-axis.
 
units::radians_per_second_t GetRateY () const
 Gets the rate of turn in radians-per-second around the Y-axis.
 
units::radians_per_second_t GetRateZ () const
 Gets the rate of turn in radians-per-second around the Z-axis.
 
units::radian_t GetAngleX () const
 Gets the currently reported angle around the X-axis.
 
units::radian_t GetAngleY () const
 Gets the currently reported angle around the Y-axis.
 
units::radian_t GetAngleZ () const
 Gets the currently reported angle around the Z-axis.
 
void Reset ()
 Reset the gyro angles to 0.
 

Detailed Description

Use a rate gyro to return the robots heading relative to a starting position.

This class is for the XRP onboard gyro, and will only work in simulation/XRP mode. Only one instance of a XRPGyro is supported.

Constructor & Destructor Documentation

◆ XRPGyro()

frc::XRPGyro::XRPGyro ( )

Constructs an XRPGyro.

Only one instance of a XRPGyro is supported.

Member Function Documentation

◆ GetAngle()

units::radian_t frc::XRPGyro::GetAngle ( ) const

Return the actual angle in radians that the robot is currently facing.

The angle is based on integration of the returned rate form the gyro. The angle is continuous, that is, it will continue from 2π->2.1π. This allows algorithms that wouldn't want to see a discontinuity in the gyro output as it sweeps from 2π to 0 radians on the second time around.

Returns
the current heading of the robot in radians.

◆ GetAngleX()

units::radian_t frc::XRPGyro::GetAngleX ( ) const

Gets the currently reported angle around the X-axis.

Returns
current angle around X-axis in radians

◆ GetAngleY()

units::radian_t frc::XRPGyro::GetAngleY ( ) const

Gets the currently reported angle around the Y-axis.

Returns
current angle around Y-axis in radians

◆ GetAngleZ()

units::radian_t frc::XRPGyro::GetAngleZ ( ) const

Gets the currently reported angle around the Z-axis.

Returns
current angle around Z-axis in radians

◆ GetRate()

units::radians_per_second_t frc::XRPGyro::GetRate ( ) const

Return the rate of rotation of the gyro.

The rate is based on the most recent reading of the gyro.

Returns
the current rate in radians per second

◆ GetRateX()

units::radians_per_second_t frc::XRPGyro::GetRateX ( ) const

Gets the rate of turn in radians-per-second around the X-axis.

Returns
rate of turn in radians-per-second

◆ GetRateY()

units::radians_per_second_t frc::XRPGyro::GetRateY ( ) const

Gets the rate of turn in radians-per-second around the Y-axis.

Returns
rate of turn in radians-per-second

◆ GetRateZ()

units::radians_per_second_t frc::XRPGyro::GetRateZ ( ) const

Gets the rate of turn in radians-per-second around the Z-axis.

Returns
rate of turn in radians-per-second

◆ GetRotation2d()

frc::Rotation2d frc::XRPGyro::GetRotation2d ( ) const

Gets the angle the robot is facing.

Returns
A Rotation2d with the current heading.

◆ Reset()

void frc::XRPGyro::Reset ( )

Reset the gyro angles to 0.


The documentation for this class was generated from the following file: