Fix public and private placement
Also fix using LogCSVData and UpdateDrive before they are declared
This commit is contained in:
parent
7422635b49
commit
56f043bcd0
250
src/Robot.cpp
250
src/Robot.cpp
@ -36,6 +36,7 @@
|
|||||||
|
|
||||||
class Robot: public IterativeRobot
|
class Robot: public IterativeRobot
|
||||||
{
|
{
|
||||||
|
private:
|
||||||
TalonSRX left_drive, right_drive;
|
TalonSRX left_drive, right_drive;
|
||||||
CANTalon shooter1, shooter2,
|
CANTalon shooter1, shooter2,
|
||||||
ramp,
|
ramp,
|
||||||
@ -43,6 +44,131 @@ class Robot: public IterativeRobot
|
|||||||
RobotDrive drive;
|
RobotDrive drive;
|
||||||
Shooter shooter;
|
Shooter shooter;
|
||||||
Joystick driver_stick, operator_stick;
|
Joystick driver_stick, operator_stick;
|
||||||
|
|
||||||
|
// 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;
|
||||||
|
bool unjamming;
|
||||||
|
bool arming;
|
||||||
|
bool arcade;
|
||||||
|
float shooter_power;
|
||||||
|
|
||||||
|
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());
|
||||||
|
|
||||||
|
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:
|
public:
|
||||||
Robot():
|
Robot():
|
||||||
left_drive(0), // Left DriveTrain Talons plug into PWM channel 1 with a Y-splitter
|
left_drive(0), // Left DriveTrain Talons plug into PWM channel 1 with a Y-splitter
|
||||||
@ -60,23 +186,6 @@ public:
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
private:
|
|
||||||
// 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;
|
|
||||||
bool unjamming;
|
|
||||||
bool arming;
|
|
||||||
bool arcade;
|
|
||||||
float shooter_power;
|
|
||||||
|
|
||||||
LiveWindow *lw = LiveWindow::GetInstance();
|
|
||||||
SendableChooser *chooser;
|
|
||||||
const std::string autoNameDefault = "Default";
|
|
||||||
const std::string autoNameCustom = "My Auto";
|
|
||||||
std::string autoSelected;
|
|
||||||
|
|
||||||
void RobotInit()
|
void RobotInit()
|
||||||
{
|
{
|
||||||
chooser = new SendableChooser();
|
chooser = new SendableChooser();
|
||||||
@ -281,118 +390,11 @@ private:
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
|
||||||
* 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 TestPeriodic()
|
void TestPeriodic()
|
||||||
{
|
{
|
||||||
lw->Run();
|
lw->Run();
|
||||||
LogCSVData();
|
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
|
|
||||||
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);
|
|
||||||
}
|
|
||||||
|
|
||||||
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);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
};
|
};
|
||||||
|
|
||||||
START_ROBOT_CLASS(Robot)
|
START_ROBOT_CLASS(Robot)
|
||||||
|
Reference in New Issue
Block a user