mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Use constexpr for all example constants
Also make DifferentialDriveKinematics constructor constexpr.
This commit is contained in:
@@ -22,50 +22,50 @@
|
||||
*/
|
||||
|
||||
namespace DriveConstants {
|
||||
const int kLeftMotor1Port = 0;
|
||||
const int kLeftMotor2Port = 1;
|
||||
const int kRightMotor1Port = 2;
|
||||
const int kRightMotor2Port = 3;
|
||||
constexpr int kLeftMotor1Port = 0;
|
||||
constexpr int kLeftMotor2Port = 1;
|
||||
constexpr int kRightMotor1Port = 2;
|
||||
constexpr int kRightMotor2Port = 3;
|
||||
|
||||
const int kLeftEncoderPorts[]{0, 1};
|
||||
const int kRightEncoderPorts[]{2, 3};
|
||||
const bool kLeftEncoderReversed = false;
|
||||
const bool kRightEncoderReversed = true;
|
||||
constexpr int kLeftEncoderPorts[]{0, 1};
|
||||
constexpr int kRightEncoderPorts[]{2, 3};
|
||||
constexpr bool kLeftEncoderReversed = false;
|
||||
constexpr bool kRightEncoderReversed = true;
|
||||
|
||||
const auto kTrackwidth = .6_m;
|
||||
const frc::DifferentialDriveKinematics kDriveKinematics(kTrackwidth);
|
||||
constexpr auto kTrackwidth = .6_m;
|
||||
constexpr frc::DifferentialDriveKinematics kDriveKinematics(kTrackwidth);
|
||||
|
||||
const int kEncoderCPR = 1024;
|
||||
const double kWheelDiameterInches = 6;
|
||||
const double kEncoderDistancePerPulse =
|
||||
constexpr int kEncoderCPR = 1024;
|
||||
constexpr double kWheelDiameterInches = 6;
|
||||
constexpr double kEncoderDistancePerPulse =
|
||||
// Assumes the encoders are directly mounted on the wheel shafts
|
||||
(kWheelDiameterInches * 3.142) / static_cast<double>(kEncoderCPR);
|
||||
|
||||
const bool kGyroReversed = true;
|
||||
constexpr bool kGyroReversed = true;
|
||||
|
||||
// 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
|
||||
// Toolsuite provides a convenient tool for obtaining these values for your
|
||||
// robot.
|
||||
const auto ks = 1_V;
|
||||
const auto kv = .8 * 1_V * 1_s / 1_m;
|
||||
const auto ka = .15 * 1_V * 1_s * 1_s / 1_m;
|
||||
constexpr auto ks = 1_V;
|
||||
constexpr auto kv = .8 * 1_V * 1_s / 1_m;
|
||||
constexpr auto ka = .15 * 1_V * 1_s * 1_s / 1_m;
|
||||
|
||||
// Example value only - as above, this must be tuned for your drive!
|
||||
const double kPDriveVel = .5;
|
||||
constexpr double kPDriveVel = .5;
|
||||
} // namespace DriveConstants
|
||||
|
||||
namespace AutoConstants {
|
||||
const auto kMaxSpeed = 3_mps;
|
||||
const auto kMaxAcceleration = 3_mps_sq;
|
||||
constexpr auto kMaxSpeed = 3_mps;
|
||||
constexpr auto kMaxAcceleration = 3_mps_sq;
|
||||
|
||||
// Reasonable baseline values for a RAMSETE follower in units of meters and
|
||||
// seconds
|
||||
const double kRamseteB = 2;
|
||||
const double kRamseteZeta = .7;
|
||||
constexpr double kRamseteB = 2;
|
||||
constexpr double kRamseteZeta = .7;
|
||||
} // namespace AutoConstants
|
||||
|
||||
namespace OIConstants {
|
||||
const int kDriverControllerPort = 1;
|
||||
constexpr int kDriverControllerPort = 1;
|
||||
} // namespace OIConstants
|
||||
|
||||
Reference in New Issue
Block a user