2016-02-09 17:22:17 -05:00
|
|
|
#include "WPILib.h"
|
2016-02-09 16:23:45 -05:00
|
|
|
#include "Shooter.h"
|
2016-02-10 20:43:45 -05:00
|
|
|
#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>
|
2016-02-09 16:23:45 -05:00
|
|
|
|
|
|
|
#ifndef BUTTON_LAYOUT
|
|
|
|
#define BUTTON_LAYOUT
|
|
|
|
|
2016-02-09 17:22:17 -05:00
|
|
|
#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
|
2016-02-09 16:23:45 -05:00
|
|
|
|
2016-02-21 20:50:24 -05:00
|
|
|
#define DEADZONE_RADIUS 0.05 // Deadzone Radius prevents tiny twitches in the joystick's value from
|
2016-02-11 20:48:03 -05:00
|
|
|
// affecting the robot. Use this for cleaning up drive train and shooter.
|
|
|
|
// Also used for detecting changes in an axis' value.
|
2016-02-09 16:23:45 -05:00
|
|
|
|
2016-02-26 17:06:28 -05:00
|
|
|
#define TURN_FACTOR 1.5 // Left(x,y) = y*(1 + TF*x) : x < 0
|
2016-02-21 20:50:24 -05:00
|
|
|
// = y : x >= 0
|
|
|
|
// Right(x,y) = y : x < 0
|
|
|
|
// = y*(1 - TF*x) : x >= 0
|
|
|
|
|
2016-02-09 16:23:45 -05:00
|
|
|
#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
|
|
|
|
|
2016-02-09 16:23:45 -05:00
|
|
|
class Robot: public IterativeRobot
|
|
|
|
{
|
2016-02-11 16:35:41 -05:00
|
|
|
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;
|
2016-02-09 16:23:45 -05:00
|
|
|
RobotDrive drive;
|
|
|
|
Shooter shooter;
|
|
|
|
Joystick driver_stick, operator_stick;
|
|
|
|
public:
|
|
|
|
Robot():
|
2016-02-10 14:42:20 -05:00
|
|
|
left_drive(0), // Left DriveTrain Talons plug into PWM channel 1 with a Y-splitter
|
2016-02-10 13:39:48 -05:00
|
|
|
right_drive(1), // Right DriveTrain Talons plug // left wheel 2
|
2016-02-10 19:11:51 -05:00
|
|
|
shooter1(11), // shooter drive 1
|
|
|
|
shooter2(10), // shooter drive 2
|
2016-02-20 15:14:51 -05:00
|
|
|
ramp(12),
|
2016-02-13 16:44:57 -05:00
|
|
|
arms(13),
|
2016-02-09 16:23:45 -05:00
|
|
|
drive(&left_drive, &right_drive),
|
|
|
|
shooter( // initialize Shooter object.
|
2016-02-20 15:14:51 -05:00
|
|
|
&shooter1, &shooter2, &ramp),
|
2016-02-09 16:23:45 -05:00
|
|
|
driver_stick(0), // right stick (operator)
|
2016-02-13 16:40:07 -05:00
|
|
|
operator_stick(1) // left stick (driver)
|
2016-02-09 16:23:45 -05:00
|
|
|
{
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
private:
|
2016-02-09 17:22:17 -05:00
|
|
|
// instance variables
|
|
|
|
bool pickupRunning; // don't want to spam the Talon with set messages. Toggle the pickup when a button is pressed or released.
|
2016-02-10 13:39:48 -05:00
|
|
|
bool inverting;
|
2016-02-13 11:12:20 -05:00
|
|
|
bool ramping;
|
|
|
|
bool shooting;
|
2016-02-13 12:00:28 -05:00
|
|
|
bool unjamming;
|
2016-02-13 16:44:57 -05:00
|
|
|
bool arming;
|
2016-02-22 21:19:51 -05:00
|
|
|
bool arcade;
|
2016-02-11 16:18:58 -05:00
|
|
|
float shooter_power;
|
2016-02-09 17:22:17 -05:00
|
|
|
|
2016-02-09 16:23:45 -05:00
|
|
|
LiveWindow *lw = LiveWindow::GetInstance();
|
|
|
|
SendableChooser *chooser;
|
|
|
|
const std::string autoNameDefault = "Default";
|
|
|
|
const std::string autoNameCustom = "My Auto";
|
|
|
|
std::string autoSelected;
|
|
|
|
|
|
|
|
void RobotInit()
|
|
|
|
{
|
|
|
|
chooser = new SendableChooser();
|
|
|
|
chooser->AddDefault(autoNameDefault, (void*)&autoNameDefault);
|
|
|
|
chooser->AddObject(autoNameCustom, (void*)&autoNameCustom);
|
|
|
|
SmartDashboard::PutData("Auto Modes", chooser);
|
2016-02-10 13:39:48 -05:00
|
|
|
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);
|
2016-02-10 13:39:48 -05:00
|
|
|
inverting = false;
|
2016-02-11 21:24:32 -05:00
|
|
|
pickupRunning = false;
|
2016-02-13 11:12:20 -05:00
|
|
|
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;
|
2016-02-10 13:39:48 -05:00
|
|
|
|
2016-02-09 16:23:45 -05:00
|
|
|
}
|
|
|
|
|
|
|
|
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
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void AutonomousPeriodic()
|
|
|
|
{
|
2016-02-20 15:22:53 -05:00
|
|
|
LogCSVData();
|
2016-02-09 16:23:45 -05:00
|
|
|
if(autoSelected == autoNameCustom){
|
|
|
|
//Custom Auto goes here
|
|
|
|
} else {
|
|
|
|
//Default Auto goes here
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
void TeleopInit()
|
|
|
|
{
|
2016-02-11 16:51:13 -05:00
|
|
|
|
2016-02-09 16:23:45 -05:00
|
|
|
}
|
|
|
|
|
|
|
|
void TeleopPeriodic()
|
|
|
|
{
|
2016-02-20 15:22:53 -05:00
|
|
|
LogCSVData();
|
2016-02-20 13:28:56 -05:00
|
|
|
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);
|
2016-02-22 21:19:51 -05:00
|
|
|
if(driver_stick.GetRawButton(7))
|
2016-02-17 15:22:32 -05:00
|
|
|
{
|
2016-02-22 21:19:51 -05:00
|
|
|
arcade = true;
|
|
|
|
}
|
|
|
|
if(driver_stick.GetRawButton(8))
|
|
|
|
{
|
|
|
|
arcade = false;
|
|
|
|
}
|
|
|
|
if (arcade)
|
|
|
|
{
|
|
|
|
drive.ArcadeDrive(driver_stick);
|
2016-02-17 15:22:32 -05:00
|
|
|
}
|
|
|
|
else
|
|
|
|
{
|
2016-02-22 21:19:51 -05:00
|
|
|
if (driver_stick.GetRawButton(THUMB))
|
|
|
|
{
|
|
|
|
float left = driver_stick.GetTwist();
|
|
|
|
float right = -driver_stick.GetTwist();
|
|
|
|
drive.TankDrive(left, right);
|
|
|
|
}
|
|
|
|
else
|
|
|
|
{
|
|
|
|
UpdateDrive();
|
|
|
|
}
|
2016-02-17 15:22:32 -05:00
|
|
|
}
|
2016-02-13 11:12:20 -05:00
|
|
|
//bool rampDoing = false;
|
2016-02-09 17:22:17 -05:00
|
|
|
// This is shit code for testing. Replace it with real code.
|
2016-02-13 11:12:20 -05:00
|
|
|
if(!ramping && operator_stick.GetRawButton(RAMP_RAISE))
|
2016-02-09 16:23:45 -05:00
|
|
|
{
|
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();
|
2016-02-13 11:12:20 -05:00
|
|
|
ramping =true;
|
2016-02-09 16:23:45 -05:00
|
|
|
}
|
2016-02-13 11:12:20 -05:00
|
|
|
else if(!ramping && operator_stick.GetRawButton(RAMP_LOWER))
|
2016-02-09 16:23:45 -05:00
|
|
|
{
|
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();
|
2016-02-13 11:12:20 -05:00
|
|
|
ramping = true;
|
2016-02-09 16:23:45 -05:00
|
|
|
}
|
2016-02-13 11:26:07 -05:00
|
|
|
/*else if(!ramping && operator_stick.GetRawButton(TRIGGER))
|
2016-02-09 16:23:45 -05:00
|
|
|
{
|
2016-02-12 19:37:36 -05:00
|
|
|
shooter.BoostRamp();
|
2016-02-13 11:12:20 -05:00
|
|
|
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-09 16:23:45 -05:00
|
|
|
{
|
2016-02-13 11:26:07 -05:00
|
|
|
shooter.StopRamp();
|
|
|
|
ramping = false;
|
2016-02-09 16:23:45 -05:00
|
|
|
}
|
|
|
|
|
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;
|
2016-02-09 16:23:45 -05:00
|
|
|
}
|
2016-02-11 20:40:41 -05:00
|
|
|
/*
|
|
|
|
* 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
|
2016-02-20 13:30:42 -05:00
|
|
|
* every iteration of the TeleopPeriodic method (once every 10ms!)
|
2016-02-11 20:40:41 -05:00
|
|
|
* The pickup is disabled when the thumb button is released, but the code still
|
|
|
|
* has 'pickupRunning' as true.
|
|
|
|
*/
|
2016-02-09 17:22:17 -05:00
|
|
|
if(operator_stick.GetRawButton(THUMB) && !pickupRunning)
|
2016-02-09 16:23:45 -05:00
|
|
|
{
|
|
|
|
shooter.PickUp();
|
2016-02-09 17:22:17 -05:00
|
|
|
pickupRunning = true;
|
2016-02-09 16:23:45 -05:00
|
|
|
}
|
2016-02-12 21:17:45 -05:00
|
|
|
else if(!operator_stick.GetRawButton(THUMB) && pickupRunning)
|
2016-02-09 16:23:45 -05:00
|
|
|
{
|
|
|
|
shooter.PickUp(false);
|
2016-02-09 17:22:17 -05:00
|
|
|
pickupRunning = false;
|
2016-02-09 16:23:45 -05:00
|
|
|
}
|
2016-02-11 20:40:41 -05:00
|
|
|
/*
|
|
|
|
* The 'inverting' variable is used to make sure that the drive train isn't getting
|
2016-02-20 13:30:42 -05:00
|
|
|
* inverted every iteration of the TeleopPeriodic method while the button is held down.
|
2016-02-11 20:40:41 -05:00
|
|
|
* This is important because the TeleopPeriodic method executes something like once every 10ms.
|
|
|
|
* Thus, this if-else if pair make the button a toggle.
|
|
|
|
*/
|
2016-02-20 16:47:00 -05:00
|
|
|
if(driver_stick.GetRawButton(TRIGGER) && !inverting)
|
2016-02-10 13:39:48 -05:00
|
|
|
{
|
2016-02-13 12:09:08 -05:00
|
|
|
std::cout << "Inverting Drive Train.";
|
2016-02-10 13:39:48 -05:00
|
|
|
left_drive.SetInverted(!left_drive.GetInverted());
|
|
|
|
right_drive.SetInverted(!right_drive.GetInverted());
|
|
|
|
inverting = true;
|
|
|
|
}
|
2016-02-20 16:47:00 -05:00
|
|
|
else if(!driver_stick.GetRawButton(TRIGGER))
|
2016-02-10 13:39:48 -05:00
|
|
|
{
|
|
|
|
inverting = false;
|
|
|
|
}
|
2016-02-11 21:24:32 -05:00
|
|
|
|
|
|
|
|
|
|
|
/*
|
2016-02-20 14:05:56 -05:00
|
|
|
* Unlike the previous actions, this method does need to be called every iteration of
|
2016-02-11 21:24:32 -05:00
|
|
|
* TeleopPeriodic. This is because the logic running this operation needs to be checked
|
|
|
|
* Every time the method is called. This cannot be a loop in the Shoot method because
|
|
|
|
* that would lock the robot every time the trigger is hit.
|
|
|
|
*/
|
2016-02-20 13:58:35 -05:00
|
|
|
if(operator_stick.GetRawButton(TRIGGER) || (shooter.GetState() != 0))
|
2016-02-11 21:24:32 -05:00
|
|
|
{
|
2016-02-13 11:12:20 -05:00
|
|
|
shooting = true;
|
2016-02-11 21:24:32 -05:00
|
|
|
shooter.Shoot();
|
|
|
|
}
|
2016-02-13 12:00:28 -05:00
|
|
|
else if(shooting && !operator_stick.GetRawButton(TRIGGER))
|
2016-02-11 21:24:32 -05:00
|
|
|
{
|
2016-02-13 11:12:20 -05:00
|
|
|
shooting = false;
|
2016-02-11 21:24:32 -05:00
|
|
|
shooter.StopShooter();
|
2016-02-27 13:29:41 -05:00
|
|
|
}
|
2016-02-11 21:24:32 -05:00
|
|
|
|
2016-02-13 16:47:57 -05:00
|
|
|
if(!arming && driver_stick.GetRawButton(RAMP_RAISE))
|
|
|
|
{
|
|
|
|
arming = true;
|
|
|
|
arms.Set(1);
|
|
|
|
}
|
|
|
|
else if(!arming && driver_stick.GetRawButton(RAMP_LOWER))
|
|
|
|
{
|
|
|
|
arming = true;
|
|
|
|
arms.Set(-1);
|
|
|
|
}
|
|
|
|
else if(arming && !driver_stick.GetRawButton(RAMP_RAISE) && !driver_stick.GetRawButton(RAMP_LOWER))
|
|
|
|
{
|
|
|
|
arming = false;
|
|
|
|
arms.Set(0);
|
|
|
|
}
|
2016-02-13 16:44:57 -05:00
|
|
|
|
2016-02-11 21:24:32 -05:00
|
|
|
// This code will become obsolete after the Shooter logic is complete.
|
2016-02-11 20:48:03 -05:00
|
|
|
float opThrottle = SaneThrottle(operator_stick.GetThrottle());
|
2016-02-11 20:40:41 -05:00
|
|
|
|
2016-02-12 21:17:45 -05:00
|
|
|
if(!pickupRunning && ( opThrottle > shooter_power + DEADZONE_RADIUS
|
|
|
|
|| opThrottle < shooter_power - DEADZONE_RADIUS))
|
2016-02-10 18:56:38 -05:00
|
|
|
{
|
2016-02-11 20:48:03 -05:00
|
|
|
shooter.SetPower(opThrottle);
|
2016-02-10 18:56:38 -05:00
|
|
|
}
|
2016-02-09 16:23:45 -05:00
|
|
|
}
|
|
|
|
|
2016-02-11 20:48:03 -05:00
|
|
|
/**
|
|
|
|
* 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);
|
2016-02-09 16:23:45 -05:00
|
|
|
}
|
|
|
|
|
|
|
|
void TestPeriodic()
|
|
|
|
{
|
|
|
|
lw->Run();
|
2016-02-20 15:22:53 -05:00
|
|
|
LogCSVData();
|
|
|
|
}
|
|
|
|
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());
|
|
|
|
|
|
|
|
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
|
2016-02-22 19:13:09 -05:00
|
|
|
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());
|
2016-02-20 15:22:53 -05:00
|
|
|
LOG(std::endl);
|
2016-02-09 16:23:45 -05:00
|
|
|
}
|
2016-02-17 15:22:32 -05:00
|
|
|
|
|
|
|
void UpdateDrive()
|
|
|
|
{
|
2016-02-20 16:47:00 -05:00
|
|
|
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
|
2016-02-17 15:22:32 -05:00
|
|
|
{
|
2016-02-20 16:47:00 -05:00
|
|
|
float left = y * SaneThrottle(driver_stick.GetThrottle());
|
|
|
|
float right = (1+x)*y * SaneThrottle(driver_stick.GetThrottle());
|
|
|
|
drive.TankDrive(left, right);
|
2016-02-17 15:22:32 -05:00
|
|
|
}
|
|
|
|
}
|
2016-02-09 16:23:45 -05:00
|
|
|
};
|
|
|
|
|
|
|
|
START_ROBOT_CLASS(Robot)
|