File tree Expand file tree Collapse file tree 5 files changed +16
-0
lines changed Expand file tree Collapse file tree 5 files changed +16
-0
lines changed Original file line number Diff line number Diff line change @@ -105,6 +105,13 @@ void Robot::RobotInit()
105105 { mShooter }
106106 );
107107
108+
109+ mShootAuto = new frc2::StartEndCommand (
110+ [&]() { mShooter ->shootAuto (); },
111+ [&]() { mShooter ->stopShooter (); },
112+ { mShooter }
113+ );
114+
108115 m_chooser.SetDefaultOption (kAutoNameDefault , kAutoNameDefault );
109116 m_chooser.AddOption (kAutoDriveAndShoot , kAutoDriveAndShoot );
110117 frc::SmartDashboard::PutData (" Auto Modes" , &m_chooser);
Original file line number Diff line number Diff line change 55Shooter::Shooter (std::shared_ptr<cpptoml::table> toml) {
66 config.speed .near = toml->get_qualified_as <double >(" speed.near" ).value_or (2700 );
77 config.speed .far = toml->get_qualified_as <double >(" speed.far" ).value_or (3200 );
8+ config.speed .auton = toml->get_qualified_as <double >(" speed.auto" ).value_or (2500 );
89 config.motor .p = toml->get_qualified_as <double >(" motor.p" ).value_or (0.01 );
910 config.motor .i = toml->get_qualified_as <double >(" motor.i" ).value_or (0.0 );
1011 config.motor .d = toml->get_qualified_as <double >(" motor.d" ).value_or (0.0 );
@@ -41,6 +42,10 @@ void Shooter::shootNear() {
4142 runShooter (config.speed .near );
4243}
4344
45+ void Shooter::shootAuto () {
46+ runShooter (config.speed .auton );
47+ }
48+
4449void Shooter::stopShooter () {
4550 mShooterMotor .StopMotor ();
4651}
Original file line number Diff line number Diff line change @@ -6,6 +6,7 @@ intakeExtendedPosition = 1.0
66
77[shooter ]
88speed.near = 2400 # RPM
9+ speed.auto = 2200 # RPM
910speed.far = 2750
1011motor.p = 0.0005
1112motor.i = 0.0
Original file line number Diff line number Diff line change @@ -71,6 +71,7 @@ class Robot : public frc::TimedRobot
7171
7272 frc2::StartEndCommand *mShootNear = nullptr ;
7373 frc2::StartEndCommand *mShootFar = nullptr ;
74+ frc2::StartEndCommand *mShootAuto = nullptr ;
7475
7576 frc2::SequentialCommandGroup * mDriveAndShoot = nullptr ;
7677};
Original file line number Diff line number Diff line change @@ -17,6 +17,7 @@ class Shooter : public frc2::SubsystemBase {
1717 void runShooter (double speed);
1818 void shootFar ();
1919 void shootNear ();
20+ void shootAuto ();
2021 void stopShooter ();
2122
2223private:
@@ -44,6 +45,7 @@ class Shooter : public frc2::SubsystemBase {
4445 struct {
4546 double near;
4647 double far;
48+ double auton;
4749 } speed;
4850
4951 struct {
You can’t perform that action at this time.
0 commit comments