Files
allwpilib/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/Constants.h
Peter Johnson 8f1f64ffb6 Remove year from file copyright message (NFC) (#2972)
Also update copyright to include "and other WPILib contributors" and clarify
license referral language to not be restricted to FIRST teams.
2020-12-26 14:12:05 -08:00

84 lines
2.9 KiB
C++

// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include <frc/kinematics/DifferentialDriveKinematics.h>
#include <frc/system/plant/DCMotor.h>
#include <frc/system/plant/LinearSystemId.h>
#include <frc/trajectory/constraint/DifferentialDriveKinematicsConstraint.h>
#include <units/acceleration.h>
#include <units/angle.h>
#include <units/length.h>
#include <units/time.h>
#include <units/velocity.h>
#include <units/voltage.h>
#include <wpi/math>
#pragma once
/**
* The Constants header provides a convenient place for teams to hold robot-wide
* numerical or bool constants. This should not be used for any other purpose.
*
* It is generally a good idea to place constants into subsystem- or
* command-specific namespaces within this header, which can then be used where
* they are needed.
*/
namespace DriveConstants {
constexpr int kLeftMotor1Port = 0;
constexpr int kLeftMotor2Port = 1;
constexpr int kRightMotor1Port = 2;
constexpr int kRightMotor2Port = 3;
constexpr int kLeftEncoderPorts[]{0, 1};
constexpr int kRightEncoderPorts[]{2, 3};
constexpr bool kLeftEncoderReversed = false;
constexpr bool kRightEncoderReversed = true;
constexpr auto kTrackwidth = 0.69_m;
extern const frc::DifferentialDriveKinematics kDriveKinematics;
constexpr int kEncoderCPR = 1024;
constexpr auto kWheelDiameter = 6_in;
constexpr double kEncoderDistancePerPulse =
// Assumes the encoders are directly mounted on the wheel shafts
(kWheelDiameter.to<double>() * wpi::math::pi) /
static_cast<double>(kEncoderCPR);
// 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 Robot Characterization
// Toolsuite provides a convenient tool for obtaining these values for your
// robot.
constexpr auto ks = 0.22_V;
constexpr auto kv = 1.98 * 1_V * 1_s / 1_m;
constexpr auto ka = 0.2 * 1_V * 1_s * 1_s / 1_m;
constexpr auto kvAngular = 1.5 * 1_V * 1_s / 1_rad;
constexpr auto kaAngular = 0.3 * 1_V * 1_s * 1_s / 1_rad;
extern const frc::LinearSystem<2, 2, 2> kDrivetrainPlant;
// Example values only -- use what's on your physical robot!
constexpr auto kDrivetrainGearbox = frc::DCMotor::CIM(2);
constexpr auto kDrivetrainGearing = 8.0;
// Example value only - as above, this must be tuned for your drive!
constexpr double kPDriveVel = 8.5;
} // namespace DriveConstants
namespace AutoConstants {
constexpr auto kMaxSpeed = 3_mps;
constexpr auto kMaxAcceleration = 3_mps_sq;
// Reasonable baseline values for a RAMSETE follower in units of meters and
// seconds
constexpr double kRamseteB = 2;
constexpr double kRamseteZeta = 0.7;
} // namespace AutoConstants
namespace OIConstants {
constexpr int kDriverControllerPort = 1;
} // namespace OIConstants