Skip to content
This repository was archived by the owner on Apr 22, 2019. It is now read-only.

Commit 4ccf1bc

Browse files
committed
master ready
1 parent a0959f5 commit 4ccf1bc

File tree

7 files changed

+20
-8
lines changed

7 files changed

+20
-8
lines changed

common/include/SlewLimiter.h

Whitespace-only changes.

src/main/cpp/Commands/ControlCargo.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@
44
ControlCargo::ControlCargo() {
55
// Use Requires() here to declare subsystem dependencies
66
Requires(Robot::m_Flap);
7-
this->pJoyOp = Robot::m_oi->GetJoystickOperator();
7+
this->pJoyDrive = Robot::m_oi->GetJoystickDrive();
88
}
99

1010
// Called just before this Command runs the first time
@@ -15,11 +15,12 @@ void ControlCargo::Initialize() {}
1515
void ControlCargo::Execute() {
1616

1717
// Control piston
18-
if(this->pJoyOp->GetTriggerAxis(Hand::kLeftHand) > 0.8){
18+
if(this->pJoyDrive->GetYButton()){
1919
Robot::m_Flap->Deploy();
2020
}else{
2121
Robot::m_Flap->Retract();
2222
}
23+
2324
}
2425

2526

src/main/cpp/Commands/ControlHatchGripper.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@ void ControlHatchGripper::Execute() {
2525
}
2626
}
2727

28-
28+
2929
bool ControlHatchGripper::IsFinished() { return false; }
3030

3131
// Called once after isFinished returns true

src/main/cpp/Commands/TriggerDrive.cpp

+11-3
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,8 @@ void TriggerDrive::Initialize() {
1717
//set Speed and Rotation
1818
this->speed = 0.0;
1919
this->rotation = 0.0;
20+
this->rotationOutput = 0.0;
21+
this->speedOutput = 0.0;
2022
}
2123

2224
// Called repeatedly when this Command is scheduled to run
@@ -50,10 +52,16 @@ void TriggerDrive::Execute() {
5052
}else if(change < (-SLEW_LIMIT)){
5153
change = -SLEW_LIMIT;
5254
};
53-
5455
this->speedOutput += change;
55-
Log(change);
56-
Log(this->speedOutput + change);
56+
57+
// // Rotation slew
58+
// double rchange = this->rotation - this->rotationOutput;
59+
// if (change > R_SLEW_LIMIT) {
60+
// rchange = R_SLEW_LIMIT;
61+
// }else if(change < (-R_SLEW_LIMIT)){
62+
// rchange = -R_SLEW_LIMIT;
63+
// };
64+
// this->rotationOutput += rchange;
5765

5866
Robot::m_DriveTrain->ArcadeDrive(this->speedOutput, this->rotation);
5967

src/main/include/Commands/ControlCargo.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ class ControlCargo : public frc::Command {
2727
void Interrupted() override; //!< Runs once if the command is forced to stop
2828

2929
private:
30-
frc::XboxController* pJoyOp; //!< A mnemonic for the operator's controller because we are lazy
30+
frc::XboxController* pJoyDrive; //!< A mnemonic for the operator's controller because we are lazy
3131
};
3232

3333
#endif // _ControlCargo_HG_

src/main/include/Commands/TriggerDrive.h

+1
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@ class TriggerDrive : public frc::Command {
3333
double speed; //!< Speed value that will be passed into DriveTrain::ArcadeDrive
3434
double rotation; //!< Rotation value that will be passed into DriveTrain::ArcadeDrive
3535
double speedOutput = 0.0;
36+
double rotationOutput = 0.0;
3637

3738
frc::XboxController* pJoyDrive; //!< A mnemonic for the driver's controller because we are lazy
3839
};

src/main/include/RobotMap.h

+3-1
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,9 @@
3232
#define ARCADE_KP 0.25
3333
#define ARCADE_KI 0.0
3434
#define ARCADE_KD 0.0
35-
#define SLEW_LIMIT 0.05
35+
36+
#define SLEW_LIMIT 0.06
37+
#define R_SLEW_LIMIT 0.04
3638

3739
// DriveTrain motor invertions
3840
#define DRIVETRAIN_LEFT_FRONT_MOTOR_INVERT false

0 commit comments

Comments
 (0)