Skip to content

Commit

Permalink
fix build
Browse files Browse the repository at this point in the history
  • Loading branch information
spacey-sooty committed Mar 21, 2024
1 parent 5a388c0 commit 2f929bd
Show file tree
Hide file tree
Showing 7 changed files with 115 additions and 17 deletions.
1 change: 1 addition & 0 deletions networktables.json
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
[]
92 changes: 92 additions & 0 deletions simgui-ds.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,92 @@
{
"keyboardJoysticks": [
{
"axisConfig": [
{
"decKey": 65,
"incKey": 68
},
{
"decKey": 87,
"incKey": 83
},
{
"decKey": 69,
"decayRate": 0.0,
"incKey": 82,
"keyRate": 0.009999999776482582
}
],
"axisCount": 3,
"buttonCount": 4,
"buttonKeys": [
90,
88,
67,
86
],
"povConfig": [
{
"key0": 328,
"key135": 323,
"key180": 322,
"key225": 321,
"key270": 324,
"key315": 327,
"key45": 329,
"key90": 326
}
],
"povCount": 1
},
{
"axisConfig": [
{
"decKey": 74,
"incKey": 76
},
{
"decKey": 73,
"incKey": 75
}
],
"axisCount": 2,
"buttonCount": 4,
"buttonKeys": [
77,
44,
46,
47
],
"povCount": 0
},
{
"axisConfig": [
{
"decKey": 263,
"incKey": 262
},
{
"decKey": 265,
"incKey": 264
}
],
"axisCount": 2,
"buttonCount": 6,
"buttonKeys": [
260,
268,
266,
261,
269,
267
],
"povCount": 0
},
{
"axisCount": 0,
"buttonCount": 0,
"povCount": 0
}
]
}
11 changes: 11 additions & 0 deletions simgui.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
{
"NTProvider": {
"types": {
"/FMSInfo": "FMSInfo",
"/SmartDashboard/Auto Selector": "String Chooser"
}
},
"NetworkTables Info": {
"visible": true
}
}
5 changes: 0 additions & 5 deletions src/main/cpp/AlphaArm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@ void AlphaArm::OnUpdate(units::second_t dt) {
_setAlphaArmVoltage = 0_V;
break;
case AlphaArmState::kRaw:
std::cout << "RawControl" << std::endl;
_setAlphaArmVoltage = _rawArmVoltage;

break;
Expand Down Expand Up @@ -73,8 +72,6 @@ void AlphaArm::OnUpdate(units::second_t dt) {
}
_config->alphaArmGearbox.motorController->SetVoltage(_setAlphaArmVoltage);
_config->alphaArmGearbox2.motorController->SetVoltage(_setAlphaArmVoltage);
std::cout << "Encoder Value: " << (_config->alphaArmEncoder.GetEncoderPosition().value() * (2 * 3.1415))
<< std::endl;
_table->GetEntry("PID Error").SetDouble(_pidArm.GetPositionError());
_table->GetEntry("SetPoint").SetDouble(_pidArm.GetSetpoint());
_table->GetEntry("Input").SetDouble((_config->alphaArmEncoder.GetEncoderPosition().value() * (2 * 3.1415)));
Expand All @@ -84,8 +81,6 @@ void AlphaArm::OnUpdate(units::second_t dt) {

_table->GetEntry("Intake SetPoint State").SetDouble(_pidIntakeState.GetSetpoint());
_table->GetEntry("Intake PID Error State").SetDouble(_pidIntakeState.GetPositionError());

std::cout << "Voltage:" << _setAlphaArmVoltage.value() << std::endl;
}

void AlphaArm::SetState(AlphaArmState state) {
Expand Down
3 changes: 1 addition & 2 deletions src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,8 +152,7 @@ void Robot::TeleopInit() {
wom::BehaviourScheduler* sched = wom::BehaviourScheduler::GetInstance();
sched->InterruptAll();

robotmap.controllers.triggerDriver->XButton()->SetTrueBehaviour(
wom::make<wom::DrivebasePoseBehaviour>(_swerveDrive, frc::Pose2d(1_m, 0_m, frc::Rotation2d(0_rad))));
robotmap.controllers.triggerDriver->XButton()->SetTrueBehaviour(wom::make<wom::XDrivebase>(_swerveDrive));
}

void Robot::TeleopPeriodic() {}
Expand Down
10 changes: 5 additions & 5 deletions wombat/src/main/cpp/behaviour/Trigger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,13 @@ Trigger::Trigger(std::function<bool()> condition, std::string name) : k_name{nam
behaviour::BehaviourScheduler::GetInstance()->AddTrigger(this);
}

Trigger::Trigger(std::function<bool()> condition, std::string name, Behaviour* true_behaviour)
Trigger::Trigger(std::function<bool()> condition, std::string name, Behaviour::ptr&& true_behaviour)
: k_name{name}, m_condition(condition), m_true_behaviour{true_behaviour} {
behaviour::BehaviourScheduler::GetInstance()->AddTrigger(this);
}

Trigger::Trigger(std::function<bool()> condition, std::string name, Behaviour* true_behaviour,
Behaviour* false_behaviour)
Trigger::Trigger(std::function<bool()> condition, std::string name, Behaviour::ptr&& true_behaviour,
Behaviour::ptr&& false_behaviour)
: k_name{name},
m_condition(condition),
m_true_behaviour{true_behaviour},
Expand Down Expand Up @@ -55,11 +55,11 @@ void Trigger::OnTick() {
std::cerr << "WARNING: No OnFalse behaviour specified for Trigger " << k_name << std::endl;
}

void Trigger::SetTrueBehaviour(Behaviour::ptr behaviour) {
void Trigger::SetTrueBehaviour(Behaviour::ptr&& behaviour) {
m_true_behaviour = behaviour;
}

void Trigger::SetFalseBehaviour(Behaviour::ptr behaviour) {
void Trigger::SetFalseBehaviour(Behaviour::ptr&& behaviour) {
m_false_behaviour = behaviour;
}

Expand Down
10 changes: 5 additions & 5 deletions wombat/src/main/include/behaviour/Trigger.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ class Trigger {
* @param name The name of the trigger, useful in debugging.
* @param true_behaviour The behaviour to run when the condition is true.
*/
Trigger(std::function<bool()> condition, std::string name, Behaviour* true_behaviour);
Trigger(std::function<bool()> condition, std::string name, Behaviour::ptr&& true_behaviour);

/**
* Creates a new Trigger that returns a boolean based off the provided condition.
Expand All @@ -60,8 +60,8 @@ class Trigger {
* @param true_behaviour The behaviour to run when the condition is true.
* @param false_behaviour The behaviour to run when the condition is false.
*/
Trigger(std::function<bool()> condition, std::string name, Behaviour* true_behaviour,
Behaviour* false_behaviour);
Trigger(std::function<bool()> condition, std::string name, Behaviour::ptr&& true_behaviour,
Behaviour::ptr&& false_behaviour);

~Trigger() = default;
Trigger(Trigger&&) = default;
Expand All @@ -83,14 +83,14 @@ class Trigger {
*
* @param behaviour The behaviour to run on true.
*/
void SetTrueBehaviour(Behaviour::ptr behaviour);
void SetTrueBehaviour(Behaviour::ptr&& behaviour);

/**
* Sets the false behaviour to the provided behaviour.
*
* @param behaviour The behaviour to run on false.
*/
void SetFalseBehaviour(Behaviour::ptr behaviour);
void SetFalseBehaviour(Behaviour::ptr&& behaviour);

/**
* Returns a Trigger* which will be true when m_condition is not.
Expand Down

0 comments on commit 2f929bd

Please sign in to comment.