mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
SCRIPT namespace replacements
This commit is contained in:
committed by
Peter Johnson
parent
ae6c043632
commit
9aca8e0fd6
@@ -6,7 +6,7 @@
|
||||
|
||||
#include <wpi/system/RobotController.hpp>
|
||||
|
||||
void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) {
|
||||
void Drivetrain::SetSpeeds(const wpi::math::DifferentialDriveWheelSpeeds& speeds) {
|
||||
auto leftFeedforward = m_feedforward.Calculate(speeds.left);
|
||||
auto rightFeedforward = m_feedforward.Calculate(speeds.right);
|
||||
double leftOutput = m_leftPIDController.Calculate(m_leftEncoder.GetRate(),
|
||||
@@ -14,26 +14,26 @@ void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) {
|
||||
double rightOutput = m_rightPIDController.Calculate(m_rightEncoder.GetRate(),
|
||||
speeds.right.value());
|
||||
|
||||
m_leftLeader.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
|
||||
m_rightLeader.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);
|
||||
m_leftLeader.SetVoltage(wpi::units::volt_t{leftOutput} + leftFeedforward);
|
||||
m_rightLeader.SetVoltage(wpi::units::volt_t{rightOutput} + rightFeedforward);
|
||||
}
|
||||
|
||||
void Drivetrain::Drive(units::meters_per_second_t xSpeed,
|
||||
units::radians_per_second_t rot) {
|
||||
void Drivetrain::Drive(wpi::units::meters_per_second_t xSpeed,
|
||||
wpi::units::radians_per_second_t rot) {
|
||||
SetSpeeds(m_kinematics.ToWheelSpeeds({xSpeed, 0_mps, rot}));
|
||||
}
|
||||
|
||||
void Drivetrain::UpdateOdometry() {
|
||||
m_odometry.Update(m_imu.GetRotation2d(),
|
||||
units::meter_t{m_leftEncoder.GetDistance()},
|
||||
units::meter_t{m_rightEncoder.GetDistance()});
|
||||
wpi::units::meter_t{m_leftEncoder.GetDistance()},
|
||||
wpi::units::meter_t{m_rightEncoder.GetDistance()});
|
||||
}
|
||||
|
||||
void Drivetrain::ResetOdometry(const frc::Pose2d& pose) {
|
||||
void Drivetrain::ResetOdometry(const wpi::math::Pose2d& pose) {
|
||||
m_drivetrainSimulator.SetPose(pose);
|
||||
m_odometry.ResetPosition(m_imu.GetRotation2d(),
|
||||
units::meter_t{m_leftEncoder.GetDistance()},
|
||||
units::meter_t{m_rightEncoder.GetDistance()}, pose);
|
||||
wpi::units::meter_t{m_leftEncoder.GetDistance()},
|
||||
wpi::units::meter_t{m_rightEncoder.GetDistance()}, pose);
|
||||
}
|
||||
|
||||
void Drivetrain::SimulationPeriodic() {
|
||||
@@ -41,10 +41,10 @@ void Drivetrain::SimulationPeriodic() {
|
||||
// simulation, and write the simulated positions and velocities to our
|
||||
// simulated encoder and gyro. We negate the right side so that positive
|
||||
// voltages make the right side move forward.
|
||||
m_drivetrainSimulator.SetInputs(units::volt_t{m_leftLeader.Get()} *
|
||||
frc::RobotController::GetInputVoltage(),
|
||||
units::volt_t{m_rightLeader.Get()} *
|
||||
frc::RobotController::GetInputVoltage());
|
||||
m_drivetrainSimulator.SetInputs(wpi::units::volt_t{m_leftLeader.Get()} *
|
||||
wpi::RobotController::GetInputVoltage(),
|
||||
wpi::units::volt_t{m_rightLeader.Get()} *
|
||||
wpi::RobotController::GetInputVoltage());
|
||||
m_drivetrainSimulator.Update(20_ms);
|
||||
|
||||
m_leftEncoderSim.SetDistance(m_drivetrainSimulator.GetLeftPosition().value());
|
||||
|
||||
@@ -11,12 +11,12 @@
|
||||
|
||||
#include "Drivetrain.hpp"
|
||||
|
||||
class Robot : public frc::TimedRobot {
|
||||
class Robot : public wpi::TimedRobot {
|
||||
public:
|
||||
Robot() {
|
||||
m_trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
|
||||
frc::Pose2d{2_m, 2_m, 0_rad}, {}, frc::Pose2d{6_m, 4_m, 0_rad},
|
||||
frc::TrajectoryConfig(2_mps, 2_mps_sq));
|
||||
m_trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory(
|
||||
wpi::math::Pose2d{2_m, 2_m, 0_rad}, {}, wpi::math::Pose2d{6_m, 4_m, 0_rad},
|
||||
wpi::math::TrajectoryConfig(2_mps, 2_mps_sq));
|
||||
}
|
||||
|
||||
void RobotPeriodic() override { m_drive.Periodic(); }
|
||||
@@ -52,21 +52,21 @@ class Robot : public frc::TimedRobot {
|
||||
void SimulationPeriodic() override { m_drive.SimulationPeriodic(); }
|
||||
|
||||
private:
|
||||
frc::XboxController m_controller{0};
|
||||
wpi::XboxController m_controller{0};
|
||||
|
||||
// Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
|
||||
// to 1.
|
||||
frc::SlewRateLimiter<units::scalar> m_speedLimiter{3 / 1_s};
|
||||
frc::SlewRateLimiter<units::scalar> m_rotLimiter{3 / 1_s};
|
||||
wpi::math::SlewRateLimiter<wpi::units::scalar> m_speedLimiter{3 / 1_s};
|
||||
wpi::math::SlewRateLimiter<wpi::units::scalar> m_rotLimiter{3 / 1_s};
|
||||
|
||||
Drivetrain m_drive;
|
||||
frc::Trajectory m_trajectory;
|
||||
frc::LTVUnicycleController m_feedback{20_ms};
|
||||
frc::Timer m_timer;
|
||||
wpi::math::Trajectory m_trajectory;
|
||||
wpi::math::LTVUnicycleController m_feedback{20_ms};
|
||||
wpi::Timer m_timer;
|
||||
};
|
||||
|
||||
#ifndef RUNNING_FRC_TESTS
|
||||
int main() {
|
||||
return frc::StartRobot<Robot>();
|
||||
return wpi::StartRobot<Robot>();
|
||||
}
|
||||
#endif
|
||||
|
||||
@@ -52,59 +52,59 @@ class Drivetrain {
|
||||
|
||||
m_rightLeader.SetInverted(true);
|
||||
|
||||
frc::SmartDashboard::PutData("Field", &m_fieldSim);
|
||||
wpi::SmartDashboard::PutData("Field", &m_fieldSim);
|
||||
}
|
||||
|
||||
static constexpr units::meters_per_second_t kMaxSpeed =
|
||||
static constexpr wpi::units::meters_per_second_t kMaxSpeed =
|
||||
3.0_mps; // 3 meters per second
|
||||
static constexpr units::radians_per_second_t kMaxAngularSpeed{
|
||||
static constexpr wpi::units::radians_per_second_t kMaxAngularSpeed{
|
||||
std::numbers::pi}; // 1/2 rotation per second
|
||||
|
||||
void SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds);
|
||||
void Drive(units::meters_per_second_t xSpeed,
|
||||
units::radians_per_second_t rot);
|
||||
void SetSpeeds(const wpi::math::DifferentialDriveWheelSpeeds& speeds);
|
||||
void Drive(wpi::units::meters_per_second_t xSpeed,
|
||||
wpi::units::radians_per_second_t rot);
|
||||
void UpdateOdometry();
|
||||
void ResetOdometry(const frc::Pose2d& pose);
|
||||
void ResetOdometry(const wpi::math::Pose2d& pose);
|
||||
|
||||
frc::Pose2d GetPose() const { return m_odometry.GetPose(); }
|
||||
wpi::math::Pose2d GetPose() const { return m_odometry.GetPose(); }
|
||||
|
||||
void SimulationPeriodic();
|
||||
void Periodic();
|
||||
|
||||
private:
|
||||
static constexpr units::meter_t kTrackwidth = 0.381_m * 2;
|
||||
static constexpr wpi::units::meter_t kTrackwidth = 0.381_m * 2;
|
||||
static constexpr double kWheelRadius = 0.0508; // meters
|
||||
static constexpr int kEncoderResolution = 4096;
|
||||
|
||||
frc::PWMSparkMax m_leftLeader{1};
|
||||
frc::PWMSparkMax m_leftFollower{2};
|
||||
frc::PWMSparkMax m_rightLeader{3};
|
||||
frc::PWMSparkMax m_rightFollower{4};
|
||||
wpi::PWMSparkMax m_leftLeader{1};
|
||||
wpi::PWMSparkMax m_leftFollower{2};
|
||||
wpi::PWMSparkMax m_rightLeader{3};
|
||||
wpi::PWMSparkMax m_rightFollower{4};
|
||||
|
||||
frc::Encoder m_leftEncoder{0, 1};
|
||||
frc::Encoder m_rightEncoder{2, 3};
|
||||
wpi::Encoder m_leftEncoder{0, 1};
|
||||
wpi::Encoder m_rightEncoder{2, 3};
|
||||
|
||||
frc::PIDController m_leftPIDController{8.5, 0.0, 0.0};
|
||||
frc::PIDController m_rightPIDController{8.5, 0.0, 0.0};
|
||||
wpi::math::PIDController m_leftPIDController{8.5, 0.0, 0.0};
|
||||
wpi::math::PIDController m_rightPIDController{8.5, 0.0, 0.0};
|
||||
|
||||
frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
|
||||
wpi::OnboardIMU m_imu{wpi::OnboardIMU::kFlat};
|
||||
|
||||
frc::DifferentialDriveKinematics m_kinematics{kTrackwidth};
|
||||
frc::DifferentialDriveOdometry m_odometry{
|
||||
m_imu.GetRotation2d(), units::meter_t{m_leftEncoder.GetDistance()},
|
||||
units::meter_t{m_rightEncoder.GetDistance()}};
|
||||
wpi::math::DifferentialDriveKinematics m_kinematics{kTrackwidth};
|
||||
wpi::math::DifferentialDriveOdometry m_odometry{
|
||||
m_imu.GetRotation2d(), wpi::units::meter_t{m_leftEncoder.GetDistance()},
|
||||
wpi::units::meter_t{m_rightEncoder.GetDistance()}};
|
||||
|
||||
// Gains are for example purposes only - must be determined for your own
|
||||
// robot!
|
||||
frc::SimpleMotorFeedforward<units::meters> m_feedforward{1_V, 3_V / 1_mps};
|
||||
wpi::math::SimpleMotorFeedforward<wpi::units::meters> m_feedforward{1_V, 3_V / 1_mps};
|
||||
|
||||
// Simulation classes help us simulate our robot
|
||||
frc::sim::EncoderSim m_leftEncoderSim{m_leftEncoder};
|
||||
frc::sim::EncoderSim m_rightEncoderSim{m_rightEncoder};
|
||||
frc::Field2d m_fieldSim;
|
||||
frc::LinearSystem<2, 2, 2> m_drivetrainSystem =
|
||||
frc::LinearSystemId::IdentifyDrivetrainSystem(
|
||||
wpi::sim::EncoderSim m_leftEncoderSim{m_leftEncoder};
|
||||
wpi::sim::EncoderSim m_rightEncoderSim{m_rightEncoder};
|
||||
wpi::Field2d m_fieldSim;
|
||||
wpi::math::LinearSystem<2, 2, 2> m_drivetrainSystem =
|
||||
wpi::math::LinearSystemId::IdentifyDrivetrainSystem(
|
||||
1.98_V / 1_mps, 0.2_V / 1_mps_sq, 1.5_V / 1_mps, 0.3_V / 1_mps_sq);
|
||||
frc::sim::DifferentialDrivetrainSim m_drivetrainSimulator{
|
||||
m_drivetrainSystem, kTrackwidth, frc::DCMotor::CIM(2), 8, 2_in};
|
||||
wpi::sim::DifferentialDrivetrainSim m_drivetrainSimulator{
|
||||
m_drivetrainSystem, kTrackwidth, wpi::math::DCMotor::CIM(2), 8, 2_in};
|
||||
};
|
||||
|
||||
Reference in New Issue
Block a user