Merge branch 'cleanup' of git://10.17.86.101/home/adam/Programs/FRC2016/ into cleanup
This commit is contained in:
commit
cc99328dec
34
Makefile
Normal file
34
Makefile
Normal file
@ -0,0 +1,34 @@
|
||||
LIBS=wpi
|
||||
CXX=arm-frc-linux-gnueabi-g++
|
||||
override CPPFLAGS +=-std=c++14
|
||||
LDFLAGS=-l$(LIBS)
|
||||
TEAM=1786
|
||||
SSH_OPTIONS=-q -o UserKnownHostsFile=/dev/null -o StrictHostKeyChecking=no
|
||||
SSH_SSHPASS=$(shell command -v sshpass >/dev/null 2>&1 && echo -n "sshpass -p ''")
|
||||
|
||||
all: deploy
|
||||
|
||||
build: FRCUserProgram
|
||||
|
||||
FRCUserProgram: src/Robot.cpp
|
||||
@echo "Building FRCUserProgram"
|
||||
$(CXX) $(CPPFLAGS) $< -o $@ $(LDFLAGS)
|
||||
|
||||
clean:
|
||||
rm FRCUserProgram
|
||||
|
||||
deploy: build
|
||||
@echo "Copying FRCUserProgram"
|
||||
@ssh $(SSH_OPTIONS) lvuser@10.17.86.20 'rm -f /home/lvuser/FRCUserProgram'
|
||||
@scp $(SSH_OPTIONS) -o "LogLevel QUIET" FRCUserProgram lvuser@10.17.86.20:/home/lvuser/FRCUserProgram
|
||||
@echo "Restarting FRCUserProgram"
|
||||
@$(SSH_SSHPASS) ssh $(SSH_OPTIONS) admin@10.17.86.20 '. /etc/profile.d/natinst-path.sh; /usr/local/frc/bin/frcKillRobot.sh -t -r'
|
||||
|
||||
restart: FRCUserProgram
|
||||
@echo "Restarting FRCUserProgram"
|
||||
@$(SSH_SSHPASS) ssh $(SSH_OPTIONS) admin@10.17.86.20 '. /etc/profile.d/natinst-path.sh; /usr/local/frc/bin/frcKillRobot.sh -t -r'
|
||||
|
||||
stop:
|
||||
@echo "Restarting FRCUserProgram"
|
||||
@$(SSH_SSHPASS) ssh $(SSH_OPTIONS) admin@10.17.86.20 '. /etc/profile.d/natinst-path.sh; /usr/local/frc/bin/frcKillRobot.sh -t'y
|
||||
|
277
src/Robot.cpp
277
src/Robot.cpp
@ -36,6 +36,7 @@
|
||||
|
||||
class Robot: public IterativeRobot
|
||||
{
|
||||
private:
|
||||
TalonSRX left_drive, right_drive;
|
||||
CANTalon shooter1, shooter2,
|
||||
ramp,
|
||||
@ -43,26 +44,7 @@ class Robot: public IterativeRobot
|
||||
RobotDrive drive;
|
||||
Shooter shooter;
|
||||
Joystick driver_stick, operator_stick;
|
||||
//DriverStation DriverStation::GetInstance();
|
||||
//float power;
|
||||
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)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
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;
|
||||
@ -79,10 +61,9 @@ private:
|
||||
const std::string autoNameCustom = "My Auto";
|
||||
std::string autoSelected;
|
||||
|
||||
/*void LogData()
|
||||
void LogCSVData()
|
||||
{
|
||||
static PowerDistributionPanel pdp;
|
||||
static DriverStation DriverStation::GetInstance() = DriverStation::GetInstance();
|
||||
static PowerDistributionPanel pdp; // preparing to read from the pdp
|
||||
static std::vector<CANTalon*> motors;
|
||||
|
||||
static std::ofstream logA, logB, logC;
|
||||
@ -91,7 +72,119 @@ private:
|
||||
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:
|
||||
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()
|
||||
{
|
||||
@ -115,16 +208,6 @@ private:
|
||||
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* This autonomous (along with the chooser code above) shows how to select between different autonomous modes
|
||||
* using the dashboard. The sendable chooser code works with the Java SmartDashboard. If you prefer the LabVIEW
|
||||
* Dashboard, remove all of the chooser code and uncomment the GetString line to get the auto name from the text box
|
||||
* below the Gyro
|
||||
*
|
||||
* You can add additional auto modes by adding additional comparisons to the if-else structure below with additional strings.
|
||||
* If using the SendableChooser make sure to add them to the chooser code above as well.
|
||||
*/
|
||||
void AutonomousInit()
|
||||
{
|
||||
autoSelected = *((std::string*)chooser->GetSelected());
|
||||
@ -307,139 +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()
|
||||
{
|
||||
lw->Run();
|
||||
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 SimpleDrive()
|
||||
{
|
||||
float x = -driver_stick.GetX();
|
||||
float y = -driver_stick.GetY();
|
||||
float left = 0;
|
||||
float right = 0;
|
||||
|
||||
if (x > 0)
|
||||
{
|
||||
right = y;
|
||||
left = (1- x*TURN_FACTOR)*y ;
|
||||
}
|
||||
else
|
||||
{
|
||||
left = y;
|
||||
right = (1+x*TURN_FACTOR)*y;
|
||||
}
|
||||
|
||||
drive.TankDrive(left, right);
|
||||
}
|
||||
|
||||
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)
|
||||
|
Reference in New Issue
Block a user