Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
23 commits
Select commit Hold shift + click to select a range
b640df0
code for new intake with wrist (#58)
danielbrownmsm Mar 23, 2023
3dd924a
feat/field-oriented-scoring (#62)
danielbrownmsm Mar 24, 2023
9759771
fix arm offset
danielbrownmsm Mar 25, 2023
1a284b5
Feat/wrist intake (#63)
danielbrownmsm Mar 25, 2023
25d4aeb
Merge branch 'scoring-integration' of https://github.com/Team-OKC-Rob…
danielbrownmsm Mar 25, 2023
298a021
fix intake wrist tilt encoder port
danielbrownmsm Mar 26, 2023
48aaeed
log the intake tilt output, setpoint, and sensor reading
danielbrownmsm Mar 26, 2023
b6f74a7
field-oriented intake tilting commands
danielbrownmsm Mar 26, 2023
0050fb7
wrap the tilt encoder because the zero-point is in a really annoying …
danielbrownmsm Mar 26, 2023
c7245a3
log the intake wrist values, and show them on shuffleboard,
danielbrownmsm Mar 26, 2023
917d674
if arm is close to 0 and trying to go to 0 then prevent it from oscil…
danielbrownmsm Mar 26, 2023
04c215f
added wrist setpoint to shuffleboard
danielbrownmsm Mar 26, 2023
e8aad74
made intake faster
danielbrownmsm Mar 26, 2023
5a33808
Merge branch 'master' into scoring-integration
danielbrownmsm Mar 26, 2023
895e017
started work on a command to pause auton execution for the arm
danielbrownmsm Mar 26, 2023
df3645d
Merge branch 'scoring-integration' of https://github.com/Team-OKC-Rob…
danielbrownmsm Mar 26, 2023
0408639
wrist setpoint on shuffleboard
danielbrownmsm Mar 27, 2023
fb8667c
fix extend thresholds/setpoints because we replaced the gearboxes
danielbrownmsm Mar 27, 2023
7b05742
intake wrist tilt tuning and fixing
danielbrownmsm Mar 27, 2023
3e82c1b
code no workey tilt then move claw arm thingy
danielbrownmsm Mar 27, 2023
563bdf3
Improved and Tuned Arm and Added ff to arm control
deadlyvortex Mar 28, 2023
24f12b4
Merge branch 'master' into Arm-Improvement-and-Tuning
danielbrownmsm Mar 30, 2023
8c1d3f6
fix PR comments
danielbrownmsm Apr 4, 2023
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ deploy {
def deployArtifact = deploy.targets.roborio.artifacts.frcCpp

// Set this to true to enable desktop support.
def includeDesktopSupport = false
def includeDesktopSupport = true

// Set to true to run simulation in debug mode
wpi.cpp.debugSimulation = false
Expand Down
1 change: 1 addition & 0 deletions src/main/cpp/RobotContainer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ bool RobotContainer::ConfigureButtonBindings() {
// second driver controls
manip_right_bumper_button_->WhenPressed(*pickup_command_);
manip_left_bumper_button_->WhenPressed(*pickup_reverse_command_);

manip_x_button_->WhenPressed(*carry_command_);

manip_b_button_->WhenPressed(*score_mid_command_);
Expand Down
11 changes: 11 additions & 0 deletions src/main/cpp/Utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,5 +32,16 @@ namespace TeamOKC {
double Radians(double degrees) {
return degrees * M_PI / 180.0;
}
double sign(double value) {
if (value>0) {
return 1;
}
if (value<0) {
return -1;
}
if (value==0) {
return 0;
}
}
} // namespace TeamOKC

11 changes: 10 additions & 1 deletion src/main/cpp/subsystems/Arm.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
#include "subsystems/Arm.h"
#include "Parameters.h"
#include "ui/UserInterface.h"
#include "Utils.h"


bool Arm::Init() {
// initializing the arm
Expand All @@ -10,8 +12,10 @@ bool Arm::Init() {
double arm_kP = RobotParams::GetParam("arm.lift_pid.kP", 0.005);
double arm_kI = RobotParams::GetParam("arm.lift_pid.kI", 0.0);
double arm_kD = RobotParams::GetParam("arm.lift_pid.kD", 0.0);
double arm_kF = RobotParams::GetParam("arm.lift_pid.kF", 0.05);
arm_pid_ = std::make_shared<frc::PIDController>(arm_kP, arm_kI, arm_kD);
arm_pid_->SetTolerance(2, 2);
arm_kF_ = arm_kF;

double extend_kP = RobotParams::GetParam("arm.extend_pid.kP", 0.005);
double extend_kI = RobotParams::GetParam("arm.extend_pid.kI", 0.0);
Expand Down Expand Up @@ -42,6 +46,7 @@ bool Arm::Init() {
return true;
}


bool Arm::SetControlMode(const ControlMode &mode){
mode_= mode;

Expand Down Expand Up @@ -146,8 +151,12 @@ bool Arm::TestControl() {
this->arm_pid_->SetSetpoint(this->desired_state_.rotation);
this->inches_pid_->SetSetpoint(this->desired_state_.extension);

// calculate feedforward
// take the sign of the desired state, multiply it by the feedforward gain times the desired rotation squared. this looks like output = signum(setpoint) * kF * setpoint^2
double ff = TeamOKC::sign(this->desired_state_.rotation) * arm_kF_ * this->desired_state_.rotation * this->desired_state_.rotation;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

add a comment about what this is actually doing


// set output
this->interface_->arm_lift_power = this->arm_pid_->Calculate(this->state_.rotation);
this->interface_->arm_lift_power = this->arm_pid_->Calculate(this->state_.rotation) + ff;
this->interface_->arm_extend_power = this->inches_pid_->Calculate(this->state_.extension);

return true;
Expand Down
2 changes: 1 addition & 1 deletion src/main/deploy/parameters.toml
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ arm_setpoint = 94.0
intake_setpoint = -40.0

[arm.negative_pickup]
extend_setpoint = 50.0
extend_setpoint = 20.0
arm_setpoint = -25.0
intake_setpoint = -70.0

Expand Down
1 change: 1 addition & 0 deletions src/main/include/Utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@ namespace TeamOKC {

bool WrapAngle(double *angle);
double Radians(double degrees);
double sign(double value);

typedef struct arm_state_t {
double extension;
Expand Down
2 changes: 2 additions & 0 deletions src/main/include/subsystems/Arm.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
#include <frc2/command/SubsystemBase.h>
#include <io/ArmIO.h>
#include <memory>
#include "Utils.h"

#include "Logging.h"
#include "wpi/DataLog.h"
Expand Down Expand Up @@ -56,6 +57,7 @@ class Arm : public frc2::SubsystemBase {
// PID controllers
std::shared_ptr<frc::PIDController> arm_pid_;
std::shared_ptr<frc::PIDController> inches_pid_;
double arm_kF_;

// controls stuff (I'd call it a state machine but it isn't really a state machine)
ControlMode mode_;
Expand Down