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

Commit c64ee0c

Browse files
committed
Revert "Merge pull request #38 from frc5024/encoder"
This reverts commit 1eb160b, reversing changes made to dc4da2e.
1 parent 1eb160b commit c64ee0c

File tree

16 files changed

+19
-209
lines changed

16 files changed

+19
-209
lines changed

.vscode/settings.json

+1-3
Original file line numberDiff line numberDiff line change
@@ -14,9 +14,7 @@
1414
"C_Cpp.default.configurationProvider": "vscode-wpilib",
1515
"wpilib.online": true,
1616
"files.associations": {
17-
"*.tidal": "haskell",
1817
"condition_variable": "cpp",
19-
"*.inc": "cpp",
20-
"iostream": "cpp"
18+
"*.inc": "cpp"
2119
}
2220
}

PathWeaver/Paths/AutoLL_0.path

-8
This file was deleted.

build.gradle

-3
Original file line numberDiff line numberDiff line change
@@ -54,15 +54,12 @@ model {
5454
sources.cpp {
5555
source {
5656
srcDir 'src/main/cpp'
57-
srcDir 'rrlib/src/main/cpp'
5857
include '**/*.cpp', '**/*.cc'
5958
}
6059
exportedHeaders {
6160
srcDir 'src/main/include'
62-
srcDir 'rrlib/src/main/include'
6361
if (includeSrcInIncludeRoot) {
6462
srcDir 'src/main/cpp'
65-
srcDir 'rrlib/src/main/cpp'
6663
}
6764
}
6865
}

rrlib/src/main/cpp/Components/Encoder.cpp

-45
This file was deleted.

rrlib/src/main/cpp/Utils/File.cpp

-7
This file was deleted.

rrlib/src/main/include/Components/Encoder.h

-38
This file was deleted.

rrlib/src/main/include/Components/GearBox.h

-18
This file was deleted.

rrlib/src/main/include/Utils/File.h

-13
This file was deleted.

src/main/cpp/Subsystems/Arm.cpp

+2-3
Original file line numberDiff line numberDiff line change
@@ -11,8 +11,6 @@ Arm::Arm() : Subsystem("Arm") {
1111
this->pArmMotor2->SetNeutralMode(NeutralMode::Brake);
1212

1313
this->pArmMotor2->SetSafetyEnabled(false);
14-
15-
this->pArmGearBox->motor = new frc::SpeedControllerGroup(*this->pArmMotor, *this->pArmMotor2);
1614
}
1715

1816
void Arm::InitDefaultCommand() {
@@ -21,7 +19,8 @@ void Arm::InitDefaultCommand() {
2119
}
2220

2321
void Arm::MoveArm(double Speed) {
24-
this->pArmGearBox->motor->Set(Speed);
22+
this->pArmMotor->Set(Speed);
23+
this->pArmMotor2->Set(Speed);
2524
}
2625

2726
double Arm::getDistanceFromFloor() {

src/main/cpp/Subsystems/DriveTrain.cpp

+10-25
Original file line numberDiff line numberDiff line change
@@ -1,32 +1,27 @@
11
#include "Subsystems/DriveTrain.h"
2-
#include "DeviceMap.h"
3-
#include <iostream>
42

5-
6-
/* DriveTrain */
73
DriveTrain::DriveTrain() : frc::Subsystem("DriveTrain") {
84
// Initialize the motors
95
this->pLeftFrontMotor = new can::WPI_TalonSRX(DRIVETRAIN_LEFT_FRONT_MOTOR);
106
this->pLeftRearMotor = new can::WPI_TalonSRX(DRIVETRAIN_LEFT_REAR_MOTOR);
7+
this->pLeftRearMotor->Follow(*pLeftFrontMotor);
118

129
this->pLeftFrontMotor->SetInverted(false);
1310
this->pLeftRearMotor->SetInverted(false);
11+
// this->pLeftFrontMotor->SetNeutralMode(NeutralMode::Brake);
12+
// this->pLeftRearMotor->SetNeutralMode(NeutralMode::Brake);
1413

1514
this->pRightFrontMotor = new can::WPI_TalonSRX(DRIVETRAIN_RIGHT_FRONT_MOTOR);
1615
this->pRightRearMotor = new can::WPI_TalonSRX(DRIVETRAIN_RIGHT_REAR_MOTOR);
16+
this->pRightRearMotor->Follow(*pRightFrontMotor);
1717

18-
this->pRightFrontMotor->SetInverted(false);
19-
this->pRightRearMotor->SetInverted(false);
18+
this->pRightFrontMotor->SetInverted(true); // change this based on test or production robot
19+
this->pRightRearMotor->SetInverted(true); // change this based on test or production robot
20+
// this->pRightFrontMotor->SetNeutralMode(NeutralMode::Brake);
21+
// this->pRightRearMotor->SetNeutralMode(NeutralMode::Brake);
2022

2123
// Create a DifferentialDrive class using our motors
22-
this->pLeftGearBox->motor = new frc::SpeedControllerGroup(*this->pLeftFrontMotor, *this->pLeftRearMotor);
23-
this->pLeftGearBox->sensor = new rr::components::TalonAdapter(this->pLeftFrontMotor, WHEEL_CIRCUM_CM, TALLON_TPR, false);
24-
this->pLeftGearBox->sensor->Reset();
25-
26-
this->pRightGearBox->motor = new frc::SpeedControllerGroup(*this->pRightFrontMotor, *this->pRightRearMotor);
27-
this->pRightGearBox->sensor = new rr::components::TalonAdapter(this->pRightFrontMotor, WHEEL_CIRCUM_CM, TALLON_TPR, true);
28-
29-
this->pRobotDrive = new frc::DifferentialDrive(*this->pLeftGearBox->motor, *this->pRightGearBox->motor);
24+
this->pRobotDrive = new frc::DifferentialDrive(*pLeftFrontMotor, *pRightFrontMotor);
3025

3126
// Disable saftey modes
3227
// Sounds like a bad idea, but this prevents the robot from locking up if we take too long on a loop
@@ -42,9 +37,7 @@ void DriveTrain::InitDefaultCommand() {
4237
}
4338

4439
void DriveTrain::ArcadeDrive(double xSpeed, double zRotation) {
45-
this->pRobotDrive->ArcadeDrive(xSpeed, zRotation); // Pass through to robot drive
46-
// The following line is for debugging encoders
47-
// std::cout << "Left: " << this->pLeftGearBox->sensor->GetTicks() << " Right: " << this->pRightGearBox->sensor->GetTicks() << std::endl;
40+
this->pRobotDrive->ArcadeDrive(zRotation, xSpeed); // API parameter order is incorrect
4841
return;
4942
}
5043

@@ -70,12 +63,4 @@ void DriveTrain::RadialDrive(double magnitude, double radial){
7063
// pass to tankdrive
7164
this->pRobotDrive->TankDrive(leftSpeed, rightSpeed);
7265
return;
73-
}
74-
75-
int DriveTrain::GetLeftEncoderPosition(){
76-
return this->pLeftGearBox->sensor->GetTicks();
77-
}
78-
79-
int DriveTrain::GetRightEncoderPosition(){
80-
return this->pRightGearBox->sensor->GetTicks();
8166
}

src/main/include/Commands/DriveWithJoystick.h

-1
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,6 @@
66
#include <Subsystems/DriveTrain.h>
77
#include "RobotMap.h"
88
#include <frc/GenericHID.h>
9-
#include <frc/WPILib.h>
109

1110
class DriveWithJoystick : public frc::Command {
1211
public:

src/main/include/Commands/TriggerDrive.h

-1
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,6 @@
66
#include <Subsystems/DriveTrain.h>
77
#include "RobotMap.h"
88
#include <frc/GenericHID.h>
9-
#include <frc/WPILib.h>
109

1110

1211
class TriggerDrive : public frc::Command {

src/main/include/DeviceMap.h

-19
This file was deleted.

src/main/include/RobotMap.h

-3
Original file line numberDiff line numberDiff line change
@@ -24,9 +24,6 @@
2424
#define DRIVETRAIN_RIGHT_FRONT_MOTOR 3
2525
#define DRIVETRAIN_RIGHT_REAR_MOTOR 4
2626

27-
#define TALLON_TPR 4096
28-
#define WHEEL_CIRCUM_CM 25.13
29-
3027
// DriveTrain motor invertions
3128
#define DRIVETRAIN_LEFT_FRONT_MOTOR_INVERT false
3229
#define DRIVETRAIN_LEFT_REAR_MOTOR_INVERT false

src/main/include/Subsystems/Arm.h

-6
Original file line numberDiff line numberDiff line change
@@ -10,9 +10,6 @@
1010
#include <ctre/Phoenix.h>
1111
#include "RobotMap.h"
1212

13-
#include <Components/GearBox.h>
14-
#include <frc/SpeedControllerGroup.h>
15-
1613
class Arm : public frc::Subsystem {
1714
public:
1815
Arm();
@@ -36,9 +33,6 @@ class Arm : public frc::Subsystem {
3633
private:
3734
can::WPI_TalonSRX* pArmMotor; //!< Pointer for Arm arm motor
3835
can::WPI_TalonSRX* pArmMotor2; //!< Pointer for Arm arm motor
39-
40-
rr::components::GearBox *pArmGearBox;
41-
4236
frc::AnalogInput m_ultrasonic{CLIMB_ULTRASONIC};
4337
static constexpr double kValueToInches = 0.125;
4438
};

src/main/include/Subsystems/DriveTrain.h

+6-16
Original file line numberDiff line numberDiff line change
@@ -3,16 +3,12 @@
33
#define _DRIVETRAIN_HG_
44

55
#include <frc/commands/Subsystem.h>
6-
// #include <frc/WPILib.h>
6+
#include <frc/WPILib.h>
77
#include <ctre/Phoenix.h>
88
#include <frc/drive/DifferentialDrive.h>
99
#include "RobotMap.h"
1010
#include <Commands/DriveWithJoystick.h>
1111

12-
#include <Components/GearBox.h>
13-
#include <Components/Encoder.h>
14-
15-
1612
class DriveTrain : public frc::Subsystem {
1713
public:
1814
DriveTrain(); //!< Class constructor
@@ -42,17 +38,11 @@ class DriveTrain : public frc::Subsystem {
4238
*/
4339
void RadialDrive(double magnitude, double radial);
4440

45-
int GetLeftEncoderPosition();
46-
int GetRightEncoderPosition();
47-
48-
private:
49-
can::WPI_TalonSRX *pLeftFrontMotor; //!< Pointer for left front motor
50-
can::WPI_TalonSRX *pLeftRearMotor; //!< Pointer for left rear motor
51-
can::WPI_TalonSRX *pRightFrontMotor; //!< Pointer for right front motor
52-
can::WPI_TalonSRX *pRightRearMotor; //!< Pointer for right rear motor
53-
54-
rr::components::GearBox *pLeftGearBox; //!< Left gear box
55-
rr::components::GearBox *pRightGearBox; //!< Right gear box
41+
private:
42+
can::WPI_TalonSRX* pLeftFrontMotor; //!< Pointer for left front motor
43+
can::WPI_TalonSRX* pLeftRearMotor; //!< Pointer for left rear motor
44+
can::WPI_TalonSRX* pRightFrontMotor;//!< Pointer for right front motor
45+
can::WPI_TalonSRX* pRightRearMotor; //!< Pointer for right rear motor
5646

5747
frc::DifferentialDrive* pRobotDrive; //!< Pointer for a differential drivebase made up of 2 motor pairs
5848
};

0 commit comments

Comments
 (0)