From 4eb4ccb188f367dd1ae21e4e6b97b26f9e2410d9 Mon Sep 17 00:00:00 2001 From: john sandstedt Date: Sat, 20 Feb 2016 15:22:53 -0500 Subject: [PATCH] adam style csv logging code --- Robot2016/src/Robot.cpp | 88 +++++++++++++++++++++++++++++++++++++++++ 1 file changed, 88 insertions(+) diff --git a/Robot2016/src/Robot.cpp b/Robot2016/src/Robot.cpp index d6cf381..a72b64b 100644 --- a/Robot2016/src/Robot.cpp +++ b/Robot2016/src/Robot.cpp @@ -19,6 +19,10 @@ #endif // BUTTON_LAYOUT +#ifndef LOG +#define LOG(X) logA << X; logB << X; logC << X //for writing data to the csv file +#endif + class Robot: public IterativeRobot { Talon left_drive, right_drive; @@ -113,6 +117,7 @@ private: void AutonomousPeriodic() { + LogCSVData(); if(autoSelected == autoNameCustom){ //Custom Auto goes here } else { @@ -129,6 +134,7 @@ private: void TeleopPeriodic() { + LogCSVData(); std::cout << "Ramp position: "<< ramp.GetEncPosition() << std::endl; drive.ArcadeDrive(&driver_stick, true); @@ -179,6 +185,88 @@ private: void TestPeriodic() { lw->Run(); + LogCSVData(); + } + void LogCSVData() + { + static PowerDistributionPanel pdp; // preparing to read from the pdp + static DriverStation* ds = DriverStation::GetInstance(); + static std::vector 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" << ds->GetAlliance()); + LOG("\t" << ds->GetLocation()); + LOG("\t" << ds->GetMatchTime()); + LOG("\t" << ds->IsFMSAttached()); + LOG("\t" << ds->IsSysBrownedOut()); + LOG(std::endl); } };