This repository has been archived on 2020-09-21. You can view files and clone it, but cannot push or open issues or pull requests.
FRC2016-old/Robot2016/src/Robot.cpp

563 lines
13 KiB
C++
Raw Normal View History

#include "WPILib.h"
#include "Shooter.h"
#include <ctime>
#include <iostream>
#include <iomanip>
#include <fstream>
#include <string>
#include <sys/time.h>
#include <vector>
#include <cmath>
2016-02-19 15:48:18 -05:00
#include <math.h>
#ifndef BUTTON_LAYOUT
#define BUTTON_LAYOUT
#define TRIGGER 1 // Trigger button number
#define THUMB 2 // Thumb button number
2016-02-19 15:48:18 -05:00
#define RAMP_RAISE 5 // Button 3 for Raising Ramp
#define RAMP_LOWER 3 // Button 4 to lower ramp.
2016-02-13 12:00:28 -05:00
#define UNJAM 11
#define ARMS_SCALE 0.75
#define DEADZONE_RADIUS 0.05 // Deadzone Radius prevents tiny twitches in the joystick's value from
// affecting the robot. Use this for cleaning up drive train and shooter.
// Also used for detecting changes in an axis' value.
#define TURN_FACTOR 1.5 // Left(x,y) = y*(1 + TF*x) : x < 0
// = y : x >= 0
// Right(x,y) = y : x < 0
// = y*(1 - TF*x) : x >= 0
#endif // BUTTON_LAYOUT
2016-02-20 15:22:53 -05:00
#ifndef LOG
#define LOG(X) logA << X; logB << X; logC << X //for writing data to the csv file
#endif
class Robot: public IterativeRobot
{
private:
TalonSRX left_drive, right_drive;
2016-02-09 19:47:17 -05:00
CANTalon shooter1, shooter2,
2016-02-20 15:14:51 -05:00
ramp,
2016-02-13 16:44:57 -05:00
arms;
RobotDrive drive;
Shooter shooter;
Joystick driver_stick, operator_stick;
2016-03-05 13:44:17 -05:00
Timer auto_clock;
// instance variables
bool pickupRunning; // don't want to spam the Talon with set messages. Toggle the pickup when a button is pressed or released.
bool inverting;
bool ramping;
bool shooting;
2016-02-13 12:00:28 -05:00
bool unjamming;
2016-02-13 16:44:57 -05:00
bool arming;
bool arcade;
float shooter_power;
2016-03-05 13:44:17 -05:00
enum auto_states
{
START,
DRIVING_FORWARD,
STOP
};
auto_states auto_status;
LiveWindow *lw = LiveWindow::GetInstance();
SendableChooser *chooser;
const std::string autoNameDefault = "Default";
const std::string autoNameCustom = "My Auto";
std::string autoSelected;
void LogCSVData()
{
static PowerDistributionPanel pdp; // preparing to read from the pdp
static std::vector<CANTalon*> motors;
static std::ofstream logA, logB, logC;
timeval tm;
SmartDashboard::PutBoolean("log A", logA.is_open());
SmartDashboard::PutBoolean("log B", logB.is_open());
SmartDashboard::PutBoolean("log C", logC.is_open());
2016-03-06 10:01:32 -05:00
SmartDashboard::PutBoolean("Ramp Limit F", !ramp.IsFwdLimitSwitchClosed());
SmartDashboard::PutBoolean("Ramp Limit R", !ramp.IsRevLimitSwitchClosed());
SmartDashboard::PutBoolean("Arms Limit F", !arms.IsFwdLimitSwitchClosed());
SmartDashboard::PutBoolean("Arms Limit R", !arms.IsRevLimitSwitchClosed());
if (!logA.is_open() && !logB.is_open() && !logC.is_open())
{
std::fstream logNumFile;
int logNum;
logNumFile.open("/home/lvuser/logNum");
logNumFile >> logNum;
logNum++;
logNumFile.seekp(0);
logNumFile << logNum;
// writing to /home/lvuser/logs/[unixtime].log
logA.open("/media/sda1/logs/log" + std::to_string(logNum) + ".csv");
std::cerr << (logA.is_open() ? "Opened" : "Failed to open") << "log A." << std::endl;
logB.open("/media/sdb1/logs/log" + std::to_string(logNum) + ".csv");
std::cerr << (logB.is_open() ? "Opened" : "Failed to open") << "log B." << std::endl;
logC.open("/home/lvuser/logs/log" + std::to_string(logNum) + ".csv");
std::cerr << (logC.is_open() ? "Opened" : "Failed to open") << "log C." << std::endl;
LOG("Time\tpdpInput voltage\tpdpTemperature\tpdpTotal Current\t");
for (int ii = 0; ii < 16; ii++)
{
LOG("pdpChannel " << ii << " current\t");
}
LOG("tlaunch_spinny Bus Voltage\ttlaunch_spinny Output Current\ttlaunch_spinny Output Voltage\ttlaunch_spinny Temperature");
motors.push_back(&ramp);
LOG("\tShooter1 Bus Voltage\tShooter1 Output Current\tShooter1 Output Voltage\tShooter1 Temperature");
motors.push_back(&shooter1);
LOG("\tShooter2 Bus Voltage\tShooter2 Output Current\tShooter2 Output Voltage\tShooter2 Temperature");
motors.push_back(&shooter2);
LOG("\tJoystick X\tJoystick Y\tJoystick Twist");
LOG("\tAlliance\tLocation\tMatch Time\tFMS Attached\tBrowned Out");
LOG("\tTestStage");
LOG(std::endl);
}
gettimeofday(&tm, NULL);
LOG(time(0) << '.' << std::setfill('0') << std::setw(3) << tm.tv_usec/1000);
// Some general information
LOG("\t" << pdp.GetVoltage());
LOG("\t" << pdp.GetTemperature());
LOG("\t" << pdp.GetTotalCurrent());
// current on each channel
for (int ii = 0; ii < 16; ii++)
{
LOG("\t" << pdp.GetCurrent(ii));
}
//Talon Data
for(int ii = 0; ii < motors.size(); ii++)
{
LOG("\t" << motors[ii]->GetBusVoltage());
LOG("\t" << motors[ii]->GetOutputVoltage());
LOG("\t" << motors[ii]->GetOutputCurrent());
LOG("\t" << motors[ii]->GetTemperature());
}
//control data
LOG("\t" << driver_stick.GetX());
LOG("\t" << driver_stick.GetY());
LOG("\t" << driver_stick.GetTwist());
//DriverStation Data
LOG("\t" << DriverStation::GetInstance().GetAlliance());
LOG("\t" << DriverStation::GetInstance().GetLocation());
LOG("\t" << DriverStation::GetInstance().GetMatchTime());
LOG("\t" << DriverStation::GetInstance().IsFMSAttached());
LOG("\t" << DriverStation::GetInstance().IsSysBrownedOut());
LOG(std::endl);
}
/**
* Takes the gross raw throttle input from joystick and returns a
* value between 0.0-1.0 (no negative values)
*/
float SaneThrottle(float rawThrottle)
{
return ((1.0 - rawThrottle) / 2.0);
}
void UpdateDrive()
{
float x = -driver_stick.GetX();
float y = -driver_stick.GetY();
if (x > 0)
{
float right = y * SaneThrottle(driver_stick.GetThrottle());
float left = (1-x)*y * SaneThrottle(driver_stick.GetThrottle());
drive.TankDrive(left, right);
}
else
{
float left = y * SaneThrottle(driver_stick.GetThrottle());
float right = (1+x)*y * SaneThrottle(driver_stick.GetThrottle());
drive.TankDrive(left, right);
}
}
public:
Robot():
left_drive(0), // Left DriveTrain Talons plug into PWM channel 1 with a Y-splitter
right_drive(1), // Right DriveTrain Talons plug // left wheel 2
shooter1(11), // shooter drive 1
shooter2(10), // shooter drive 2
ramp(12),
arms(13),
drive(&left_drive, &right_drive),
shooter( // initialize Shooter object.
&shooter1, &shooter2, &ramp),
driver_stick(0), // right stick (operator)
operator_stick(1) // left stick (driver)
{
}
void RobotInit()
{
chooser = new SendableChooser();
chooser->AddDefault(autoNameDefault, (void*)&autoNameDefault);
chooser->AddObject(autoNameCustom, (void*)&autoNameCustom);
SmartDashboard::PutData("Auto Modes", chooser);
shooter1.Enable();
shooter2.Enable();
2016-02-20 17:12:23 -05:00
left_drive.SetInverted(true);
right_drive.SetInverted(true);
2016-02-20 15:14:51 -05:00
//ramp.SetInverted(true);
inverting = false;
pickupRunning = false;
ramping = false;
shooting = false;
2016-02-13 12:00:28 -05:00
unjamming = false;
2016-02-13 16:44:57 -05:00
arming = false;
2016-02-11 16:51:13 -05:00
shooter_power = 0;
2016-02-22 21:26:11 -05:00
arcade = false;
}
void AutonomousInit()
{
autoSelected = *((std::string*)chooser->GetSelected());
//std::string autoSelected = SmartDashboard::GetString("Auto Selector", autoNameDefault);
std::cout << "Auto selected: " << autoSelected << std::endl;
if(autoSelected == autoNameCustom){
//Custom Auto goes here
} else {
//Default Auto goes here
2016-03-05 13:44:17 -05:00
auto_status = START;
}
}
void AutonomousPeriodic()
{
const float drivePower = 1;
const float driveTime = 3; //Seconds to drive forward
2016-02-20 15:22:53 -05:00
LogCSVData();
if(autoSelected == autoNameCustom){
//Custom Auto goes here
} else {
//Default Auto goes here
2016-03-05 13:44:17 -05:00
switch (auto_status)
{
case START:
{
auto_clock.Start();
auto_status = DRIVING_FORWARD;
break;
}
case DRIVING_FORWARD:
{
if (auto_clock.Get() > driveTime)
2016-03-05 13:44:17 -05:00
{
drive.TankDrive(0.0, 0.0);
auto_status = STOP;
}
else
{
drive.TankDrive(drivePower, drivePower);
}
break;
}
case STOP:
{
std::cout << "All done!\n" ;
break;
}
}
}
}
void TeleopInit()
{
2016-02-11 16:51:13 -05:00
}
void TeleopPeriodic()
{
2016-02-20 15:22:53 -05:00
LogCSVData();
std::cout << "arm encoder position: " << arms.GetEncPosition() << std::endl;
std::cout << "arm encoder velocity: " << arms.GetEncVel() << std::endl;
2016-02-20 17:12:23 -05:00
drive.ArcadeDrive(-driver_stick.GetY(), -driver_stick.GetX()*0.75);
if(driver_stick.GetRawButton(7))
{
arcade = true;
}
if(driver_stick.GetRawButton(8))
{
arcade = false;
}
if (arcade)
{
drive.ArcadeDrive(driver_stick);
}
else
{
if (driver_stick.GetRawButton(THUMB))
{
float left = driver_stick.GetTwist();
float right = -driver_stick.GetTwist();
drive.TankDrive(left, right);
}
else
{
UpdateDrive();
}
}
//bool rampDoing = false;
// This is shit code for testing. Replace it with real code.
if(!ramping && operator_stick.GetRawButton(RAMP_RAISE))
{
2016-02-13 11:26:07 -05:00
std::cout << "Raising Ramp.";
2016-02-20 15:14:51 -05:00
//ramp.Set(1);
2016-02-12 19:37:36 -05:00
shooter.RaiseRamp();
ramping =true;
}
else if(!ramping && operator_stick.GetRawButton(RAMP_LOWER))
{
2016-02-13 11:26:07 -05:00
std::cout << "Lowering Ramp.";
2016-02-20 15:14:51 -05:00
//ramp.Set(-1);
2016-02-12 19:37:36 -05:00
shooter.LowerRamp();
ramping = true;
}
2016-02-13 11:26:07 -05:00
/*else if(!ramping && operator_stick.GetRawButton(TRIGGER))
{
2016-02-12 19:37:36 -05:00
shooter.BoostRamp();
ramping = true;
2016-02-27 14:30:47 -05:00
}*/
2016-02-20 15:45:47 -05:00
else if(ramping && !operator_stick.GetRawButton(RAMP_RAISE)
&& !operator_stick.GetRawButton(RAMP_LOWER))
{
2016-02-13 11:26:07 -05:00
shooter.StopRamp();
ramping = false;
}
2016-02-12 19:37:36 -05:00
2016-02-13 12:00:28 -05:00
if(!unjamming && operator_stick.GetRawButton(UNJAM))
{
unjamming = true;
shooter.Unjam();
}
2016-02-20 18:15:28 -05:00
else if(!unjamming && operator_stick.GetRawButton(TRIGGER))
{
shooter.ShootLow();
unjamming = true;
}
else if(unjamming && !operator_stick.GetRawButton(UNJAM) && !operator_stick.GetRawButton(TRIGGER))
2016-02-13 12:00:28 -05:00
{
shooter.PickUp(false);
unjamming = false;
}
/*
* Run the Shooter only while the THUMB button is held down on the operator stick.
* the 'pickupRunning' boolean is there to prevent the shooter from calling PickUp
* every iteration of the TeleopPeriodic method (once every 10ms!)
* The pickup is disabled when the thumb button is released, but the code still
* has 'pickupRunning' as true.
*/
if(operator_stick.GetRawButton(THUMB) && !pickupRunning)
{
shooter.PickUp();
pickupRunning = true;
}
2016-02-12 21:17:45 -05:00
else if(!operator_stick.GetRawButton(THUMB) && pickupRunning)
{
shooter.PickUp(false);
pickupRunning = false;
}
/*
* The 'inverting' variable is used to make sure that the drive train isn't getting
* inverted every iteration of the TeleopPeriodic method while the button is held down.
* This is important because the TeleopPeriodic method executes something like once every 10ms.
* Thus, this if-else if pair make the button a toggle.
*/
if(driver_stick.GetRawButton(TRIGGER) && !inverting)
{
2016-02-13 12:09:08 -05:00
std::cout << "Inverting Drive Train.";
left_drive.SetInverted(!left_drive.GetInverted());
right_drive.SetInverted(!right_drive.GetInverted());
inverting = true;
}
else if(!driver_stick.GetRawButton(TRIGGER))
{
inverting = false;
}
if(operator_stick.GetRawButton(4))
2016-02-13 16:47:57 -05:00
{
arms.Set(-operator_stick.GetY() * ARMS_SCALE);
2016-02-13 16:47:57 -05:00
}
else
2016-02-13 16:47:57 -05:00
{
arms.Set(0);
}
2016-02-13 16:44:57 -05:00
// This code will become obsolete after the Shooter logic is complete.
float opThrottle = SaneThrottle(operator_stick.GetThrottle());
2016-02-12 21:17:45 -05:00
if(!pickupRunning && ( opThrottle > shooter_power + DEADZONE_RADIUS
|| opThrottle < shooter_power - DEADZONE_RADIUS))
{
shooter.SetPower(opThrottle);
}
}
void TestPeriodic()
{
2016-03-05 14:28:32 -05:00
const int driveTime = 5; //Drive for 5 seconds
const float drivePower = 0.5, armPower=.35, rampPower=.4; //Arbitrary powers to test at
static Timer t;
enum test_stages {
INIT,
ARMS_UP,
ARMS_DOWN,
RAMP_UP,
RAMP_DOWN,
DRIVE_FORWARD,
DRIVE_BACKWARD,
TURN_CW,
TURN_CCW,
END};
static enum test_stages test_stage, old_test_stage;
if (old_test_stage != test_stage)
{
//Reset timer between stages
t.Stop();
t.Reset();
//Wait for a button press between stages
if (operator_stick.GetRawButton(TRIGGER))
old_test_stage = test_stage;
}
else
{
if(!t.Get()) t.Start();
switch (test_stage)
{
case INIT:
{
break;
}
case ARMS_UP:
{
if (arms.GetForwardLimitOK())
arms.Set(1);
else
{
arms.Set(0);
test_stage = ARMS_DOWN;
}
break;
}
case ARMS_DOWN:
{
if (arms.GetReverseLimitOK())
arms.Set(-1);
else
{
arms.Set(0);
test_stage = RAMP_UP;
}
break;
}
case RAMP_UP:
{
if (arms.GetForwardLimitOK())
ramp.Set(1);
else
{
ramp.Set(0);
test_stage = RAMP_DOWN;
}
break;
}
case RAMP_DOWN:
{
if (arms.GetReverseLimitOK())
ramp.Set(-1);
else
{
ramp.Set(0);
test_stage = DRIVE_FORWARD;
}
break;
}
case DRIVE_FORWARD:
{
if (t.Get() < driveTime)
drive.TankDrive(drivePower, drivePower);
else
{
drive.TankDrive(0.0, 0.0);
test_stage = DRIVE_BACKWARD;
}
break;
}
case DRIVE_BACKWARD:
{
if (t.Get() < driveTime)
drive.TankDrive(-drivePower, -drivePower);
else
{
drive.TankDrive(0.0, 0.0);
test_stage = TURN_CW;
}
break;
}
case TURN_CW:
{
if (t.Get() < driveTime)
drive.TankDrive(drivePower, -drivePower);
else
{
drive.TankDrive(0.0, 0.0);
test_stage = TURN_CCW;
}
break;
}
case TURN_CCW:
{
if (t.Get() < driveTime)
drive.TankDrive(-drivePower, drivePower);
else
{
drive.TankDrive(0.0, 0.0);
test_stage = END;
}
break;
}
case END:
{
break;
}
}
}
2016-02-20 15:22:53 -05:00
LogCSVData();
}
};
START_ROBOT_CLASS(Robot)