mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpilib] Add Gyro::GetRotation2d() (#2555)
This commit is contained in:
@@ -1,5 +1,5 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
@@ -53,8 +53,6 @@ constexpr bool kRearLeftDriveEncoderReversed = true;
|
||||
constexpr bool kFrontRightDriveEncoderReversed = false;
|
||||
constexpr bool kRearRightDriveEncoderReversed = true;
|
||||
|
||||
constexpr bool kGyroReversed = false;
|
||||
|
||||
// These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT!
|
||||
// These characterization values MUST be determined either experimentally or
|
||||
// theoretically for *your* robot's drive. The RobotPy Characterization
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
|
||||
/* Copyright (c) 2019-2020 FIRST. All Rights Reserved. */
|
||||
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
||||
/* must be accompanied by the FIRST BSD license file in the root directory of */
|
||||
/* the project. */
|
||||
@@ -63,7 +63,7 @@ class DriveSubsystem : public frc2::SubsystemBase {
|
||||
*
|
||||
* @return the robot's heading in degrees, from 180 to 180
|
||||
*/
|
||||
double GetHeading();
|
||||
units::degree_t GetHeading() const;
|
||||
|
||||
/**
|
||||
* Zeroes the heading of the robot.
|
||||
|
||||
Reference in New Issue
Block a user