Skip to content
This repository has been archived by the owner on Apr 15, 2024. It is now read-only.

Commit

Permalink
fix warnings (CurtinFRC#82)
Browse files Browse the repository at this point in the history
  • Loading branch information
spacey-sooty authored Jan 11, 2024
1 parent fde8fe3 commit 01d1e46
Show file tree
Hide file tree
Showing 6 changed files with 8 additions and 24 deletions.
9 changes: 1 addition & 8 deletions src/main/cpp/Robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,8 @@
#include <units/time.h>
#include <units/voltage.h>

// include frc::DriveKinematics
#include <frc/kinematics/DifferentialDriveKinematics.h>

// include frc::RamseteController
#include <frc/controller/RamseteController.h>

// include frc::Timer
#include <frc/Timer.h>

static units::second_t lastPeriodic;
Expand Down Expand Up @@ -78,9 +73,7 @@ void Robot::TeleopInit() {
// _swerveDrive->OnStart();
// sched->InterruptAll();
}
void Robot::TeleopPeriodic() {
auto dt = wom::now() - lastPeriodic;
}
void Robot::TeleopPeriodic() {}

void Robot::DisabledInit() {}
void Robot::DisabledPeriodic() {}
Expand Down
2 changes: 1 addition & 1 deletion src/main/include/Robot.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,13 +11,13 @@
#include <frc/simulation/DifferentialDrivetrainSim.h>
#include <frc/simulation/EncoderSim.h>
#include <frc/smartdashboard/Field2d.h>
#include <frc/smartdashboard/SendableChooser.h>
#include <frc/smartdashboard/SmartDashboard.h>

#include <string>

#include "RobotMap.h"
#include "Wombat.h"
#include "frc/smartdashboard/SendableChooser.h"

class Robot : public frc::TimedRobot {
public:
Expand Down
11 changes: 3 additions & 8 deletions wombat/src/main/cpp/drivetrain/behaviours/SwerveBehaviours.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ ManualDrivebase::ManualDrivebase(wom::drivetrain::SwerveDrive* swerveDrivebase,
Controls(swerveDrivebase);
}

void ManualDrivebase::OnStart(units::second_t dt) {
void ManualDrivebase::OnStart() {
_swerveDrivebase->OnStart();
_swerveDrivebase->SetAccelerationLimit(6_mps_sq);
std::cout << "Manual Drivebase Start" << std::endl;
Expand All @@ -51,7 +51,7 @@ void ManualDrivebase::OnTick(units::second_t deltaTime) {
if (_driverController->GetLeftBumperPressed()) {
maxMovementMagnitude = lowSensitivityDriveSpeed;
maxRotationMagnitude = lowSensitivityRotateSpeed;
} else if (_driverController->GetLeftBumperReleased() &
} else if (_driverController->GetLeftBumperReleased() &&
!_driverController->GetRightBumper()) {
maxMovementMagnitude = defaultDriveSpeed;
maxRotationMagnitude = defaultRotateSpeed;
Expand All @@ -64,7 +64,7 @@ void ManualDrivebase::OnTick(units::second_t deltaTime) {
_swerveDrivebase->SetAccelerationLimit(12_mps_sq);
_swerveDrivebase->SetVoltageLimit(14_V);

} else if (_driverController->GetRightBumperReleased() &
} else if (_driverController->GetRightBumperReleased() &&
!_driverController->GetLeftBumper()) {
maxMovementMagnitude = defaultDriveSpeed;
maxRotationMagnitude = defaultRotateSpeed;
Expand All @@ -87,8 +87,6 @@ void ManualDrivebase::OnTick(units::second_t deltaTime) {

double r_x = wom::utils::spow2(
-wom::utils::deadzone(_driverController->GetRightX(), turningDeadzone));
double r_y = wom::utils::spow2(
-wom::utils::deadzone(_driverController->GetRightY(), turningDeadzone));

double turnX = _driverController->GetRightX();
double turnY = _driverController->GetRightY();
Expand Down Expand Up @@ -188,9 +186,6 @@ void wom::drivetrain::behaviours::TempSimSwerveDrive::OnUpdate() {
frc::Trajectory::State desired_state =
current_trajectory.Sample(m_timer->Get());

// get the current pose of the robot
frc::Pose2d current_pose = m_driveSim.GetPose();

// get the current wheel speeds
wom::utils::WriteTrajectoryState(current_trajectory_state_table,
desired_state);
Expand Down
4 changes: 2 additions & 2 deletions wombat/src/main/cpp/utils/Encoder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@ wom::utils::Encoder::Encoder(double encoderTicksPerRotation, int type,
units::meter_t wheelRadius, double reduction)
: _reduction(reduction),
_encoderTicksPerRotation(encoderTicksPerRotation),
_wheelRadius(wheelRadius),
_type(type) {}
_type(type),
_wheelRadius(wheelRadius) {}

double wom::utils::Encoder::GetEncoderTicks() const {
return GetEncoderRawTicks();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,7 @@

#include "behaviour/Behaviour.h"
#include "drivetrain/SwerveDrive.h"
#include "frc/smartdashboard/SendableChooser.h"
#include "utils/Pathplanner.h"
#include "utils/Util.h"

namespace wom {
namespace drivetrain {
Expand Down Expand Up @@ -49,7 +47,7 @@ class ManualDrivebase : public behaviour::Behaviour {
*/
void CalculateRequestedAngle(double joystickX, double joystickY,
units::degree_t defaultAngle);
void OnStart(units::second_t dt);
void OnStart() override;
void ResetMode();

private:
Expand Down
2 changes: 0 additions & 2 deletions wombat/src/main/include/vision/Limelight.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,6 @@
#include <utility>
#include <vector>

#include "behaviour/HasBehaviour.h"

namespace wom {
namespace vision {

Expand Down

0 comments on commit 01d1e46

Please sign in to comment.