diff --git a/build.gradle b/build.gradle index a55a04a..6edd6c5 100644 --- a/build.gradle +++ b/build.gradle @@ -36,7 +36,7 @@ deploy { def deployArtifact = deploy.targets.roborio.artifacts.frcCpp // Set this to true to enable desktop support. -def includeDesktopSupport = true +def includeDesktopSupport = false // Set to true to run simulation in debug mode wpi.cpp.debugSimulation = false diff --git a/logs/FRC_20230330_183315_MOKC_P4.wpilog b/logs/FRC_20230330_183315_MOKC_P4.wpilog new file mode 100644 index 0000000..e5740e8 Binary files /dev/null and b/logs/FRC_20230330_183315_MOKC_P4.wpilog differ diff --git a/logs/FRC_20230330_191637_MOKC_P8.wpilog b/logs/FRC_20230330_191637_MOKC_P8.wpilog new file mode 100644 index 0000000..de79b87 Binary files /dev/null and b/logs/FRC_20230330_191637_MOKC_P8.wpilog differ diff --git a/logs/FRC_20230331_140811_MOKC_Q2.wpilog b/logs/FRC_20230331_140811_MOKC_Q2.wpilog new file mode 100644 index 0000000..c7a6b7d Binary files /dev/null and b/logs/FRC_20230331_140811_MOKC_Q2.wpilog differ diff --git a/logs/FRC_20230331_150043_MOKC_Q8.wpilog b/logs/FRC_20230331_150043_MOKC_Q8.wpilog new file mode 100644 index 0000000..cbe5fbf Binary files /dev/null and b/logs/FRC_20230331_150043_MOKC_Q8.wpilog differ diff --git a/logs/FRC_20230331_160108_MOKC_Q13.wpilog b/logs/FRC_20230331_160108_MOKC_Q13.wpilog new file mode 100644 index 0000000..3a2e830 Binary files /dev/null and b/logs/FRC_20230331_160108_MOKC_Q13.wpilog differ diff --git a/logs/FRC_20230331_181809_MOKC_Q23.wpilog b/logs/FRC_20230331_181809_MOKC_Q23.wpilog new file mode 100644 index 0000000..615156c Binary files /dev/null and b/logs/FRC_20230331_181809_MOKC_Q23.wpilog differ diff --git a/src/main/cpp/RobotContainer.cpp b/src/main/cpp/RobotContainer.cpp index f956f26..545433b 100644 --- a/src/main/cpp/RobotContainer.cpp +++ b/src/main/cpp/RobotContainer.cpp @@ -64,18 +64,16 @@ bool RobotContainer::ConfigureButtonBindings() { // driver_x_button_->WhileActiveContinous(*retractArmCommand); // driver_b_button_->WhileActiveContinous(*extendArmCommand); - // manip_left_stick_button_->WhileHeld(*inc_wrist_tilt_command_); - // manip_right_stick_button_->WhileHeld(*dec_wrist_tilt_command_); - + // second driver controls - manip_a_button_->WhenPressed(*human_player_command_); - manip_right_bumper_button_->WhenPressed(*pickup_command_); - manip_left_bumper_button_->WhenPressed(*pickup_reverse_command_); + manip_a_button_->WhenPressed(*arm_human_player_command_); + manip_right_bumper_button_->WhenPressed(*arm_pickup_command_); + manip_left_bumper_button_->WhenPressed(*arm_pickup_reverse_command_); - manip_x_button_->WhenPressed(*carry_command_); + manip_x_button_->WhenPressed(*arm_carry_command_); - manip_b_button_->WhenPressed(*score_mid_command_); - manip_y_button_->WhenPressed(*score_high_command_); + manip_b_button_->WhenPressed(*arm_score_mid_command_); + manip_y_button_->WhenPressed(*arm_score_high_command_); manip_start_button_->WhenPressed(*reset_gyro_command_); @@ -129,7 +127,6 @@ bool RobotContainer::InitActuators(Actuators *actuators_interface) { actuators_interface->arm_extend_motor->SetIdleMode(BRAKE); actuators_interface->intake_motor = std::make_unique(INTAKE_MOTOR, BRUSHLESS); - actuators_interface->wrist_motor = std::make_unique(WRIST_MOTOR, BRUSHLESS); OKC_CHECK(actuators_interface->intake_motor != nullptr); @@ -200,8 +197,6 @@ bool RobotContainer::InitSensors(const Actuators &actuators, OKC_CHECK(sensor_interface->arm_lift_encoder != nullptr); sensor_interface->intake_encoder = std::make_unique(actuators.intake_motor->GetEncoder()); - sensor_interface->wrist_encoder = std::make_unique(WRIST_ABS_ENCODER); - return true; } @@ -320,23 +315,11 @@ bool RobotContainer::InitCommands() { double negative_score_high_rotation_ = RobotParams::GetParam("arm.negative_score_high.arm_setpoint", 0.0); double negative_score_high_extension_ = RobotParams::GetParam("arm.negative_score_high.extend_setpoint", 1.0); - double tilt_pickup_reverse_ = RobotParams::GetParam("arm.negative_pickup.intake_setpoint", 0.0); - double tilt_pickup_ = RobotParams::GetParam("arm.pickup.intake_setpoint", 0.0); - - double tilt_score_mid_ = RobotParams::GetParam("arm.score_medium.intake_setpoint", 0.0); - double tilt_score_mid_reverse_ = RobotParams::GetParam("arm.negative_score_medium.intake_setpoint", 0.0); - - double tilt_score_high_ = RobotParams::GetParam("arm.score_high.intake_setpoint", 0.0); - double tilt_score_high_reverse_ = RobotParams::GetParam("arm.negative_score_high.intake_setpoint", 0.0); - double human_player_extension_ = RobotParams::GetParam("arm.human_player.extend_setpoint", 1.0); double human_player_rotation_ = RobotParams::GetParam("arm.human_player.arm_setpoint", 0.0); - double tilt_human_player = RobotParams::GetParam("arm.human_player.intake_setpoint", 0.0); - + double negative_human_player_extension_ = RobotParams::GetParam("arm.negative_human_player.extend_setpoint", 1.0); double negative_human_player_rotation_ = RobotParams::GetParam("arm.negative_human_player.arm_setpoint", 0.0); - double tilt_human_player_reverse_ = RobotParams::GetParam("arm.negative_human_player.intake_setpoint", 0.0); - // autons score_preload_backup_auto_ = std::make_shared(swerve_drive_, arm_, intake_); @@ -372,28 +355,6 @@ bool RobotContainer::InitCommands() { other_intake_command = std::make_shared(intake_, -0.7); stop_intake_command = std::make_shared(intake_, -0.03); - inc_wrist_tilt_command_ = std::make_shared(intake_, 1); - dec_wrist_tilt_command_ = std::make_shared(intake_, -1); - - tilt_pickup_reverse_command_ = std::make_shared(intake_, tilt_pickup_reverse_); - tilt_pickup_command_ = std::make_shared(intake_, tilt_pickup_); - tilt_carry_command_ = std::make_shared(intake_, 0.0); - - tilt_mid_command_ = std::make_shared(intake_, swerve_drive_, tilt_score_mid_, tilt_score_mid_reverse_); - tilt_high_command_ = std::make_shared(intake_, swerve_drive_, tilt_score_high_, tilt_score_high_reverse_); - tilt_human_player_command_ = std::make_shared(intake_, swerve_drive_, tilt_human_player_reverse_, tilt_human_player); - - // pickup commands - pickup_command_ = std::make_shared(tilt_pickup_command_, arm_pickup_command_); - pickup_reverse_command_ = std::make_shared(tilt_pickup_reverse_command_, arm_pickup_reverse_command_); - - score_mid_command_ = std::make_shared(tilt_mid_command_, arm_score_mid_command_); - score_high_command_ = std::make_shared(tilt_high_command_, arm_score_high_command_); - carry_command_ = std::make_shared(tilt_carry_command_, arm_carry_command_); - - // human player - human_player_command_ = std::make_shared(tilt_human_player_command_, arm_human_player_command_); - return true; } diff --git a/src/main/cpp/autos/ScorePreloadedAuto.cpp b/src/main/cpp/autos/ScorePreloadedAuto.cpp index d316f84..3393941 100644 --- a/src/main/cpp/autos/ScorePreloadedAuto.cpp +++ b/src/main/cpp/autos/ScorePreloadedAuto.cpp @@ -3,7 +3,6 @@ #include "frc2/command/WaitCommand.h" #include "commands/intake/IntakeCommand.h" #include "commands/arm/ArmSetStateCommand.h" -#include "commands/intake/IntakePositionCommand.h" #include "Parameters.h" ScorePreloadedAuto::ScorePreloadedAuto(std::shared_ptr swerve, std::shared_ptr arm, std::shared_ptr intake) { @@ -12,9 +11,6 @@ ScorePreloadedAuto::ScorePreloadedAuto(std::shared_ptr swerve, std: double degrees = RobotParams::GetParam("arm.score_high.arm_setpoint", 0.0); double extend = RobotParams::GetParam("arm.score_high.extend_setpoint", 1.0); - double pickup_degrees = RobotParams::GetParam("arm.pickup.arm_setpoint", 0.0); - double pickup_extend = RobotParams::GetParam("arm.pickup.extend_setpoint", 1.0); - double negative_pickup_degrees = RobotParams::GetParam("arm.negative_pickup.arm_setpoint", 0.0); double negative_pickup_extend = RobotParams::GetParam("arm.negative_pickup.extend_setpoint", 1.0); diff --git a/src/main/cpp/autos/ScorePreloadedBalanceAuto.cpp b/src/main/cpp/autos/ScorePreloadedBalanceAuto.cpp index 9b58da3..aebc9cf 100644 --- a/src/main/cpp/autos/ScorePreloadedBalanceAuto.cpp +++ b/src/main/cpp/autos/ScorePreloadedBalanceAuto.cpp @@ -4,7 +4,6 @@ #include "commands/intake/IntakeCommand.h" #include "commands/swerve/AutoBalanceCommand.h" #include "commands/arm/ArmSetStateCommand.h" -#include "commands/intake/IntakePositionCommand.h" #include "Parameters.h" ScorePreloadedBalanceAuto::ScorePreloadedBalanceAuto(std::shared_ptr swerve, std::shared_ptr arm, std::shared_ptr intake) { @@ -13,9 +12,6 @@ ScorePreloadedBalanceAuto::ScorePreloadedBalanceAuto(std::shared_ptr arm, std::shared_ptr intake) { @@ -12,9 +11,6 @@ ScorePreloadedNoDriveAuto::ScorePreloadedNoDriveAuto(std::shared_ptr arm, s double degrees = RobotParams::GetParam("arm.score_high.arm_setpoint", 0.0); double extend = RobotParams::GetParam("arm.score_high.extend_setpoint", 1.0); - double pickup_degrees = RobotParams::GetParam("arm.pickup.arm_setpoint", 0.0); - double pickup_extend = RobotParams::GetParam("arm.pickup.extend_setpoint", 1.0); - double score_position = RobotParams::GetParam("arm.score_high.intake_setpoint", 0.0); AddCommands( diff --git a/src/main/cpp/autos/ScoreTwoAuto.cpp b/src/main/cpp/autos/ScoreTwoAuto.cpp index fb3d7f2..2b0e3df 100644 --- a/src/main/cpp/autos/ScoreTwoAuto.cpp +++ b/src/main/cpp/autos/ScoreTwoAuto.cpp @@ -11,9 +11,6 @@ ScoreTwoAuto::ScoreTwoAuto(std::shared_ptr swerve, std::shared_ptr< double degrees = RobotParams::GetParam("arm.score_high.arm_setpoint", 0.0); double extend = RobotParams::GetParam("arm.score_high.extend_setpoint", 1.0); - double pickup_degrees = RobotParams::GetParam("arm.pickup.arm_setpoint", 0.0); - double pickup_extend = RobotParams::GetParam("arm.pickup.extend_setpoint", 1.0); - double negative_pickup_degrees = RobotParams::GetParam("arm.negative_pickup.arm_setpoint", 0.0); double negative_pickup_extend = RobotParams::GetParam("arm.negative_pickup.extend_setpoint", 1.0); diff --git a/src/main/cpp/commands/arm/MoveArmThenTiltCommand.cpp b/src/main/cpp/commands/arm/MoveArmThenTiltCommand.cpp deleted file mode 100644 index 5b1aade..0000000 --- a/src/main/cpp/commands/arm/MoveArmThenTiltCommand.cpp +++ /dev/null @@ -1,38 +0,0 @@ -#include "commands/arm/MoveArmThenTiltCommand.h" -#include "commands/intake/IntakePositionCommand.h" -#include "commands/arm/ArmSetStateCommand.h" - -MoveArmThenTiltCommand::MoveArmThenTiltCommand(std::shared_ptr move_intake, std::shared_ptr move_arm) { - move_intake_ = move_intake; - move_arm_ = move_arm; - - arm_good_ = false; - done_ = false; -} - -void MoveArmThenTiltCommand::Initialize() { - move_arm_->Initialize(); - - arm_good_ = false; - done_ = false; -} - -void MoveArmThenTiltCommand::Execute() { - if (!arm_good_) { - move_arm_->Execute(); - } - - if (move_arm_->IsFinished()) { - arm_good_ = true; - } - - if (arm_good_) { - move_intake_->Execute(); - - done_ = true; - } -} - -bool MoveArmThenTiltCommand::IsFinished() { - return done_; -} \ No newline at end of file diff --git a/src/main/cpp/commands/arm/TiltThenMoveArmCommand.cpp b/src/main/cpp/commands/arm/TiltThenMoveArmCommand.cpp deleted file mode 100644 index 8c292df..0000000 --- a/src/main/cpp/commands/arm/TiltThenMoveArmCommand.cpp +++ /dev/null @@ -1,38 +0,0 @@ -#include "commands/arm/TiltThenMoveArmCommand.h" -#include "commands/intake/IntakePositionCommand.h" -#include "commands/arm/ArmSetStateCommand.h" - -TiltThenMoveArmCommand::TiltThenMoveArmCommand(std::shared_ptr move_intake, std::shared_ptr move_arm) { - move_intake_ = move_intake; - move_arm_ = move_arm; - - intake_good = false; - done_ = false; -} - -void TiltThenMoveArmCommand::Initialize() { - move_intake_->Initialize(); - - intake_good = false; - done_ = false; -} - -void TiltThenMoveArmCommand::Execute() { - if (!intake_good) { - move_intake_->Execute(); - } - - if (move_intake_->IsFinished()) { - intake_good = true; - } - - if (intake_good) { - move_arm_->Execute(); - - done_ = true; - } -} - -bool TiltThenMoveArmCommand::IsFinished() { - return done_; -} \ No newline at end of file diff --git a/src/main/cpp/commands/intake/FieldOrientedIntakeCommand.cpp b/src/main/cpp/commands/intake/FieldOrientedIntakeCommand.cpp deleted file mode 100644 index 243c957..0000000 --- a/src/main/cpp/commands/intake/FieldOrientedIntakeCommand.cpp +++ /dev/null @@ -1,53 +0,0 @@ -#include -#include - -#include "Utils.h" -#include "subsystems/Intake.h" - -#include "commands/intake/FieldOrientedIntakeCommand.h" - -FieldOrientedIntakeCommand::FieldOrientedIntakeCommand(std::shared_ptr intake, std::shared_ptr swerve, double angle, double reverse_angle) { - // Set everything. - intake_ = intake; - angle_ = angle; - swerve_drive_ = swerve; - reverse_angle_ = reverse_angle; - - if (intake_ != nullptr) { - this->AddRequirements(intake_.get()); - } -} - -void FieldOrientedIntakeCommand::Initialize() { - VOKC_CHECK(intake_ != nullptr) - VOKC_CALL(intake_->SetControlMode(Auto)); -} - - -void FieldOrientedIntakeCommand::Execute() { - VOKC_CHECK(intake_ != nullptr); - - // get the current robot heading - double heading = 0.0; - VOKC_CALL(swerve_drive_->GetHeading(&heading)); - - // convert to [-180, 180] - TeamOKC::WrapAngle(&heading); - - // if the heading is pointing away from the scoring area - if (abs(heading) < 90.0) { - // score on the normal side of the robot - // set the desired state of the arm - VOKC_CALL(intake_->SetIntakeTilt(angle_)); - } else { - // otherwise, score on the other side - // set the desired state of the arm - VOKC_CALL(intake_->SetIntakeTilt(reverse_angle_)); - } - -} - -bool FieldOrientedIntakeCommand::IsFinished() { - // Always end this command. - return true; -} \ No newline at end of file diff --git a/src/main/cpp/commands/intake/IncrementIntakePositionCommand.cpp b/src/main/cpp/commands/intake/IncrementIntakePositionCommand.cpp deleted file mode 100644 index e57680b..0000000 --- a/src/main/cpp/commands/intake/IncrementIntakePositionCommand.cpp +++ /dev/null @@ -1,33 +0,0 @@ -#include -#include - -#include "Utils.h" -#include "subsystems/Intake.h" - -#include "commands/intake/IncrementIntakePositionCommand.h" - -IncrementIntakePositionCommand::IncrementIntakePositionCommand(std::shared_ptr intake, double angle) { - // Set everything. - intake_ = intake; - angle_ = angle; - - if (intake_ != nullptr) { - this->AddRequirements(intake_.get()); - } -} - -void IncrementIntakePositionCommand::Initialize() { - VOKC_CHECK(intake_ != nullptr); - VOKC_CALL(intake_->SetControlMode(Auto)); -} - - -void IncrementIntakePositionCommand::Execute() { - VOKC_CHECK(intake_ != nullptr); - VOKC_CALL(intake_->IncrementIntakeTilt(angle_)); -} - -bool IncrementIntakePositionCommand::IsFinished() { - // Always end this command. - return true; -} \ No newline at end of file diff --git a/src/main/cpp/commands/intake/IntakeBlockingPositionCommand.cpp b/src/main/cpp/commands/intake/IntakeBlockingPositionCommand.cpp deleted file mode 100644 index 4f9be9f..0000000 --- a/src/main/cpp/commands/intake/IntakeBlockingPositionCommand.cpp +++ /dev/null @@ -1,38 +0,0 @@ -#include -#include - -#include "Utils.h" -#include "subsystems/Intake.h" - -#include "commands/intake/IntakeBlockingPositionCommand.h" - -IntakeBlockingPositionCommand::IntakeBlockingPositionCommand(std::shared_ptr intake, double angle) { - // Set everything. - intake_ = intake; - angle_ = angle; - - if (intake_ != nullptr) { - this->AddRequirements(intake_.get()); - } -} - -void IntakeBlockingPositionCommand::Initialize() { - VOKC_CHECK(intake_ != nullptr) - VOKC_CALL(intake_->SetControlMode(Auto)); -} - - -void IntakeBlockingPositionCommand::Execute() { - VOKC_CHECK(intake_ != nullptr); - VOKC_CALL(intake_->SetIntakeTilt(angle_)); -} - -bool IntakeBlockingPositionCommand::IsFinished() { - // bool at = false; - - // OKC_CALL(intake_->AtSetpoint(&at)); - - // return at; - - return true; -} \ No newline at end of file diff --git a/src/main/cpp/commands/intake/IntakePositionCommand.cpp b/src/main/cpp/commands/intake/IntakePositionCommand.cpp deleted file mode 100644 index 8d2d26b..0000000 --- a/src/main/cpp/commands/intake/IntakePositionCommand.cpp +++ /dev/null @@ -1,50 +0,0 @@ -#include -#include - -#include "Utils.h" -#include "subsystems/Intake.h" - -#include "commands/intake/IntakePositionCommand.h" - -IntakePositionCommand::IntakePositionCommand(std::shared_ptr intake, double angle) { - // Set everything. - intake_ = intake; - angle_ = angle; - - if (intake_ != nullptr) { - this->AddRequirements(intake_.get()); - } -} - -void IntakePositionCommand::Initialize() { - VOKC_CHECK(intake_ != nullptr) - VOKC_CALL(intake_->SetControlMode(Auto)); -} - - -void IntakePositionCommand::Execute() { - VOKC_CHECK(intake_ != nullptr); - - // if the setpoint is 0 - if (angle_ == 0) { - // then we have to do some special stuff because we can't have the wrist be at 0 inside the robot with a game piece, so we want to slide it either to 80 or -80 - - double tilt = 0.0; - VOKC_CALL(intake_->GetIntakeTilt(&tilt)); - - // if we're already more than 0, send it to positive 80 - if (tilt > 0) { - intake_->SetIntakeTilt(70); - } else { - // otherwise slide it to -80 - intake_->SetIntakeTilt(-70); - } - } else { - VOKC_CALL(intake_->SetIntakeTilt(angle_)); - } -} - -bool IntakePositionCommand::IsFinished() { - // Always end this command. - return true; -} \ No newline at end of file diff --git a/src/main/cpp/hardware/Hardware.cpp b/src/main/cpp/hardware/Hardware.cpp index a96a64e..7582670 100644 --- a/src/main/cpp/hardware/Hardware.cpp +++ b/src/main/cpp/hardware/Hardware.cpp @@ -120,8 +120,6 @@ bool SetupIntakeInterface(std::unique_ptr &hardware, std::shared_ptrintake_motor.get(), sensors->intake_encoder.get(), - actuators->wrist_motor.get(), - sensors->wrist_encoder.get() }; interface = std::make_shared(intake_interface); diff --git a/src/main/cpp/io/IntakeIO.cpp b/src/main/cpp/io/IntakeIO.cpp index 0144a4a..a2112e9 100644 --- a/src/main/cpp/io/IntakeIO.cpp +++ b/src/main/cpp/io/IntakeIO.cpp @@ -2,7 +2,8 @@ #include "Parameters.h" bool IntakeIO::Init() { - offset_ = RobotParams::GetParam("intake.tilt_offset", 0.0); + + hw_interface_->intake_motor->SetSmartCurrentLimit(30); hw_interface_->intake_motor->SetSmartCurrentLimit(30); @@ -45,15 +46,10 @@ bool IntakeIO::ProcessIO() { OKC_CHECK(hw_interface_->intake_motor != nullptr); sw_interface_->intake_encoder = hw_interface_->intake_encoder->GetPosition(); - // wrist encoder - OKC_CHECK(hw_interface_->wrist_encoder != nullptr); - sw_interface_->tilt_encoder = hw_interface_->wrist_encoder->GetAbsolutePosition() * 360.0 + offset_; - TeamOKC::WrapAngle(&sw_interface_->tilt_encoder); + // === outputs === hw_interface_->intake_motor->Set(sw_interface_->intake_power); - hw_interface_->wrist_motor->Set(sw_interface_->tilt_power); - return true; } diff --git a/src/main/cpp/subsystems/Arm.cpp b/src/main/cpp/subsystems/Arm.cpp index 0a8e6bb..cbd50f6 100644 --- a/src/main/cpp/subsystems/Arm.cpp +++ b/src/main/cpp/subsystems/Arm.cpp @@ -277,14 +277,14 @@ bool Arm::AutoControl() { void Arm::Periodic() { - if (ArmUI::nt_manual_arm_mode->GetBoolean(false)){ + if (ArmUI::nt_test_mode->GetBoolean(false)) { + mode_ = Test; + } else if (ArmUI::nt_manual_arm_mode->GetBoolean(false)) { mode_ = Manual; - } - - else { + } else { mode_ = Auto; - } + // control the arm either using the raw axis values or PID controllers switch (mode_) { case Auto: diff --git a/src/main/cpp/subsystems/Intake.cpp b/src/main/cpp/subsystems/Intake.cpp index 5410d42..529121b 100644 --- a/src/main/cpp/subsystems/Intake.cpp +++ b/src/main/cpp/subsystems/Intake.cpp @@ -4,93 +4,37 @@ //pulls PID values from the parameters.toml file bool Intake::Init() { - OKC_CHECK(this->interface_ != nullptr); - - // the PID controller for the wrist - double wrist_kP = RobotParams::GetParam("intake.wrist_pid.kP", 0.005); - double wrist_kI = RobotParams::GetParam("intake.wrist_pid.kI", 0.0); - double wrist_kD = RobotParams::GetParam("intake.wrist_pid.kD", 0.0); - wrist_pid_ = std::make_shared(wrist_kP, wrist_kI, wrist_kD); - wrist_pid_->SetTolerance(7, 10); - - setpoint_log_ = wpi::log::DoubleLogEntry(TeamOKC::log, "/tilt/setpoint"); - output_log_ = wpi::log::DoubleLogEntry(TeamOKC::log, "/tilt/output"); - encoder_log_ = wpi::log::DoubleLogEntry(TeamOKC::log, "/tilt/encoder"); - - wrist_pid_->SetSetpoint(0.0); - return true; } -bool Intake::Reset() { - OKC_CHECK(this->interface_ != nullptr); - - this->wrist_pid_->Reset(); +bool Intake::SetControlMode(const ControlMode &mode) { + mode_= mode; return true; -} - -bool Intake::GetIntakeTilt(double *tilt) { - OKC_CHECK(interface_ != nullptr); - - *tilt = interface_->tilt_encoder; - return true; } + bool Intake::SetIntakePower(double power) { intake_power_ = power; return true; } -bool Intake::SetIntakeTilt(double degrees) { - OKC_CHECK(this->wrist_pid_ != nullptr); - - this->wrist_pid_->SetSetpoint(degrees); - - return true; -} - -bool Intake::IncrementIntakeTilt(double degrees) { - OKC_CHECK(this->wrist_pid_ != nullptr); - - this->wrist_pid_->SetSetpoint(this->wrist_pid_->GetSetpoint() + degrees); - - return true; -} - -bool Intake::SetControlMode(const ControlMode &mode) { - mode_= mode; - - return true; -} - bool Intake::ManualControl() { OKC_CHECK(interface_ != nullptr); interface_->intake_power = intake_power_; + return true; } + bool Intake::AutoControl() { OKC_CHECK(interface_ != nullptr); - OKC_CHECK(this->wrist_pid_ != nullptr); - interface_->tilt_power = -this->wrist_pid_->Calculate(interface_->tilt_encoder); - TeamOKC::Clamp(-0.6, 0.6, &interface_->tilt_power); - interface_->intake_power = intake_power_; - - return true; -} - -bool Intake::AtSetpoint(bool *at) { - OKC_CHECK(interface_ != nullptr); - - *at = wrist_pid_->AtSetpoint(); - - return true; + return true; } void Intake::SimulationPeriodic() { @@ -98,6 +42,7 @@ void Intake::SimulationPeriodic() { } void Intake::Periodic() { + switch (mode_) { case Manual: VOKC_CALL(this->ManualControl()); @@ -106,15 +51,8 @@ void Intake::Periodic() { VOKC_CALL(this->AutoControl()); break; default: - VOKC_CHECK_MSG(false, "unhandled intake enum"); + VOKC_CHECK_MSG(false, "Unhandled enum"); } - - VOKC_CALL(IntakeUI::nt_tilt->SetDouble(this->interface_->tilt_encoder)); - VOKC_CALL(IntakeUI::nt_tilt_setpoint->SetDouble(this->wrist_pid_->GetSetpoint())); - - setpoint_log_.Append(this->wrist_pid_->GetSetpoint()); - output_log_.Append(this->interface_->tilt_power); - encoder_log_.Append(this->interface_->tilt_encoder); } diff --git a/src/main/cpp/subsystems/SwerveDrive.cpp b/src/main/cpp/subsystems/SwerveDrive.cpp index 82863fb..d22455a 100644 --- a/src/main/cpp/subsystems/SwerveDrive.cpp +++ b/src/main/cpp/subsystems/SwerveDrive.cpp @@ -90,8 +90,6 @@ bool SwerveDrive::Init() { // auton parameters run_up_speed_ = RobotParams::GetParam("auto_balance.run_up_speed", 0.4); - tilted_speed_ = RobotParams::GetParam("auto_balance.tilted_speed", 0.2); - tilted_threshold_ = RobotParams::GetParam("auto_balance.tilted_threshold", 13.0); reverse_threshold_ = RobotParams::GetParam("auto_balance.reverse_threshold", 1.0); pitch_threshold_ = RobotParams::GetParam("auto_balance.pitch_threshold", 1.0); drive_backward_speed_ = RobotParams::GetParam("auto_balance.drive_backward_speed", -0.15); @@ -375,17 +373,9 @@ bool SwerveDrive::AutoBalance(double sign) { OKC_CALL(this->right_front_module_->GetSteerOutput(&this->interface_->right_front_steer_motor_output)); OKC_CALL(this->right_back_module_->GetSteerOutput(&this->interface_->right_back_steer_motor_output)); - // once we've tilted enough, then we can move on to climbing slower to avoid rocketing over the thing - if (this->interface_->imu_pitch > tilted_threshold_*sign) { - balance_state_ = CLIMB; - } + } else if (balance_state_ == CLIMB) { - // drive slower - this->interface_->left_front_drive_motor_output = tilted_speed_ * sign; - this->interface_->left_back_drive_motor_output = tilted_speed_ * sign; - this->interface_->right_front_drive_motor_output = tilted_speed_ * sign; - this->interface_->right_back_drive_motor_output = tilted_speed_ * sign; - + // keep the wheels straight OKC_CALL(this->left_front_module_->SetAngle(0.0)); OKC_CALL(this->left_back_module_->SetAngle(0.0)); diff --git a/src/main/cpp/ui/UserInterface.cpp b/src/main/cpp/ui/UserInterface.cpp index 8073beb..bdfbbe6 100644 --- a/src/main/cpp/ui/UserInterface.cpp +++ b/src/main/cpp/ui/UserInterface.cpp @@ -60,6 +60,8 @@ namespace ArmUI { nt::GenericEntry *const nt_manual_arm_mode = nt_tab.Add("manual arm mode", false).GetEntry(); nt::GenericEntry *const arm_control_state = nt_tab.Add("arm control state", "init").GetEntry(); + nt::GenericEntry *const nt_test_mode = nt_tab.Add("test mode", false ).GetEntry(); + } namespace ClawUI { @@ -71,6 +73,5 @@ namespace ClawUI { namespace IntakeUI { frc::ShuffleboardTab &nt_tab = frc::Shuffleboard::GetTab("intake"); - nt::GenericEntry *const nt_tilt = nt_tab.Add("wrist encoder", 0.0).GetEntry(); - nt::GenericEntry *const nt_tilt_setpoint = nt_tab.Add("wrist setpoint", 0.0).GetEntry(); + } \ No newline at end of file diff --git a/src/main/include/RobotContainer.h b/src/main/include/RobotContainer.h index 7b784cd..214a4d0 100644 --- a/src/main/include/RobotContainer.h +++ b/src/main/include/RobotContainer.h @@ -45,15 +45,10 @@ #include "commands/arm/IncrementArmExtendCommand.h" #include "commands/arm/ArmFieldOrientedCommand.h" #include "commands/arm/ArmSetStateCommand.h" -#include "commands/arm/TiltThenMoveArmCommand.h" -#include "commands/arm/MoveArmThenTiltCommand.h" + //intake #include "commands/intake/IntakeCommand.h" -#include "commands/intake/IntakePositionCommand.h" -#include "commands/intake/IncrementIntakePositionCommand.h" -#include "commands/intake/FieldOrientedIntakeCommand.h" -#include "commands/intake/IntakeBlockingPositionCommand.h" // misc #include @@ -192,26 +187,4 @@ class RobotContainer { std::shared_ptr intake_command; std::shared_ptr other_intake_command; std::shared_ptr stop_intake_command; - - std::shared_ptr inc_wrist_tilt_command_; - std::shared_ptr dec_wrist_tilt_command_; - - std::shared_ptr tilt_pickup_reverse_command_; - std::shared_ptr tilt_pickup_command_; - std::shared_ptr tilt_carry_command_; - - std::shared_ptr tilt_mid_command_; - std::shared_ptr tilt_high_command_; - - std::shared_ptr tilt_human_player_command_; - - // sequential commands - std::shared_ptr pickup_command_; - std::shared_ptr pickup_reverse_command_; - - std::shared_ptr score_mid_command_; - std::shared_ptr score_high_command_; - std::shared_ptr carry_command_; - - std::shared_ptr human_player_command_; }; diff --git a/src/main/include/commands/arm/MoveArmThenTiltCommand.h b/src/main/include/commands/arm/MoveArmThenTiltCommand.h deleted file mode 100644 index dbc683a..0000000 --- a/src/main/include/commands/arm/MoveArmThenTiltCommand.h +++ /dev/null @@ -1,28 +0,0 @@ -#pragma once - -#include -#include - -#include "commands/intake/IntakeBlockingPositionCommand.h" -#include "commands/arm/ArmSetStateCommand.h" - -/** - * Move arm to a preset position - */ -class MoveArmThenTiltCommand - : public frc2::CommandHelper { -public: - explicit MoveArmThenTiltCommand(std::shared_ptr move_intake, std::shared_ptr move_arm); - - void Initialize() override; - void Execute() override; - bool IsFinished() override; - -private: - std::shared_ptr move_intake_; - std::shared_ptr move_arm_; - - bool arm_good_ = false; - bool done_ = false; - -}; \ No newline at end of file diff --git a/src/main/include/commands/arm/TiltThenMoveArmCommand.h b/src/main/include/commands/arm/TiltThenMoveArmCommand.h deleted file mode 100644 index 541fe76..0000000 --- a/src/main/include/commands/arm/TiltThenMoveArmCommand.h +++ /dev/null @@ -1,27 +0,0 @@ -#pragma once - -#include -#include - -#include "commands/intake/IntakeBlockingPositionCommand.h" -#include "commands/arm/ArmSetStateCommand.h" - -/** - * Move arm to a preset position - */ -class TiltThenMoveArmCommand - : public frc2::CommandHelper { -public: - explicit TiltThenMoveArmCommand(std::shared_ptr move_intake, std::shared_ptr move_arm); - - void Initialize() override; - void Execute() override; - bool IsFinished() override; - -private: - std::shared_ptr move_intake_; - std::shared_ptr move_arm_; - - bool intake_good = false; - bool done_ = false; -}; \ No newline at end of file diff --git a/src/main/include/commands/intake/FieldOrientedIntakeCommand.h b/src/main/include/commands/intake/FieldOrientedIntakeCommand.h deleted file mode 100644 index bb8ecdf..0000000 --- a/src/main/include/commands/intake/FieldOrientedIntakeCommand.h +++ /dev/null @@ -1,32 +0,0 @@ -#pragma once - -#include -#include - -#include "Utils.h" -#include "subsystems/Intake.h" -#include "subsystems/SwerveDrive.h" - -/** - * - */ -class FieldOrientedIntakeCommand - : public frc2::CommandHelper { -public: - /** - * Creates a new IncrementArmExtendCommand. - * - * @param arm The subsystem used by this command. - */ - explicit FieldOrientedIntakeCommand(std::shared_ptr intake, std::shared_ptr swerve, double angle, double reverse_angle); - - void Execute() override; - void Initialize() override; - bool IsFinished() override; - -private: - std::shared_ptr intake_; - std::shared_ptr swerve_drive_; - double angle_; - double reverse_angle_; -}; \ No newline at end of file diff --git a/src/main/include/commands/intake/IncrementIntakePositionCommand.h b/src/main/include/commands/intake/IncrementIntakePositionCommand.h deleted file mode 100644 index da4681d..0000000 --- a/src/main/include/commands/intake/IncrementIntakePositionCommand.h +++ /dev/null @@ -1,29 +0,0 @@ -#pragma once - -#include -#include - -#include "Utils.h" -#include "subsystems/Intake.h" - -/** - * - */ -class IncrementIntakePositionCommand - : public frc2::CommandHelper { -public: - /** - * Creates a new IncrementArmExtendCommand. - * - * @param arm The subsystem used by this command. - */ - explicit IncrementIntakePositionCommand(std::shared_ptr intake, double angle); - - void Execute() override; - void Initialize() override; - bool IsFinished() override; - -private: - std::shared_ptr intake_; - double angle_; -}; \ No newline at end of file diff --git a/src/main/include/commands/intake/IntakeBlockingPositionCommand.h b/src/main/include/commands/intake/IntakeBlockingPositionCommand.h deleted file mode 100644 index 5ef2288..0000000 --- a/src/main/include/commands/intake/IntakeBlockingPositionCommand.h +++ /dev/null @@ -1,29 +0,0 @@ -#pragma once - -#include -#include - -#include "Utils.h" -#include "subsystems/Intake.h" - -/** - * - */ -class IntakeBlockingPositionCommand - : public frc2::CommandHelper { -public: - /** - * Creates a new IncrementArmExtendCommand. - * - * @param arm The subsystem used by this command. - */ - explicit IntakeBlockingPositionCommand(std::shared_ptr intake, double angle); - - void Execute() override; - void Initialize() override; - bool IsFinished() override; - -private: - std::shared_ptr intake_; - double angle_; -}; \ No newline at end of file diff --git a/src/main/include/commands/intake/IntakePositionCommand.h b/src/main/include/commands/intake/IntakePositionCommand.h deleted file mode 100644 index 1d2ec17..0000000 --- a/src/main/include/commands/intake/IntakePositionCommand.h +++ /dev/null @@ -1,29 +0,0 @@ -#pragma once - -#include -#include - -#include "Utils.h" -#include "subsystems/Intake.h" - -/** - * - */ -class IntakePositionCommand - : public frc2::CommandHelper { -public: - /** - * Creates a new IncrementArmExtendCommand. - * - * @param arm The subsystem used by this command. - */ - explicit IntakePositionCommand(std::shared_ptr intake, double angle); - - void Execute() override; - void Initialize() override; - bool IsFinished() override; - -private: - std::shared_ptr intake_; - double angle_; -}; \ No newline at end of file diff --git a/src/main/include/hardware/Actuators.h b/src/main/include/hardware/Actuators.h index 5042f50..e500975 100644 --- a/src/main/include/hardware/Actuators.h +++ b/src/main/include/hardware/Actuators.h @@ -30,7 +30,6 @@ #define CLAW_MOTOR 12 #define INTAKE_MOTOR 12 -#define WRIST_MOTOR 13 typedef struct actuators_t { @@ -56,5 +55,4 @@ typedef struct actuators_t { //intake motors std::unique_ptr intake_motor; - std::unique_ptr wrist_motor; } Actuators; \ No newline at end of file diff --git a/src/main/include/hardware/Sensors.h b/src/main/include/hardware/Sensors.h index 8a34a53..d5e411c 100644 --- a/src/main/include/hardware/Sensors.h +++ b/src/main/include/hardware/Sensors.h @@ -18,7 +18,6 @@ // DIO ports (on the RIO) #define EXTEND_LIMIT_SWITCH 9 #define ARM_ABS_ENCODER 1 -#define WRIST_ABS_ENCODER 3 typedef struct sensors_t { // navX IMU @@ -54,5 +53,4 @@ typedef struct sensors_t { //intake sensord std::unique_ptr intake_encoder; - std::unique_ptr wrist_encoder; } Sensors; diff --git a/src/main/include/io/IntakeIO.h b/src/main/include/io/IntakeIO.h index d647b83..e24febb 100644 --- a/src/main/include/io/IntakeIO.h +++ b/src/main/include/io/IntakeIO.h @@ -19,20 +19,14 @@ typedef struct intake_config_t { typedef struct intake_hardware_interface_t { rev::CANSparkMax *const intake_motor; rev::RelativeEncoder *const intake_encoder; - - rev::CANSparkMax *const wrist_motor; - frc::DutyCycleEncoder *const wrist_encoder; // (rev through-bore encoder in the absolute position mode) } IntakeHardwareInterface; typedef struct intake_software_interface_t { // actuator outputs - double intake_power; - double tilt_power; - + double intake_power; // sensor inputs double intake_encoder; - double tilt_encoder; // config diff --git a/src/main/include/subsystems/Intake.h b/src/main/include/subsystems/Intake.h index 08a3c52..03e9c0e 100644 --- a/src/main/include/subsystems/Intake.h +++ b/src/main/include/subsystems/Intake.h @@ -20,10 +20,7 @@ class Intake : public frc2::SubsystemBase { bool Init(); bool SetIntakePower(double power); - bool SetIntakeTilt(double tilt); - bool GetIntakeTilt(double *tilt); - bool IncrementIntakeTilt(double inc); - + bool SetControlMode(const ControlMode &mode); bool ManualControl(); bool AutoControl(); @@ -37,7 +34,6 @@ class Intake : public frc2::SubsystemBase { private: IntakeSoftwareInterface *const interface_; - std::shared_ptr wrist_pid_; double intake_power_; diff --git a/src/main/include/subsystems/SwerveDrive.h b/src/main/include/subsystems/SwerveDrive.h index 565a278..fb3c331 100644 --- a/src/main/include/subsystems/SwerveDrive.h +++ b/src/main/include/subsystems/SwerveDrive.h @@ -119,8 +119,6 @@ class SwerveDrive : public frc2::SubsystemBase { BalanceState balance_state_ = RUN_UP; double run_up_speed_; - double tilted_speed_; - double tilted_threshold_; double reverse_threshold_; double pitch_threshold_; double drive_backward_speed_; diff --git a/src/main/include/ui/UserInterface.h b/src/main/include/ui/UserInterface.h index 73ecf2e..cbf0d46 100644 --- a/src/main/include/ui/UserInterface.h +++ b/src/main/include/ui/UserInterface.h @@ -57,6 +57,8 @@ namespace ArmUI { extern nt::GenericEntry *const nt_extend_setpoint; extern nt::GenericEntry *const nt_extend_power; extern nt::GenericEntry *const nt_limit_switch; + + extern nt::GenericEntry *const nt_test_mode; extern nt::GenericEntry *const nt_manual_arm_mode; // arm state @@ -72,6 +74,4 @@ namespace ClawUI { namespace IntakeUI { extern frc::ShuffleboardTab &nt_tab; - extern nt::GenericEntry *const nt_tilt; - extern nt::GenericEntry *const nt_tilt_setpoint; } \ No newline at end of file diff --git a/src/test/cpp/subsystems/intake_test.cpp b/src/test/cpp/subsystems/intake_test.cpp new file mode 100644 index 0000000..f790c0b --- /dev/null +++ b/src/test/cpp/subsystems/intake_test.cpp @@ -0,0 +1,47 @@ +#include +#include +#include + +#include + +#include "frc/geometry/Pose2d.h" + +#include "subsystems/Intake.h" +#include "io/IntakeIO.h" +#include "Parameters.h" + +class IntakeTest : public testing::Test { +public: + virtual void SetUp() { + intake_ = std::make_shared(&intake_interface_); + intake_->Init(); + // std::string deploy_path = frc::filesystem::GetDeployDirectory(); + // std::string param_file = deploy_path + "/parameters.toml"; + // RobotParams::LoadParameters(param_file); + } + +protected: + std::shared_ptr intake_; + + IntakeSoftwareInterface intake_interface_; +}; + +TEST_F(IntakeTest, InitIntake) { + ASSERT_TRUE(intake_->Init()); + +} + +TEST_F(IntakeTest, SetIntake) { + ASSERT_TRUE(intake_->SetControlMode()); + ASSERT_TRUE(intake_->SetIntakePower()); + ASSERT_TRUE(intake_->SetTurn()); + //TODO get value from mode + //EXPECT_EQ(mode_, Manual); + +} + +TEST_F(IntakeTest, ControlIntake) { + ASSERT_TRUE(intake_->ManualControl()); + ASSERT_TRUE(intake_->AutoControl()); + +} \ No newline at end of file