diff --git a/CPP_CtrePigeon_SmartDash/.cproject b/CPP_CtrePigeon_SmartDash/.cproject
index 74a54f8..fd763d5 100644
--- a/CPP_CtrePigeon_SmartDash/.cproject
+++ b/CPP_CtrePigeon_SmartDash/.cproject
@@ -1,288 +1,288 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/CPP_CtrePigeon_SmartDash/.project b/CPP_CtrePigeon_SmartDash/.project
index f121ddd..07d76ac 100644
--- a/CPP_CtrePigeon_SmartDash/.project
+++ b/CPP_CtrePigeon_SmartDash/.project
@@ -1,28 +1,28 @@
- CPP_CtrePigeon_SmartDash
-
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.genmakebuilder
- clean,full,incremental,
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
- full,incremental,
-
-
-
-
-
- org.eclipse.cdt.core.cnature
- org.eclipse.cdt.core.ccnature
- org.eclipse.cdt.managedbuilder.core.managedBuildNature
- org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ CPP_CtrePigeon_SmartDash
+
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.genmakebuilder
+ clean,full,incremental,
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
+ full,incremental,
+
+
+
+
+
+ org.eclipse.cdt.core.cnature
+ org.eclipse.cdt.core.ccnature
+ org.eclipse.cdt.managedbuilder.core.managedBuildNature
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/CPP_CtrePigeon_SmartDash/.settings/language.settings.xml b/CPP_CtrePigeon_SmartDash/.settings/language.settings.xml
index f995371..f4b6c43 100644
--- a/CPP_CtrePigeon_SmartDash/.settings/language.settings.xml
+++ b/CPP_CtrePigeon_SmartDash/.settings/language.settings.xml
@@ -1,33 +1,33 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/CPP_CtrePigeon_SmartDash/src/Robot.cpp b/CPP_CtrePigeon_SmartDash/src/Robot.cpp
index 41e8806..f2ac726 100644
--- a/CPP_CtrePigeon_SmartDash/src/Robot.cpp
+++ b/CPP_CtrePigeon_SmartDash/src/Robot.cpp
@@ -15,64 +15,64 @@
class Robot: public frc::IterativeRobot {
public:
- /* forward proto */
- class PlotThread;
-
- PigeonImu * _pidgey;
-
- PlotThread *_plotThread;
-
- Robot() {
- _pidgey = new PigeonImu(0);
- _plotThread = NULL;
- }
-
-
- /*
- * 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 TeleopInit() {
- _plotThread = new PlotThread(this);
- }
-
- void TeleopPeriodic() {
-
- }
-
- /** quick and dirty threaded plotter */
- class PlotThread {
- public:
- Robot * _robot;
- std::thread * _thrd;
- PlotThread(Robot * robot){
- this->_robot = robot;
- this->_thrd = new std::thread(&PlotThread::execute, this);
- }
-
- void execute() {
- /* speed up network tables, this is a test project so eat up all
- * of the network possible for the purpose of this test.
- */
- NetworkTable::SetUpdateRate(0.010); /* this suggests each time unit is 10ms in the plot */
- while (true) {
- /* yield for a ms or so - this is not meant to be accurate */
- std::this_thread::sleep_for(std::chrono::milliseconds(1));
- /* grab the last signal update from our 1ms frame update */
- double heading = _robot->_pidgey->GetFusedHeading();
- SmartDashboard::PutNumber("hdng", heading);
- }
- }
- };
+ /* forward proto */
+ class PlotThread;
+
+ PigeonImu * _pidgey;
+
+ PlotThread *_plotThread;
+
+ Robot() {
+ _pidgey = new PigeonImu(0);
+ _plotThread = NULL;
+ }
+
+
+ /*
+ * 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 TeleopInit() {
+ _plotThread = new PlotThread(this);
+ }
+
+ void TeleopPeriodic() {
+
+ }
+
+ /** quick and dirty threaded plotter */
+ class PlotThread {
+ public:
+ Robot * _robot;
+ std::thread * _thrd;
+ PlotThread(Robot * robot){
+ this->_robot = robot;
+ this->_thrd = new std::thread(&PlotThread::execute, this);
+ }
+
+ void execute() {
+ /* speed up network tables, this is a test project so eat up all
+ * of the network possible for the purpose of this test.
+ */
+ NetworkTable::SetUpdateRate(0.010); /* this suggests each time unit is 10ms in the plot */
+ while (true) {
+ /* yield for a ms or so - this is not meant to be accurate */
+ std::this_thread::sleep_for(std::chrono::milliseconds(1));
+ /* grab the last signal update from our 1ms frame update */
+ double heading = _robot->_pidgey->GetFusedHeading();
+ SmartDashboard::PutNumber("hdng", heading);
+ }
+ }
+ };
};
START_ROBOT_CLASS(Robot)
diff --git a/CPP_Mecanum_CANTalon_Example/.cproject b/CPP_Mecanum_CANTalon_Example/.cproject
index f496e04..12aa024 100644
--- a/CPP_Mecanum_CANTalon_Example/.cproject
+++ b/CPP_Mecanum_CANTalon_Example/.cproject
@@ -1,286 +1,286 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/CPP_Mecanum_CANTalon_Example/.project b/CPP_Mecanum_CANTalon_Example/.project
index 477e160..a865e33 100644
--- a/CPP_Mecanum_CANTalon_Example/.project
+++ b/CPP_Mecanum_CANTalon_Example/.project
@@ -1,28 +1,28 @@
- CPP_Mecanum_CANTalon_Example
-
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.genmakebuilder
- clean,full,incremental,
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
- full,incremental,
-
-
-
-
-
- org.eclipse.cdt.core.cnature
- org.eclipse.cdt.core.ccnature
- org.eclipse.cdt.managedbuilder.core.managedBuildNature
- org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ CPP_Mecanum_CANTalon_Example
+
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.genmakebuilder
+ clean,full,incremental,
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
+ full,incremental,
+
+
+
+
+
+ org.eclipse.cdt.core.cnature
+ org.eclipse.cdt.core.ccnature
+ org.eclipse.cdt.managedbuilder.core.managedBuildNature
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/CPP_Mecanum_CANTalon_Example/.settings/language.settings.xml b/CPP_Mecanum_CANTalon_Example/.settings/language.settings.xml
index 123662f..fc131fb 100644
--- a/CPP_Mecanum_CANTalon_Example/.settings/language.settings.xml
+++ b/CPP_Mecanum_CANTalon_Example/.settings/language.settings.xml
@@ -1,33 +1,33 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/CPP_Mecanum_CANTalon_Example/src/Robot.cpp b/CPP_Mecanum_CANTalon_Example/src/Robot.cpp
index d765e54..b7f9893 100644
--- a/CPP_Mecanum_CANTalon_Example/src/Robot.cpp
+++ b/CPP_Mecanum_CANTalon_Example/src/Robot.cpp
@@ -2,61 +2,61 @@
#include "CANTalon.h"
class MecanumDefaultCode : public IterativeRobot
{
- CANTalon lf; /*left front */
- CANTalon lr;/*left rear */
- CANTalon rf; /*right front */
- CANTalon rr; /*right rear */
+ CANTalon lf; /*left front */
+ CANTalon lr;/*left rear */
+ CANTalon rf; /*right front */
+ CANTalon rr; /*right rear */
public:
- RobotDrive *m_robotDrive; // RobotDrive object using PWM 1-4 for drive motors
- Joystick *m_driveStick; // Joystick object on USB port 1 (mecanum drive)public:
- AnalogGyro gyro;
- /**
- * Constructor for this "MecanumDefaultCode" Class.
- */
- MecanumDefaultCode(void) : lf(3), lr(1), rf(4), rr(5), gyro(0)
- {
- /* Set every Talon to reset the motor safety timeout. */
- lf.Set(0);
- lr.Set(0);
- rf.Set(0);
- rr.Set(0);
- // Create a RobotDrive object using PWMS 1, 2, 3, and 4
- m_robotDrive = new RobotDrive(lf, lr, rf, rr);
- m_robotDrive->SetExpiration(0.5);
- m_robotDrive->SetSafetyEnabled(false);
- // Define joystick being used at USB port #0 on the Drivers Station
- m_driveStick = new Joystick(0);
- }
- void TeleopInit()
- {
- gyro.Reset();
- }
- /** @return 10% deadband */
- double Db(double axisVal)
- {
- if(axisVal < -0.10)
- return axisVal;
- if(axisVal > +0.10)
- return axisVal;
- return 0;
- }
- /**
- * Gets called once for each new packet from the DS.
- */
- void TeleopPeriodic(void)
- {
- float angle = gyro.GetAngle();
- //std::cout << "Angle : " << angle << std::endl;
- m_robotDrive->MecanumDrive_Cartesian( Db(m_driveStick->GetX()),
- Db(m_driveStick->GetY()),
- Db(m_driveStick->GetZ()),
- angle);
- /* my right side motors need to drive negative to move robot forward */
- m_robotDrive->SetInvertedMotor(RobotDrive::kFrontRightMotor,true);
- m_robotDrive->SetInvertedMotor(RobotDrive::kRearRightMotor,true);
- /* on button 5, reset gyro angle to zero */
- if(m_driveStick->GetRawButton(5))
- gyro.Reset();
- }
+ RobotDrive *m_robotDrive; // RobotDrive object using PWM 1-4 for drive motors
+ Joystick *m_driveStick; // Joystick object on USB port 1 (mecanum drive)public:
+ AnalogGyro gyro;
+ /**
+ * Constructor for this "MecanumDefaultCode" Class.
+ */
+ MecanumDefaultCode(void) : lf(3), lr(1), rf(4), rr(5), gyro(0)
+ {
+ /* Set every Talon to reset the motor safety timeout. */
+ lf.Set(0);
+ lr.Set(0);
+ rf.Set(0);
+ rr.Set(0);
+ // Create a RobotDrive object using PWMS 1, 2, 3, and 4
+ m_robotDrive = new RobotDrive(lf, lr, rf, rr);
+ m_robotDrive->SetExpiration(0.5);
+ m_robotDrive->SetSafetyEnabled(false);
+ // Define joystick being used at USB port #0 on the Drivers Station
+ m_driveStick = new Joystick(0);
+ }
+ void TeleopInit()
+ {
+ gyro.Reset();
+ }
+ /** @return 10% deadband */
+ double Db(double axisVal)
+ {
+ if(axisVal < -0.10)
+ return axisVal;
+ if(axisVal > +0.10)
+ return axisVal;
+ return 0;
+ }
+ /**
+ * Gets called once for each new packet from the DS.
+ */
+ void TeleopPeriodic(void)
+ {
+ float angle = gyro.GetAngle();
+ //std::cout << "Angle : " << angle << std::endl;
+ m_robotDrive->MecanumDrive_Cartesian( Db(m_driveStick->GetX()),
+ Db(m_driveStick->GetY()),
+ Db(m_driveStick->GetZ()),
+ angle);
+ /* my right side motors need to drive negative to move robot forward */
+ m_robotDrive->SetInvertedMotor(RobotDrive::kFrontRightMotor,true);
+ m_robotDrive->SetInvertedMotor(RobotDrive::kRearRightMotor,true);
+ /* on button 5, reset gyro angle to zero */
+ if(m_driveStick->GetRawButton(5))
+ gyro.Reset();
+ }
};
START_ROBOT_CLASS(MecanumDefaultCode);
diff --git a/CPP_MotionProfileExample/.cproject b/CPP_MotionProfileExample/.cproject
index 51d1302..4ff9379 100644
--- a/CPP_MotionProfileExample/.cproject
+++ b/CPP_MotionProfileExample/.cproject
@@ -1,287 +1,287 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/CPP_MotionProfileExample/.project b/CPP_MotionProfileExample/.project
index 413ad5b..52f43bc 100644
--- a/CPP_MotionProfileExample/.project
+++ b/CPP_MotionProfileExample/.project
@@ -1,28 +1,28 @@
- CPP_MotionProfileExample
-
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.genmakebuilder
- clean,full,incremental,
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
- full,incremental,
-
-
-
-
-
- org.eclipse.cdt.core.cnature
- org.eclipse.cdt.core.ccnature
- org.eclipse.cdt.managedbuilder.core.managedBuildNature
- org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ CPP_MotionProfileExample
+
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.genmakebuilder
+ clean,full,incremental,
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
+ full,incremental,
+
+
+
+
+
+ org.eclipse.cdt.core.cnature
+ org.eclipse.cdt.core.ccnature
+ org.eclipse.cdt.managedbuilder.core.managedBuildNature
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/CPP_MotionProfileExample/.settings/language.settings.xml b/CPP_MotionProfileExample/.settings/language.settings.xml
index 123662f..fc131fb 100644
--- a/CPP_MotionProfileExample/.settings/language.settings.xml
+++ b/CPP_MotionProfileExample/.settings/language.settings.xml
@@ -1,33 +1,33 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/CPP_MotionProfileExample/src/Robot.cpp b/CPP_MotionProfileExample/src/Robot.cpp
index cb970e7..7c2e115 100644
--- a/CPP_MotionProfileExample/src/Robot.cpp
+++ b/CPP_MotionProfileExample/src/Robot.cpp
@@ -28,89 +28,89 @@
class Robot: public IterativeRobot
{
public:
- /** The Talon we want to motion profile. */
- CANTalon _talon;
-
- /** some example logic on how one can manage an MP */
- MotionProfileExample _example;
-
- /** joystick for testing */
- Joystick _joy;
-
- /** cache last buttons so we can detect press events. In a command-based project you can leverage the on-press event
- * but for this simple example, lets just do quick compares to prev-btn-states */
- bool _btnsLast[10] = {false,false,false,false,false,false,false,false,false,false};
-
-
- Robot() : _talon(6), _example(_talon), _joy(0)
- {
- _talon.SetFeedbackDevice(CANTalon::CtreMagEncoder_Relative);
- _talon.SetSensorDirection(true); /* keep sensor and motor in phase */
- }
- /** function is called periodically during operator control */
- void TeleopPeriodic()
- {
- /* get buttons */
- bool btns[10];
- for(unsigned int i=1;i<10;++i)
- btns[i] = _joy.GetRawButton(i);
-
- /* get the left joystick axis on Logitech Gampead */
- double leftYjoystick = -1 * _joy.GetY(); /* multiple by -1 so joystick forward is positive */
-
- /* call this periodically, and catch the output. Only apply it if user wants to run MP. */
- _example.control();
-
- if (btns[5] == false) { /* Check button 5 (top left shoulder on the logitech gamead). */
- /*
- * If it's not being pressed, just do a simple drive. This
- * could be a RobotDrive class or custom drivetrain logic.
- * The point is we want the switch in and out of MP Control mode.*/
-
- /* button5 is off so straight drive */
- _talon.SetControlMode(CANTalon::kVoltage);
- _talon.Set(12.0 * leftYjoystick);
-
- _example.reset();
- } else {
- /* Button5 is held down so switch to motion profile control mode => This is done in MotionProfileControl.
- * When we transition from no-press to press,
- * pass a "true" once to MotionProfileControl.
- */
- _talon.SetControlMode(CANTalon::kMotionProfile);
-
- CANTalon::SetValueMotionProfile setOutput = _example.getSetValue();
-
- _talon.Set(setOutput);
-
- /* if btn is pressed and was not pressed last time,
- * In other words we just detected the on-press event.
- * This will signal the robot to start a MP */
- if( (btns[6] == true) && (_btnsLast[6] == false) ) {
- /* user just tapped button 6 */
-
- //------------ We could start an MP if MP isn't already running ------------//
- _example.start();
- }
- }
-
- /* save buttons states for on-press detection */
- for(int i=1;i<10;++i)
- _btnsLast[i] = btns[i];
-
- }
-
- void DisabledPeriodic()
- {
- /* it's generally a good idea to put motor controllers back
- * into a known state when robot is disabled. That way when you
- * enable the robot doesn't just continue doing what it was doing before.
- * BUT if that's what the application/testing requires than modify this accordingly */
- _talon.SetControlMode(CANTalon::kPercentVbus);
- _talon.Set( 0 );
- /* clear our buffer and put everything into a known state */
- _example.reset();
- }
+ /** The Talon we want to motion profile. */
+ CANTalon _talon;
+
+ /** some example logic on how one can manage an MP */
+ MotionProfileExample _example;
+
+ /** joystick for testing */
+ Joystick _joy;
+
+ /** cache last buttons so we can detect press events. In a command-based project you can leverage the on-press event
+ * but for this simple example, lets just do quick compares to prev-btn-states */
+ bool _btnsLast[10] = {false,false,false,false,false,false,false,false,false,false};
+
+
+ Robot() : _talon(6), _example(_talon), _joy(0)
+ {
+ _talon.SetFeedbackDevice(CANTalon::CtreMagEncoder_Relative);
+ _talon.SetSensorDirection(true); /* keep sensor and motor in phase */
+ }
+ /** function is called periodically during operator control */
+ void TeleopPeriodic()
+ {
+ /* get buttons */
+ bool btns[10];
+ for(unsigned int i=1;i<10;++i)
+ btns[i] = _joy.GetRawButton(i);
+
+ /* get the left joystick axis on Logitech Gampead */
+ double leftYjoystick = -1 * _joy.GetY(); /* multiple by -1 so joystick forward is positive */
+
+ /* call this periodically, and catch the output. Only apply it if user wants to run MP. */
+ _example.control();
+
+ if (btns[5] == false) { /* Check button 5 (top left shoulder on the logitech gamead). */
+ /*
+ * If it's not being pressed, just do a simple drive. This
+ * could be a RobotDrive class or custom drivetrain logic.
+ * The point is we want the switch in and out of MP Control mode.*/
+
+ /* button5 is off so straight drive */
+ _talon.SetControlMode(CANTalon::kVoltage);
+ _talon.Set(12.0 * leftYjoystick);
+
+ _example.reset();
+ } else {
+ /* Button5 is held down so switch to motion profile control mode => This is done in MotionProfileControl.
+ * When we transition from no-press to press,
+ * pass a "true" once to MotionProfileControl.
+ */
+ _talon.SetControlMode(CANTalon::kMotionProfile);
+
+ CANTalon::SetValueMotionProfile setOutput = _example.getSetValue();
+
+ _talon.Set(setOutput);
+
+ /* if btn is pressed and was not pressed last time,
+ * In other words we just detected the on-press event.
+ * This will signal the robot to start a MP */
+ if( (btns[6] == true) && (_btnsLast[6] == false) ) {
+ /* user just tapped button 6 */
+
+ //------------ We could start an MP if MP isn't already running ------------//
+ _example.start();
+ }
+ }
+
+ /* save buttons states for on-press detection */
+ for(int i=1;i<10;++i)
+ _btnsLast[i] = btns[i];
+
+ }
+
+ void DisabledPeriodic()
+ {
+ /* it's generally a good idea to put motor controllers back
+ * into a known state when robot is disabled. That way when you
+ * enable the robot doesn't just continue doing what it was doing before.
+ * BUT if that's what the application/testing requires than modify this accordingly */
+ _talon.SetControlMode(CANTalon::kPercentVbus);
+ _talon.Set( 0 );
+ /* clear our buffer and put everything into a known state */
+ _example.reset();
+ }
};
START_ROBOT_CLASS(Robot)
diff --git a/CPP_Pigeon_StraightServo_Example/.cproject b/CPP_Pigeon_StraightServo_Example/.cproject
index fd9f88e..104aaa2 100644
--- a/CPP_Pigeon_StraightServo_Example/.cproject
+++ b/CPP_Pigeon_StraightServo_Example/.cproject
@@ -1,288 +1,288 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/CPP_Pigeon_StraightServo_Example/.project b/CPP_Pigeon_StraightServo_Example/.project
index 992c486..2dcc99a 100644
--- a/CPP_Pigeon_StraightServo_Example/.project
+++ b/CPP_Pigeon_StraightServo_Example/.project
@@ -1,28 +1,28 @@
- CPP_Pigeon_StraightServo_Example
-
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.genmakebuilder
- clean,full,incremental,
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
- full,incremental,
-
-
-
-
-
- org.eclipse.cdt.core.cnature
- org.eclipse.cdt.core.ccnature
- org.eclipse.cdt.managedbuilder.core.managedBuildNature
- org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ CPP_Pigeon_StraightServo_Example
+
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.genmakebuilder
+ clean,full,incremental,
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
+ full,incremental,
+
+
+
+
+
+ org.eclipse.cdt.core.cnature
+ org.eclipse.cdt.core.ccnature
+ org.eclipse.cdt.managedbuilder.core.managedBuildNature
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/CPP_Pigeon_StraightServo_Example/.settings/language.settings.xml b/CPP_Pigeon_StraightServo_Example/.settings/language.settings.xml
index 4313ad1..8c5002a 100644
--- a/CPP_Pigeon_StraightServo_Example/.settings/language.settings.xml
+++ b/CPP_Pigeon_StraightServo_Example/.settings/language.settings.xml
@@ -1,33 +1,33 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/CPP_Pigeon_StraightServo_Example/src/Robot.cpp b/CPP_Pigeon_StraightServo_Example/src/Robot.cpp
index 75448f1..7538fd4 100644
--- a/CPP_Pigeon_StraightServo_Example/src/Robot.cpp
+++ b/CPP_Pigeon_StraightServo_Example/src/Robot.cpp
@@ -14,208 +14,208 @@
#include "PigeonImu.h"
#include "CANTalon.h"
class Robot: public IterativeRobot {
- /* robot peripherals */
- CANTalon * _leftFront;
- CANTalon * _rightFront;
- CANTalon * _leftRear;
- CANTalon * _rightRear;
- CANTalon * _spareTalon; /* spare talon, remove if not necessary, Pigeon can be placed on CANbus or plugged into a Talon. */
- PigeonImu * _pidgey;
- Joystick *_driveStick; /* Joystick object on USB port 1 */
- /** state for tracking whats controlling the drivetrain */
- enum {
- GoStraightOff, GoStraightWithPidgeon, GoStraightSameThrottle
- } _goStraight = GoStraightOff;
+ /* robot peripherals */
+ CANTalon * _leftFront;
+ CANTalon * _rightFront;
+ CANTalon * _leftRear;
+ CANTalon * _rightRear;
+ CANTalon * _spareTalon; /* spare talon, remove if not necessary, Pigeon can be placed on CANbus or plugged into a Talon. */
+ PigeonImu * _pidgey;
+ Joystick *_driveStick; /* Joystick object on USB port 1 */
+ /** state for tracking whats controlling the drivetrain */
+ enum {
+ GoStraightOff, GoStraightWithPidgeon, GoStraightSameThrottle
+ } _goStraight = GoStraightOff;
- /* Some gains for heading servo,
- * these were tweaked by using the web-based config (CAN Talon) and
- * pressing gamepad button 6 to load them.
- */
- double kPgain = 0.04; /* percent throttle per degree of error */
- double kDgain = 0.0004; /* percent throttle per angular velocity dps */
- double kMaxCorrectionRatio = 0.30; /* cap corrective turning throttle to 30 percent of forward throttle */
- /** holds the current angle to servo to */
- double _targetAngle = 0;
- /** count loops to print every second or so */
- int _printLoops = 0;
+ /* Some gains for heading servo,
+ * these were tweaked by using the web-based config (CAN Talon) and
+ * pressing gamepad button 6 to load them.
+ */
+ double kPgain = 0.04; /* percent throttle per degree of error */
+ double kDgain = 0.0004; /* percent throttle per angular velocity dps */
+ double kMaxCorrectionRatio = 0.30; /* cap corrective turning throttle to 30 percent of forward throttle */
+ /** holds the current angle to servo to */
+ double _targetAngle = 0;
+ /** count loops to print every second or so */
+ int _printLoops = 0;
public:
- /**
- * Constructor for this class.
- */
- Robot() {
- _leftFront = new CANTalon(6);
- _rightFront = new CANTalon(3);
- _leftRear = new CANTalon(4);
- _rightRear = new CANTalon(1);
- _spareTalon = new CANTalon(2);
+ /**
+ * Constructor for this class.
+ */
+ Robot() {
+ _leftFront = new CANTalon(6);
+ _rightFront = new CANTalon(3);
+ _leftRear = new CANTalon(4);
+ _rightRear = new CANTalon(1);
+ _spareTalon = new CANTalon(2);
- /* choose which cabling method for Pigeon */
- //_pidgey = new PigeonImu(0); /* Pigeon is on CANBus (powered from ~12V, and has a device ID of zero */
- _pidgey = new PigeonImu(_spareTalon); /* Pigeon is ribbon cabled to the specified CANTalon. */
+ /* choose which cabling method for Pigeon */
+ //_pidgey = new PigeonImu(0); /* Pigeon is on CANBus (powered from ~12V, and has a device ID of zero */
+ _pidgey = new PigeonImu(_spareTalon); /* Pigeon is ribbon cabled to the specified CANTalon. */
- /* Define joystick being used at USB port #0 on the Drivers Station */
- _driveStick = new Joystick(0);
- }
+ /* Define joystick being used at USB port #0 on the Drivers Station */
+ _driveStick = new Joystick(0);
+ }
- void TeleopInit() {
- _pidgey->SetFusedHeading(0.0); /* reset heading, angle measurement wraps at plus/minus 23,040 degrees (64 rotations) */
- _goStraight = GoStraightOff;
- }
+ void TeleopInit() {
+ _pidgey->SetFusedHeading(0.0); /* reset heading, angle measurement wraps at plus/minus 23,040 degrees (64 rotations) */
+ _goStraight = GoStraightOff;
+ }
- /**
- * Gets called once for each new packet from the DS.
- */
- void TeleopPeriodic() {
- /* some temps for Pigeon API */
- PigeonImu::GeneralStatus genStatus;
- double xyz_dps[3];
- /* grab some input data from Pigeon and gamepad*/
- _pidgey->GetGeneralStatus(genStatus);
- _pidgey->GetRawGyro(xyz_dps);
- double currentAngle = _pidgey->GetFusedHeading();
- bool angleIsGood = (_pidgey->GetState() == PigeonImu::Ready) ? true : false;
- double currentAngularRate = xyz_dps[2];
- /* get input from gamepad */
- bool userWantsGoStraight = _driveStick->GetRawButton(5); /* top left shoulder button */
- double forwardThrottle = _driveStick->GetAxis(Joystick::kYAxis) * -1.0; /* sign so that positive is forward */
- double turnThrottle = _driveStick->GetAxis(Joystick::kTwistAxis) * -1.0; /* sign so that positive means turn left */
- /* deadbands so centering joysticks always results in zero output */
- forwardThrottle = Db(forwardThrottle);
- turnThrottle = Db(turnThrottle);
- /* simple state machine to update our goStraight selection */
- switch (_goStraight) {
+ /**
+ * Gets called once for each new packet from the DS.
+ */
+ void TeleopPeriodic() {
+ /* some temps for Pigeon API */
+ PigeonImu::GeneralStatus genStatus;
+ double xyz_dps[3];
+ /* grab some input data from Pigeon and gamepad*/
+ _pidgey->GetGeneralStatus(genStatus);
+ _pidgey->GetRawGyro(xyz_dps);
+ double currentAngle = _pidgey->GetFusedHeading();
+ bool angleIsGood = (_pidgey->GetState() == PigeonImu::Ready) ? true : false;
+ double currentAngularRate = xyz_dps[2];
+ /* get input from gamepad */
+ bool userWantsGoStraight = _driveStick->GetRawButton(5); /* top left shoulder button */
+ double forwardThrottle = _driveStick->GetAxis(Joystick::kYAxis) * -1.0; /* sign so that positive is forward */
+ double turnThrottle = _driveStick->GetAxis(Joystick::kTwistAxis) * -1.0; /* sign so that positive means turn left */
+ /* deadbands so centering joysticks always results in zero output */
+ forwardThrottle = Db(forwardThrottle);
+ turnThrottle = Db(turnThrottle);
+ /* simple state machine to update our goStraight selection */
+ switch (_goStraight) {
- /* go straight is off, better check gamepad to see if we should enable the feature */
- case GoStraightOff:
- if (userWantsGoStraight == false) {
- /* nothing to do */
- } else if (angleIsGood == false) {
- /* user wants to servo but Pigeon isn't connected? */
- _goStraight = GoStraightSameThrottle; /* just apply same throttle to both sides */
- } else {
- /* user wants to servo, save the current heading so we know where to servo to. */
- _goStraight = GoStraightWithPidgeon;
- _targetAngle = currentAngle;
- }
- break;
+ /* go straight is off, better check gamepad to see if we should enable the feature */
+ case GoStraightOff:
+ if (userWantsGoStraight == false) {
+ /* nothing to do */
+ } else if (angleIsGood == false) {
+ /* user wants to servo but Pigeon isn't connected? */
+ _goStraight = GoStraightSameThrottle; /* just apply same throttle to both sides */
+ } else {
+ /* user wants to servo, save the current heading so we know where to servo to. */
+ _goStraight = GoStraightWithPidgeon;
+ _targetAngle = currentAngle;
+ }
+ break;
- /* we are servo-ing heading with Pigeon */
- case GoStraightWithPidgeon:
- if (userWantsGoStraight == false) {
- _goStraight = GoStraightOff; /* user let go, turn off the feature */
- } else if (angleIsGood == false) {
- _goStraight = GoStraightSameThrottle; /* we were servoing with pidgy, but we lost connection? Check wiring and deviceID setup */
- } else {
- /* user still wants to drive straight, keep doing it */
- }
- break;
+ /* we are servo-ing heading with Pigeon */
+ case GoStraightWithPidgeon:
+ if (userWantsGoStraight == false) {
+ _goStraight = GoStraightOff; /* user let go, turn off the feature */
+ } else if (angleIsGood == false) {
+ _goStraight = GoStraightSameThrottle; /* we were servoing with pidgy, but we lost connection? Check wiring and deviceID setup */
+ } else {
+ /* user still wants to drive straight, keep doing it */
+ }
+ break;
- /* we are simply applying the same throttle to both sides, apparently Pigeon is not connected */
- case GoStraightSameThrottle:
- if (userWantsGoStraight == false) {
- _goStraight = GoStraightOff; /* user let go, turn off the feature */
- } else {
- /* user still wants to drive straight, keep doing it */
- }
- break;
- }
+ /* we are simply applying the same throttle to both sides, apparently Pigeon is not connected */
+ case GoStraightSameThrottle:
+ if (userWantsGoStraight == false) {
+ _goStraight = GoStraightOff; /* user let go, turn off the feature */
+ } else {
+ /* user still wants to drive straight, keep doing it */
+ }
+ break;
+ }
- /* if we can servo with IMU, do the math here */
- if (_goStraight == GoStraightWithPidgeon) {
- /* very simple Proportional and Derivative (PD) loop with a cap,
- * replace with favorite close loop strategy or leverage future Talon <=> Pigeon features. */
- turnThrottle = (_targetAngle - currentAngle) * kPgain - (currentAngularRate) * kDgain;
- /* the max correction is the forward throttle times a scalar,
- * This can be done a number of ways but basically only apply small turning correction when we are moving slow
- * and larger correction the faster we move. Otherwise you may need stiffer pgain at higher velocities. */
- double maxThrot = MaxCorrection(forwardThrottle, kMaxCorrectionRatio);
- turnThrottle = Cap(turnThrottle, maxThrot);
- } else if (_goStraight == GoStraightSameThrottle) {
- /* clear the turn throttle, just apply same throttle to both sides */
- turnThrottle = 0;
- } else {
- /* do nothing */
- }
+ /* if we can servo with IMU, do the math here */
+ if (_goStraight == GoStraightWithPidgeon) {
+ /* very simple Proportional and Derivative (PD) loop with a cap,
+ * replace with favorite close loop strategy or leverage future Talon <=> Pigeon features. */
+ turnThrottle = (_targetAngle - currentAngle) * kPgain - (currentAngularRate) * kDgain;
+ /* the max correction is the forward throttle times a scalar,
+ * This can be done a number of ways but basically only apply small turning correction when we are moving slow
+ * and larger correction the faster we move. Otherwise you may need stiffer pgain at higher velocities. */
+ double maxThrot = MaxCorrection(forwardThrottle, kMaxCorrectionRatio);
+ turnThrottle = Cap(turnThrottle, maxThrot);
+ } else if (_goStraight == GoStraightSameThrottle) {
+ /* clear the turn throttle, just apply same throttle to both sides */
+ turnThrottle = 0;
+ } else {
+ /* do nothing */
+ }
- /* positive turnThrottle means turn to the left, this can be replaced with ArcadeDrive object, or teams drivetrain object */
- float left = forwardThrottle - turnThrottle;
- float right = forwardThrottle + turnThrottle;
- left = Cap(left, 1.0);
- right = Cap(right, 1.0);
+ /* positive turnThrottle means turn to the left, this can be replaced with ArcadeDrive object, or teams drivetrain object */
+ float left = forwardThrottle - turnThrottle;
+ float right = forwardThrottle + turnThrottle;
+ left = Cap(left, 1.0);
+ right = Cap(right, 1.0);
- /* my right side motors need to drive negative to move robot forward */
- _leftFront->Set(left);
- _leftRear->Set(left);
- _rightFront->Set(-1. * right);
- _rightRear->Set(-1. * right);
+ /* my right side motors need to drive negative to move robot forward */
+ _leftFront->Set(left);
+ _leftRear->Set(left);
+ _rightFront->Set(-1. * right);
+ _rightRear->Set(-1. * right);
- /* some printing for easy debugging */
- if (++_printLoops > 50){
- _printLoops = 0;
- printf("------------------------------------------\n");
- printf("error: %f\n", _targetAngle - currentAngle);
- printf("angle: %f\n", currentAngle);
- printf("rate: %f\n", currentAngularRate);
- printf("noMotionBiasCount: %i\n", genStatus.noMotionBiasCount);
- printf("tempCompensationCount: %i\n", genStatus.tempCompensationCount);
- printf("%s\n", angleIsGood ? "Angle is good" : "Angle is NOT GOOD");
- printf("------------------------------------------\n");
- }
+ /* some printing for easy debugging */
+ if (++_printLoops > 50){
+ _printLoops = 0;
+ printf("------------------------------------------\n");
+ printf("error: %f\n", _targetAngle - currentAngle);
+ printf("angle: %f\n", currentAngle);
+ printf("rate: %f\n", currentAngularRate);
+ printf("noMotionBiasCount: %i\n", genStatus.noMotionBiasCount);
+ printf("tempCompensationCount: %i\n", genStatus.tempCompensationCount);
+ printf("%s\n", angleIsGood ? "Angle is good" : "Angle is NOT GOOD");
+ printf("------------------------------------------\n");
+ }
- /* press btn 6, top right shoulder, to apply gains from webdash. This can
- * be replaced with your favorite means of changing gains. */
- if (_driveStick->GetRawButton(6)) {
- UpdatGains();
- }
- }
+ /* press btn 6, top right shoulder, to apply gains from webdash. This can
+ * be replaced with your favorite means of changing gains. */
+ if (_driveStick->GetRawButton(6)) {
+ UpdatGains();
+ }
+ }
- /** @return 10% deadband */
- double Db(double axisVal) {
- if (axisVal < -0.10)
- return axisVal;
- if (axisVal > +0.10)
- return axisVal;
- return 0;
- }
- /** @param value to cap.
- * @param peak positive double representing the maximum (peak) value.
- * @return a capped value.
- */
- double Cap(double value, double peak) {
- if (value < -peak)
- return -peak;
- if (value > +peak)
- return +peak;
- return value;
- }
- /**
- * As a simple trick, lets take the spare talon and use the web-based
- * config to easily change the gains we use for the Pigeon servo.
- * The talon isn't being used for closed-loop, just use it as a convenient
- * storage for gains.
- */
- void UpdatGains() {
- kPgain = _spareTalon->GetP();
- kDgain = _spareTalon->GetD();
- kMaxCorrectionRatio = _spareTalon->GetF();
- }
- /**
- * Given the robot forward throttle and ratio, return the max
- * corrective turning throttle to adjust for heading. This is
- * a simple method of avoiding using different gains for
- * low speed, high speed, and no-speed (zero turns).
- */
- double MaxCorrection(double forwardThrot, double scalor) {
- /* make it positive */
- if(forwardThrot < 0) {forwardThrot = -forwardThrot;}
- /* max correction is the current forward throttle scaled down */
- forwardThrot *= scalor;
- /* ensure caller is allowed at least 10% throttle,
- * regardless of forward throttle */
- if(forwardThrot < 0.10)
- return 0.10;
- return forwardThrot;
- }
+ /** @return 10% deadband */
+ double Db(double axisVal) {
+ if (axisVal < -0.10)
+ return axisVal;
+ if (axisVal > +0.10)
+ return axisVal;
+ return 0;
+ }
+ /** @param value to cap.
+ * @param peak positive double representing the maximum (peak) value.
+ * @return a capped value.
+ */
+ double Cap(double value, double peak) {
+ if (value < -peak)
+ return -peak;
+ if (value > +peak)
+ return +peak;
+ return value;
+ }
+ /**
+ * As a simple trick, lets take the spare talon and use the web-based
+ * config to easily change the gains we use for the Pigeon servo.
+ * The talon isn't being used for closed-loop, just use it as a convenient
+ * storage for gains.
+ */
+ void UpdatGains() {
+ kPgain = _spareTalon->GetP();
+ kDgain = _spareTalon->GetD();
+ kMaxCorrectionRatio = _spareTalon->GetF();
+ }
+ /**
+ * Given the robot forward throttle and ratio, return the max
+ * corrective turning throttle to adjust for heading. This is
+ * a simple method of avoiding using different gains for
+ * low speed, high speed, and no-speed (zero turns).
+ */
+ double MaxCorrection(double forwardThrot, double scalor) {
+ /* make it positive */
+ if(forwardThrot < 0) {forwardThrot = -forwardThrot;}
+ /* max correction is the current forward throttle scaled down */
+ forwardThrot *= scalor;
+ /* ensure caller is allowed at least 10% throttle,
+ * regardless of forward throttle */
+ if(forwardThrot < 0.10)
+ return 0.10;
+ return forwardThrot;
+ }
};
START_ROBOT_CLASS(Robot)
diff --git a/CPP_PositionClosedLoop/.cproject b/CPP_PositionClosedLoop/.cproject
index e988740..6555574 100644
--- a/CPP_PositionClosedLoop/.cproject
+++ b/CPP_PositionClosedLoop/.cproject
@@ -1,288 +1,288 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/CPP_PositionClosedLoop/.project b/CPP_PositionClosedLoop/.project
index 74de47b..bbdab36 100644
--- a/CPP_PositionClosedLoop/.project
+++ b/CPP_PositionClosedLoop/.project
@@ -1,28 +1,28 @@
- CPP_PositionClosedLoop
-
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.genmakebuilder
- clean,full,incremental,
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
- full,incremental,
-
-
-
-
-
- org.eclipse.cdt.core.cnature
- org.eclipse.cdt.core.ccnature
- org.eclipse.cdt.managedbuilder.core.managedBuildNature
- org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ CPP_PositionClosedLoop
+
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.genmakebuilder
+ clean,full,incremental,
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
+ full,incremental,
+
+
+
+
+
+ org.eclipse.cdt.core.cnature
+ org.eclipse.cdt.core.ccnature
+ org.eclipse.cdt.managedbuilder.core.managedBuildNature
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/CPP_PositionClosedLoop/.settings/language.settings.xml b/CPP_PositionClosedLoop/.settings/language.settings.xml
index 4313ad1..8c5002a 100644
--- a/CPP_PositionClosedLoop/.settings/language.settings.xml
+++ b/CPP_PositionClosedLoop/.settings/language.settings.xml
@@ -1,33 +1,33 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/CPP_PositionClosedLoop/src/Robot.cpp b/CPP_PositionClosedLoop/src/Robot.cpp
index c5a1044..b51210a 100644
--- a/CPP_PositionClosedLoop/src/Robot.cpp
+++ b/CPP_PositionClosedLoop/src/Robot.cpp
@@ -20,87 +20,87 @@
class Robot: public IterativeRobot {
private:
- CANTalon * _talon = new CANTalon(0);
- Joystick * _joy = new Joystick(0);
- std::string _sb;
- int _loops = 0;
- bool _lastButton1 = false;
- /** save the target position to servo to */
- double targetPositionRotations;
+ CANTalon * _talon = new CANTalon(0);
+ Joystick * _joy = new Joystick(0);
+ std::string _sb;
+ int _loops = 0;
+ bool _lastButton1 = false;
+ /** save the target position to servo to */
+ double targetPositionRotations;
- void RobotInit() {
- /* lets grab the 360 degree position of the MagEncoder's absolute position */
- int absolutePosition = _talon->GetPulseWidthPosition() & 0xFFF; /* mask out the bottom12 bits, we don't care about the wrap arounds */
- /* use the low level API to set the quad encoder signal */
- _talon->SetEncPosition(absolutePosition);
+ void RobotInit() {
+ /* lets grab the 360 degree position of the MagEncoder's absolute position */
+ int absolutePosition = _talon->GetPulseWidthPosition() & 0xFFF; /* mask out the bottom12 bits, we don't care about the wrap arounds */
+ /* use the low level API to set the quad encoder signal */
+ _talon->SetEncPosition(absolutePosition);
- /* choose the sensor and sensor direction */
- _talon->SetFeedbackDevice(CANTalon::CtreMagEncoder_Relative);
- _talon->SetSensorDirection(false);
- //_talon->ConfigEncoderCodesPerRev(XXX), // if using FeedbackDevice.QuadEncoder
- //_talon->ConfigPotentiometerTurns(XXX), // if using FeedbackDevice.AnalogEncoder or AnalogPot
+ /* choose the sensor and sensor direction */
+ _talon->SetFeedbackDevice(CANTalon::CtreMagEncoder_Relative);
+ _talon->SetSensorDirection(false);
+ //_talon->ConfigEncoderCodesPerRev(XXX), // if using FeedbackDevice.QuadEncoder
+ //_talon->ConfigPotentiometerTurns(XXX), // if using FeedbackDevice.AnalogEncoder or AnalogPot
- /* set the peak and nominal outputs, 12V means full */
- _talon->ConfigNominalOutputVoltage(+0., -0.);
- _talon->ConfigPeakOutputVoltage(+12., -12.);
- /* set the allowable closed-loop error,
- * Closed-Loop output will be neutral within this range.
- * See Table in Section 17.2.1 for native units per rotation.
- */
- _talon->SetAllowableClosedLoopErr(0); /* always servo */
- /* set closed loop gains in slot0 */
- _talon->SelectProfileSlot(0);
- _talon->SetF(0.0);
- _talon->SetP(0.1);
- _talon->SetI(0.0);
- _talon->SetD(0.0);
- }
+ /* set the peak and nominal outputs, 12V means full */
+ _talon->ConfigNominalOutputVoltage(+0., -0.);
+ _talon->ConfigPeakOutputVoltage(+12., -12.);
+ /* set the allowable closed-loop error,
+ * Closed-Loop output will be neutral within this range.
+ * See Table in Section 17.2.1 for native units per rotation.
+ */
+ _talon->SetAllowableClosedLoopErr(0); /* always servo */
+ /* set closed loop gains in slot0 */
+ _talon->SelectProfileSlot(0);
+ _talon->SetF(0.0);
+ _talon->SetP(0.1);
+ _talon->SetI(0.0);
+ _talon->SetD(0.0);
+ }
- /**
- * This function is called periodically during operator control
- */
- void TeleopPeriodic() {
- /* get gamepad axis */
- double leftYstick = _joy->GetAxis(Joystick::kYAxis);
- double motorOutput = _talon->GetOutputVoltage() / _talon->GetBusVoltage();
- bool button1 = _joy->GetRawButton(1);
- bool button2 = _joy->GetRawButton(2);
- /* prepare line to print */
- _sb.append("\tout:");
- _sb.append(std::to_string(motorOutput));
- _sb.append("\tpos:");
- _sb.append(std::to_string(_talon->GetPosition()));
- /* on button1 press enter closed-loop mode on target position */
- if (!_lastButton1 && button1) {
- /* Position mode - button just pressed */
- targetPositionRotations = leftYstick * 50.0; /* 50 Rotations in either direction */
- _talon->SetControlMode(CANSpeedController::kPosition);
- _talon->Set(targetPositionRotations); /* 50 rotations in either direction */
+ /**
+ * This function is called periodically during operator control
+ */
+ void TeleopPeriodic() {
+ /* get gamepad axis */
+ double leftYstick = _joy->GetAxis(Joystick::kYAxis);
+ double motorOutput = _talon->GetOutputVoltage() / _talon->GetBusVoltage();
+ bool button1 = _joy->GetRawButton(1);
+ bool button2 = _joy->GetRawButton(2);
+ /* prepare line to print */
+ _sb.append("\tout:");
+ _sb.append(std::to_string(motorOutput));
+ _sb.append("\tpos:");
+ _sb.append(std::to_string(_talon->GetPosition()));
+ /* on button1 press enter closed-loop mode on target position */
+ if (!_lastButton1 && button1) {
+ /* Position mode - button just pressed */
+ targetPositionRotations = leftYstick * 50.0; /* 50 Rotations in either direction */
+ _talon->SetControlMode(CANSpeedController::kPosition);
+ _talon->Set(targetPositionRotations); /* 50 rotations in either direction */
- }
- /* on button2 just straight drive */
- if (button2) {
- /* Percent voltage mode */
- _talon->SetControlMode(CANSpeedController::kPercentVbus);
- _talon->Set(leftYstick);
- }
- /* if Talon is in position closed-loop, print some more info */
- if (_talon->GetControlMode() == CANSpeedController::kPosition) {
- /* append more signals to print when in speed mode. */
- _sb.append("\terrNative:");
- _sb.append(std::to_string(_talon->GetClosedLoopError()));
- _sb.append("\ttrg:");
- _sb.append(std::to_string(targetPositionRotations));
- }
- /* print every ten loops, printing too much too fast is generally bad for performance */
- if (++_loops >= 10) {
- _loops = 0;
- printf("%s\n",_sb.c_str());
- }
- _sb.clear();
- /* save button state for on press detect */
- _lastButton1 = button1;
- }
+ }
+ /* on button2 just straight drive */
+ if (button2) {
+ /* Percent voltage mode */
+ _talon->SetControlMode(CANSpeedController::kPercentVbus);
+ _talon->Set(leftYstick);
+ }
+ /* if Talon is in position closed-loop, print some more info */
+ if (_talon->GetControlMode() == CANSpeedController::kPosition) {
+ /* append more signals to print when in speed mode. */
+ _sb.append("\terrNative:");
+ _sb.append(std::to_string(_talon->GetClosedLoopError()));
+ _sb.append("\ttrg:");
+ _sb.append(std::to_string(targetPositionRotations));
+ }
+ /* print every ten loops, printing too much too fast is generally bad for performance */
+ if (++_loops >= 10) {
+ _loops = 0;
+ printf("%s\n",_sb.c_str());
+ }
+ _sb.clear();
+ /* save button state for on press detect */
+ _lastButton1 = button1;
+ }
};
diff --git a/CPP_SetSensorPositionExample/.cproject b/CPP_SetSensorPositionExample/.cproject
index 743f369..d2db240 100644
--- a/CPP_SetSensorPositionExample/.cproject
+++ b/CPP_SetSensorPositionExample/.cproject
@@ -1,289 +1,289 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/CPP_SetSensorPositionExample/.project b/CPP_SetSensorPositionExample/.project
index 3782604..d4d72c5 100644
--- a/CPP_SetSensorPositionExample/.project
+++ b/CPP_SetSensorPositionExample/.project
@@ -1,28 +1,28 @@
- CPP_SetSensorPositionExample
-
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.genmakebuilder
- clean,full,incremental,
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
- full,incremental,
-
-
-
-
-
- org.eclipse.cdt.core.cnature
- org.eclipse.cdt.core.ccnature
- org.eclipse.cdt.managedbuilder.core.managedBuildNature
- org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ CPP_SetSensorPositionExample
+
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.genmakebuilder
+ clean,full,incremental,
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
+ full,incremental,
+
+
+
+
+
+ org.eclipse.cdt.core.cnature
+ org.eclipse.cdt.core.ccnature
+ org.eclipse.cdt.managedbuilder.core.managedBuildNature
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/CPP_SetSensorPositionExample/.settings/language.settings.xml b/CPP_SetSensorPositionExample/.settings/language.settings.xml
index 0bee554..38b9a5d 100644
--- a/CPP_SetSensorPositionExample/.settings/language.settings.xml
+++ b/CPP_SetSensorPositionExample/.settings/language.settings.xml
@@ -1,33 +1,33 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/CPP_SetSensorPositionExample/src/Robot.cpp b/CPP_SetSensorPositionExample/src/Robot.cpp
index 6c93554..40376c3 100644
--- a/CPP_SetSensorPositionExample/src/Robot.cpp
+++ b/CPP_SetSensorPositionExample/src/Robot.cpp
@@ -6,46 +6,46 @@
#include
class Robot: public frc::IterativeRobot {
public:
- CANTalon _srx;
- Joystick _joy;
- std::stringstream _work;
- bool _btn1, _btn2, _btn3, _btn4;
- /** simple constructor */
- Robot() : _srx(9), _joy(0), _work(), _btn1(false), _btn2(false), _btn3(false), _btn4(false) { }
- /* everytime we enter disable, reinit*/
- void DisabledInit() {
- _srx.SetFeedbackDevice(CANTalon::CtreMagEncoder_Relative); /* MagEncoder meets the requirements for Unit-Scaling */
- _srx.SetStatusFrameRateMs(CANTalon::StatusFrameRateFeedback, 5); /* Talon will send new frame every 5ms */
- }
- /* every loop */
- void DisabledPeriodic() {
- bool btn1 = _joy.GetRawButton(1); /* get buttons */
- bool btn2 = _joy.GetRawButton(2);
- bool btn3 = _joy.GetRawButton(3);
- bool btn4 = _joy.GetRawButton(4);
+ CANTalon _srx;
+ Joystick _joy;
+ std::stringstream _work;
+ bool _btn1, _btn2, _btn3, _btn4;
+ /** simple constructor */
+ Robot() : _srx(9), _joy(0), _work(), _btn1(false), _btn2(false), _btn3(false), _btn4(false) { }
+ /* everytime we enter disable, reinit*/
+ void DisabledInit() {
+ _srx.SetFeedbackDevice(CANTalon::CtreMagEncoder_Relative); /* MagEncoder meets the requirements for Unit-Scaling */
+ _srx.SetStatusFrameRateMs(CANTalon::StatusFrameRateFeedback, 5); /* Talon will send new frame every 5ms */
+ }
+ /* every loop */
+ void DisabledPeriodic() {
+ bool btn1 = _joy.GetRawButton(1); /* get buttons */
+ bool btn2 = _joy.GetRawButton(2);
+ bool btn3 = _joy.GetRawButton(3);
+ bool btn4 = _joy.GetRawButton(4);
- /* on button unpress => press, change pos register */
- if(!_btn1 && btn1) { _srx.SetPosition(10.0); _work << "set:10.0" << std::endl; }
- if(!_btn2 && btn2) { _srx.SetPosition(20.0); _work << "set:20.0" << std::endl; }
- if(!_btn3 && btn3) { _srx.SetPosition(30.0); _work << "set:30.0" << std::endl; }
- if(!_btn4 && btn4) { _srx.SetPosition(40.0); _work << "set:40.0" << std::endl; }
+ /* on button unpress => press, change pos register */
+ if(!_btn1 && btn1) { _srx.SetPosition(10.0); _work << "set:10.0" << std::endl; }
+ if(!_btn2 && btn2) { _srx.SetPosition(20.0); _work << "set:20.0" << std::endl; }
+ if(!_btn3 && btn3) { _srx.SetPosition(30.0); _work << "set:30.0" << std::endl; }
+ if(!_btn4 && btn4) { _srx.SetPosition(40.0); _work << "set:40.0" << std::endl; }
- /* remove this and at most we get one stale print (one loop) */
- usleep(10e3);
+ /* remove this and at most we get one stale print (one loop) */
+ usleep(10e3);
- /* call get and serialize what we get */
- double read = _srx.GetPosition();
- _work << "read:" << read<< std::endl;
+ /* call get and serialize what we get */
+ double read = _srx.GetPosition();
+ _work << "read:" << read<< std::endl;
- /* print any rendered strings, and clear work */
- printf(_work.str().c_str());
- _work.str("");
+ /* print any rendered strings, and clear work */
+ printf(_work.str().c_str());
+ _work.str("");
- _btn1 = btn1; /* save button states */
- _btn2 = btn2;
- _btn3 = btn3;
- _btn4 = btn4;
- }
+ _btn1 = btn1; /* save button states */
+ _btn2 = btn2;
+ _btn3 = btn3;
+ _btn4 = btn4;
+ }
};
START_ROBOT_CLASS(Robot)
diff --git a/CPP_SimpleCommand_Example/.cproject b/CPP_SimpleCommand_Example/.cproject
index bfb5b85..faff5a2 100644
--- a/CPP_SimpleCommand_Example/.cproject
+++ b/CPP_SimpleCommand_Example/.cproject
@@ -1,289 +1,289 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/CPP_SimpleCommand_Example/.project b/CPP_SimpleCommand_Example/.project
index 8025009..3a7cabe 100644
--- a/CPP_SimpleCommand_Example/.project
+++ b/CPP_SimpleCommand_Example/.project
@@ -1,28 +1,28 @@
- CPP_SimpleCommand_Example
-
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.genmakebuilder
- clean,full,incremental,
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
- full,incremental,
-
-
-
-
-
- org.eclipse.cdt.core.cnature
- org.eclipse.cdt.core.ccnature
- org.eclipse.cdt.managedbuilder.core.managedBuildNature
- org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ CPP_SimpleCommand_Example
+
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.genmakebuilder
+ clean,full,incremental,
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
+ full,incremental,
+
+
+
+
+
+ org.eclipse.cdt.core.cnature
+ org.eclipse.cdt.core.ccnature
+ org.eclipse.cdt.managedbuilder.core.managedBuildNature
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/CPP_SimpleCommand_Example/.settings/language.settings.xml b/CPP_SimpleCommand_Example/.settings/language.settings.xml
index 0bee554..38b9a5d 100644
--- a/CPP_SimpleCommand_Example/.settings/language.settings.xml
+++ b/CPP_SimpleCommand_Example/.settings/language.settings.xml
@@ -1,33 +1,33 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/CPP_SimpleCommand_Example/src/CommandBase.cpp b/CPP_SimpleCommand_Example/src/CommandBase.cpp
index a3dfe3f..5c05ba7 100644
--- a/CPP_SimpleCommand_Example/src/CommandBase.cpp
+++ b/CPP_SimpleCommand_Example/src/CommandBase.cpp
@@ -7,11 +7,11 @@
// Initialize a single static instance of all of your subsystems. The following
// line should be repeated for each subsystem in the project.
std::unique_ptr CommandBase::exampleSubsystem =
- std::make_unique();
+ std::make_unique();
std::unique_ptr CommandBase::oi = std::make_unique();
CommandBase::CommandBase(const std::string &name) :
- frc::Command(name) {
+ frc::Command(name) {
}
diff --git a/CPP_SimpleCommand_Example/src/Commands/ExampleCommand.cpp b/CPP_SimpleCommand_Example/src/Commands/ExampleCommand.cpp
index d8bf1af..526736d 100644
--- a/CPP_SimpleCommand_Example/src/Commands/ExampleCommand.cpp
+++ b/CPP_SimpleCommand_Example/src/Commands/ExampleCommand.cpp
@@ -1,8 +1,8 @@
#include "ExampleCommand.h"
ExampleCommand::ExampleCommand() {
- // Use Requires() here to declare subsystem dependencies
- // eg. Requires(Robot::chassis.get());
+ // Use Requires() here to declare subsystem dependencies
+ // eg. Requires(Robot::chassis.get());
}
// Called just before this Command runs the first time
@@ -13,13 +13,13 @@ void ExampleCommand::Initialize() {
// Called repeatedly when this Command is scheduled to run
void ExampleCommand::Execute() {
- /* [CTRE] Example use for this command, this command will fire in auton. */
- CommandBase::exampleSubsystem.get()->SetOutputOfSomeKind(-0.10);
+ /* [CTRE] Example use for this command, this command will fire in auton. */
+ CommandBase::exampleSubsystem.get()->SetOutputOfSomeKind(-0.10);
}
// Make this return true when this Command no longer needs to run execute()
bool ExampleCommand::IsFinished() {
- return false;
+ return false;
}
// Called once after isFinished returns true
diff --git a/CPP_SimpleCommand_Example/src/OI.cpp b/CPP_SimpleCommand_Example/src/OI.cpp
index f89b13c..41a65e6 100644
--- a/CPP_SimpleCommand_Example/src/OI.cpp
+++ b/CPP_SimpleCommand_Example/src/OI.cpp
@@ -3,5 +3,5 @@
#include
OI::OI() {
- // Process operator interface input here.
+ // Process operator interface input here.
}
diff --git a/CPP_SimpleCommand_Example/src/Robot.cpp b/CPP_SimpleCommand_Example/src/Robot.cpp
index 2f9e9f1..c7f40a6 100644
--- a/CPP_SimpleCommand_Example/src/Robot.cpp
+++ b/CPP_SimpleCommand_Example/src/Robot.cpp
@@ -13,87 +13,87 @@
class Robot: public frc::IterativeRobot {
public:
- void RobotInit() override {
- /* [CTRE] Invoke the late initialization routines for our subsystems */
- CommandBase::exampleSubsystem.get()->InitHardware();
-
- chooser.AddDefault("Default Auto", new ExampleCommand());
- // chooser.AddObject("My Auto", new MyAutoCommand());
- frc::SmartDashboard::PutData("Auto Modes", &chooser);
- }
-
- /**
- * This function is called once each time the robot enters Disabled mode.
- * You can use it to reset any subsystem information you want to clear when
- * the robot is disabled.
- */
- void DisabledInit() override {
-
- }
-
- void DisabledPeriodic() override {
- frc::Scheduler::GetInstance()->Run();
- }
-
- /**
- * 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 code to get the auto name from the text box below the Gyro.
- *
- * You can add additional auto modes by adding additional commands to the
- * chooser code above (like the commented example) or additional comparisons
- * to the if-else structure below with additional strings & commands.
- */
- void AutonomousInit() override {
- /* std::string autoSelected = frc::SmartDashboard::GetString("Auto Selector", "Default");
- if (autoSelected == "My Auto") {
- autonomousCommand.reset(new MyAutoCommand());
- }
- else {
- autonomousCommand.reset(new ExampleCommand());
- } */
-
- autonomousCommand.reset(chooser.GetSelected());
-
- if (autonomousCommand.get() != nullptr) {
- autonomousCommand->Start();
- }
- }
-
- void AutonomousPeriodic() override {
- frc::Scheduler::GetInstance()->Run();
- }
-
- void TeleopInit() override {
- // This makes sure that the autonomous stops running when
- // teleop starts running. If you want the autonomous to
- // continue until interrupted by another command, remove
- // this line or comment it out.
- if (autonomousCommand != nullptr) {
- autonomousCommand->Cancel();
- }
- }
-
- void TeleopPeriodic() override {
- frc::Scheduler::GetInstance()->Run();
-
- /*
- * [CTRE]
- * Subsystem typically are called from commands, but as a simple example
- * set our output to a hardcoded value in teleop loop.
- */
- CommandBase::exampleSubsystem.get()->SetOutputOfSomeKind(+0.10f);
- }
-
- void TestPeriodic() override {
- frc::LiveWindow::GetInstance()->Run();
- }
+ void RobotInit() override {
+ /* [CTRE] Invoke the late initialization routines for our subsystems */
+ CommandBase::exampleSubsystem.get()->InitHardware();
+
+ chooser.AddDefault("Default Auto", new ExampleCommand());
+ // chooser.AddObject("My Auto", new MyAutoCommand());
+ frc::SmartDashboard::PutData("Auto Modes", &chooser);
+ }
+
+ /**
+ * This function is called once each time the robot enters Disabled mode.
+ * You can use it to reset any subsystem information you want to clear when
+ * the robot is disabled.
+ */
+ void DisabledInit() override {
+
+ }
+
+ void DisabledPeriodic() override {
+ frc::Scheduler::GetInstance()->Run();
+ }
+
+ /**
+ * 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 code to get the auto name from the text box below the Gyro.
+ *
+ * You can add additional auto modes by adding additional commands to the
+ * chooser code above (like the commented example) or additional comparisons
+ * to the if-else structure below with additional strings & commands.
+ */
+ void AutonomousInit() override {
+ /* std::string autoSelected = frc::SmartDashboard::GetString("Auto Selector", "Default");
+ if (autoSelected == "My Auto") {
+ autonomousCommand.reset(new MyAutoCommand());
+ }
+ else {
+ autonomousCommand.reset(new ExampleCommand());
+ } */
+
+ autonomousCommand.reset(chooser.GetSelected());
+
+ if (autonomousCommand.get() != nullptr) {
+ autonomousCommand->Start();
+ }
+ }
+
+ void AutonomousPeriodic() override {
+ frc::Scheduler::GetInstance()->Run();
+ }
+
+ void TeleopInit() override {
+ // This makes sure that the autonomous stops running when
+ // teleop starts running. If you want the autonomous to
+ // continue until interrupted by another command, remove
+ // this line or comment it out.
+ if (autonomousCommand != nullptr) {
+ autonomousCommand->Cancel();
+ }
+ }
+
+ void TeleopPeriodic() override {
+ frc::Scheduler::GetInstance()->Run();
+
+ /*
+ * [CTRE]
+ * Subsystem typically are called from commands, but as a simple example
+ * set our output to a hardcoded value in teleop loop.
+ */
+ CommandBase::exampleSubsystem.get()->SetOutputOfSomeKind(+0.10f);
+ }
+
+ void TestPeriodic() override {
+ frc::LiveWindow::GetInstance()->Run();
+ }
private:
- std::unique_ptr autonomousCommand;
- frc::SendableChooser chooser;
+ std::unique_ptr autonomousCommand;
+ frc::SendableChooser chooser;
};
START_ROBOT_CLASS(Robot)
diff --git a/CPP_SimpleCommand_Example/src/Subsystems/ExampleSubsystem.cpp b/CPP_SimpleCommand_Example/src/Subsystems/ExampleSubsystem.cpp
index 637614f..6173a1e 100644
--- a/CPP_SimpleCommand_Example/src/Subsystems/ExampleSubsystem.cpp
+++ b/CPP_SimpleCommand_Example/src/Subsystems/ExampleSubsystem.cpp
@@ -3,12 +3,12 @@
#include "../RobotMap.h"
ExampleSubsystem::ExampleSubsystem() :
- frc::Subsystem("ExampleSubsystem") {
+ frc::Subsystem("ExampleSubsystem") {
}
void ExampleSubsystem::InitDefaultCommand() {
- // Set the default command for a subsystem here.
- // SetDefaultCommand(new MySpecialCommand());
+ // Set the default command for a subsystem here.
+ // SetDefaultCommand(new MySpecialCommand());
}
// Put methods for controlling this subsystem
@@ -23,7 +23,7 @@ void ExampleSubsystem::InitDefaultCommand() {
*/
void ExampleSubsystem::InitHardware()
{
- _talon = new CANTalon(MY_TALON_SRX_DEVICEID);
+ _talon = new CANTalon(MY_TALON_SRX_DEVICEID);
}
/**
* [CTRE]
@@ -31,9 +31,9 @@ void ExampleSubsystem::InitHardware()
*/
void ExampleSubsystem::SetOutputOfSomeKind(double output)
{
- // additionally could null check _talon if need be.
- // for example: if(_talon == 0) { return; }
- _talon->Set(output);
+ // additionally could null check _talon if need be.
+ // for example: if(_talon == 0) { return; }
+ _talon->Set(output);
}
diff --git a/CPP_VelocityClosedLoop/.cproject b/CPP_VelocityClosedLoop/.cproject
index 50d36c6..06cc131 100644
--- a/CPP_VelocityClosedLoop/.cproject
+++ b/CPP_VelocityClosedLoop/.cproject
@@ -1,288 +1,288 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/CPP_VelocityClosedLoop/.project b/CPP_VelocityClosedLoop/.project
index 1949e0e..3a9c5d5 100644
--- a/CPP_VelocityClosedLoop/.project
+++ b/CPP_VelocityClosedLoop/.project
@@ -1,28 +1,28 @@
- CPP_VelocityClosedLoop
-
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.genmakebuilder
- clean,full,incremental,
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
- full,incremental,
-
-
-
-
-
- org.eclipse.cdt.core.cnature
- org.eclipse.cdt.core.ccnature
- org.eclipse.cdt.managedbuilder.core.managedBuildNature
- org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ CPP_VelocityClosedLoop
+
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.genmakebuilder
+ clean,full,incremental,
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
+ full,incremental,
+
+
+
+
+
+ org.eclipse.cdt.core.cnature
+ org.eclipse.cdt.core.ccnature
+ org.eclipse.cdt.managedbuilder.core.managedBuildNature
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/CPP_VelocityClosedLoop/.settings/language.settings.xml b/CPP_VelocityClosedLoop/.settings/language.settings.xml
index 5ce6124..d972b6b 100644
--- a/CPP_VelocityClosedLoop/.settings/language.settings.xml
+++ b/CPP_VelocityClosedLoop/.settings/language.settings.xml
@@ -1,33 +1,33 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/CPP_VelocityClosedLoop/src/Robot.cpp b/CPP_VelocityClosedLoop/src/Robot.cpp
index c052688..9b285b3 100644
--- a/CPP_VelocityClosedLoop/src/Robot.cpp
+++ b/CPP_VelocityClosedLoop/src/Robot.cpp
@@ -20,64 +20,64 @@
class Robot: public IterativeRobot {
private:
- CANTalon * _talon = new CANTalon(0);
- Joystick * _joy = new Joystick(0);
- std::string _sb;
- int _loops = 0;
+ CANTalon * _talon = new CANTalon(0);
+ Joystick * _joy = new Joystick(0);
+ std::string _sb;
+ int _loops = 0;
- void RobotInit() {
+ void RobotInit() {
/* first choose the sensor */
- _talon->SetFeedbackDevice(CANTalon::CtreMagEncoder_Relative);
- _talon->SetSensorDirection(false);
- //_talon->ConfigEncoderCodesPerRev(XXX), // if using FeedbackDevice.QuadEncoder
- //_talon->ConfigPotentiometerTurns(XXX), // if using FeedbackDevice.AnalogEncoder or AnalogPot
+ _talon->SetFeedbackDevice(CANTalon::CtreMagEncoder_Relative);
+ _talon->SetSensorDirection(false);
+ //_talon->ConfigEncoderCodesPerRev(XXX), // if using FeedbackDevice.QuadEncoder
+ //_talon->ConfigPotentiometerTurns(XXX), // if using FeedbackDevice.AnalogEncoder or AnalogPot
- /* set the peak and nominal outputs, 12V means full */
- _talon->ConfigNominalOutputVoltage(+0.0f, -0.0f);
- _talon->ConfigPeakOutputVoltage(+12.0f, -12.0f);
- /* set closed loop gains in slot0 */
- _talon->SelectProfileSlot(0);
- _talon->SetF(0.1097);
- _talon->SetP(0.22);
- _talon->SetI(0.0);
- _talon->SetD(0.0);
- }
- /**
- * This function is called periodically during operator control
- */
- void TeleopPeriodic() {
- /* get gamepad axis */
- double leftYstick = _joy->GetAxis(Joystick::kYAxis);
- double motorOutput = _talon->GetOutputVoltage() / _talon->GetBusVoltage();
- /* prepare line to print */
- _sb.append("\tout:");
- _sb.append(std::to_string(motorOutput));
- _sb.append("\tspd:");
- _sb.append(std::to_string(_talon->GetSpeed()));
- /* while button1 is held down, closed-loop on target velocity */
- if (_joy->GetRawButton(1)) {
- /* Speed mode */
- double targetSpeed = leftYstick * 1500.0; /* 1500 RPM in either direction */
- _talon->SetControlMode(CANSpeedController::kSpeed);
- _talon->Set(targetSpeed); /* 1500 RPM in either direction */
+ /* set the peak and nominal outputs, 12V means full */
+ _talon->ConfigNominalOutputVoltage(+0.0f, -0.0f);
+ _talon->ConfigPeakOutputVoltage(+12.0f, -12.0f);
+ /* set closed loop gains in slot0 */
+ _talon->SelectProfileSlot(0);
+ _talon->SetF(0.1097);
+ _talon->SetP(0.22);
+ _talon->SetI(0.0);
+ _talon->SetD(0.0);
+ }
+ /**
+ * This function is called periodically during operator control
+ */
+ void TeleopPeriodic() {
+ /* get gamepad axis */
+ double leftYstick = _joy->GetAxis(Joystick::kYAxis);
+ double motorOutput = _talon->GetOutputVoltage() / _talon->GetBusVoltage();
+ /* prepare line to print */
+ _sb.append("\tout:");
+ _sb.append(std::to_string(motorOutput));
+ _sb.append("\tspd:");
+ _sb.append(std::to_string(_talon->GetSpeed()));
+ /* while button1 is held down, closed-loop on target velocity */
+ if (_joy->GetRawButton(1)) {
+ /* Speed mode */
+ double targetSpeed = leftYstick * 1500.0; /* 1500 RPM in either direction */
+ _talon->SetControlMode(CANSpeedController::kSpeed);
+ _talon->Set(targetSpeed); /* 1500 RPM in either direction */
- /* append more signals to print when in speed mode. */
- _sb.append("\terrNative:");
- _sb.append(std::to_string(_talon->GetClosedLoopError()));
- _sb.append("\ttrg:");
- _sb.append(std::to_string(targetSpeed));
+ /* append more signals to print when in speed mode. */
+ _sb.append("\terrNative:");
+ _sb.append(std::to_string(_talon->GetClosedLoopError()));
+ _sb.append("\ttrg:");
+ _sb.append(std::to_string(targetSpeed));
} else {
- /* Percent voltage mode */
- _talon->SetControlMode(CANSpeedController::kPercentVbus);
- _talon->Set(leftYstick);
- }
- /* print every ten loops, printing too much too fast is generally bad for performance */
- if (++_loops >= 10) {
- _loops = 0;
- printf("%s\n",_sb.c_str());
- }
- _sb.clear();
- }
+ /* Percent voltage mode */
+ _talon->SetControlMode(CANSpeedController::kPercentVbus);
+ _talon->Set(leftYstick);
+ }
+ /* print every ten loops, printing too much too fast is generally bad for performance */
+ if (++_loops >= 10) {
+ _loops = 0;
+ printf("%s\n",_sb.c_str());
+ }
+ _sb.clear();
+ }
};
START_ROBOT_CLASS(Robot)
diff --git a/JAVA_BrakeCoastSwitching/.classpath b/JAVA_BrakeCoastSwitching/.classpath
index 9e787aa..dea58b7 100644
--- a/JAVA_BrakeCoastSwitching/.classpath
+++ b/JAVA_BrakeCoastSwitching/.classpath
@@ -1,11 +1,11 @@
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
diff --git a/JAVA_BrakeCoastSwitching/.project b/JAVA_BrakeCoastSwitching/.project
index 59c75ec..91b0c81 100644
--- a/JAVA_BrakeCoastSwitching/.project
+++ b/JAVA_BrakeCoastSwitching/.project
@@ -1,18 +1,18 @@
- JAVA_BrakeCoastSwitching
-
-
-
-
-
- org.eclipse.jdt.core.javabuilder
-
-
-
-
-
- org.eclipse.jdt.core.javanature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ JAVA_BrakeCoastSwitching
+
+
+
+
+
+ org.eclipse.jdt.core.javabuilder
+
+
+
+
+
+ org.eclipse.jdt.core.javanature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/JAVA_BrakeCoastSwitching/src/org/usfirst/frc/team469/robot/Robot.java b/JAVA_BrakeCoastSwitching/src/org/usfirst/frc/team469/robot/Robot.java
index d19fdb2..8d9decb 100644
--- a/JAVA_BrakeCoastSwitching/src/org/usfirst/frc/team469/robot/Robot.java
+++ b/JAVA_BrakeCoastSwitching/src/org/usfirst/frc/team469/robot/Robot.java
@@ -1,44 +1,44 @@
-package org.usfirst.frc.team469.robot;
-import com.ctre.CANTalon;
-import edu.wpi.first.wpilibj.IterativeRobot;
-import edu.wpi.first.wpilibj.Joystick;
+package org.usfirs .frc. eam469.robo ;
+impor com.c re.CANTalon;
+impor edu.wpi.firs .wpilibj.I era iveRobo ;
+impor edu.wpi.firs .wpilibj.Joys ick;
-public class Robot extends IterativeRobot {
- /** our test talon */
- CANTalon _tal = new CANTalon(0);
- /* our test gamepad */
- Joystick _joy = new Joystick(0);
- /** save buttons each loop */
- boolean [] _btnsLast = {false,false,false,false,false,false,false,false,false,false};
- /** desired brake mode, init value assigned here */
- boolean _brake = true;
- /** c'tor Select the brake mode to start with. */
- public Robot() {
- _tal.enableBrakeMode(_brake); /* override brake setting programmatically */
- System.out.println("brake:" + _brake); /* instrument to console */
- }
- /** Every loop, flip brake mode if button1 when is pressed. */
- public void commonloop() {
- /* get buttons */
- boolean [] btns= new boolean [_btnsLast.length];
- for(int i=1;i<_btnsLast.length;++i)
- btns[i] = _joy.getRawButton(i);
-
- /* flip brake when btn1 is pressed */
- if(btns[1] && !_btnsLast[1]) {
- _brake = !_brake;
- _tal.enableBrakeMode(_brake); /* override brake setting programmatically */
- System.out.println("brake:" + _brake); /* instrument to console */
- }
-
- /* save buttons states for on-press detection */
- for(int i=1;i<10;++i)
- _btnsLast[i] = btns[i];
+public class Robo ex ends I era iveRobo {
+ /** our es alon */
+ CANTalon _ al = new CANTalon(0);
+ /* our es gamepad */
+ Joys ick _joy = new Joys ick(0);
+ /** save bu ons each loop */
+ boolean [] _b nsLas = {false,false,false,false,false,false,false,false,false,false};
+ /** desired brake mode, ini value assigned here */
+ boolean _brake = rue;
+ /** c' or Selec he brake mode o s ar wi h. */
+ public Robo () {
+ _ al.enableBrakeMode(_brake); /* override brake se ing programma ically */
+ Sys em.ou .prin ln("brake:" + _brake); /* ins rumen o console */
+ }
+ /** Every loop, flip brake mode if bu on1 when is pressed. */
+ public void commonloop() {
+ /* ge bu ons */
+ boolean [] b ns= new boolean [_b nsLas .leng h];
+ for(in i=1;i<_b nsLas .leng h;++i)
+ b ns[i] = _joy.ge RawBu on(i);
+
+ /* flip brake when b n1 is pressed */
+ if(b ns[1] && !_b nsLas [1]) {
+ _brake = !_brake;
+ _ al.enableBrakeMode(_brake); /* override brake se ing programma ically */
+ Sys em.ou .prin ln("brake:" + _brake); /* ins rumen o console */
+ }
+
+ /* save bu ons s a es for on-press de ec ion */
+ for(in i=1;i<10;++i)
+ _b nsLas [i] = b ns[i];
+ }
+ public void disabledPeriodic() {
+ commonloop(); /* jus call a "common" loop */
+ }
+ public void eleopPeriodic() {
+ commonloop(); /* jus call a "common" loop */
}
- public void disabledPeriodic() {
- commonloop(); /* just call a "common" loop */
- }
- public void teleopPeriodic() {
- commonloop(); /* just call a "common" loop */
- }
}
diff --git a/JAVA_CtreMagEncoder_SmartDash/.classpath b/JAVA_CtreMagEncoder_SmartDash/.classpath
index 616c997..fd17558 100644
--- a/JAVA_CtreMagEncoder_SmartDash/.classpath
+++ b/JAVA_CtreMagEncoder_SmartDash/.classpath
@@ -1,11 +1,11 @@
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
diff --git a/JAVA_CtreMagEncoder_SmartDash/.project b/JAVA_CtreMagEncoder_SmartDash/.project
index 2a179d8..2026820 100644
--- a/JAVA_CtreMagEncoder_SmartDash/.project
+++ b/JAVA_CtreMagEncoder_SmartDash/.project
@@ -1,18 +1,18 @@
- JAVA_CTREMagEncoder_SmartDash
-
-
-
-
-
- org.eclipse.jdt.core.javabuilder
-
-
-
-
-
- org.eclipse.jdt.core.javanature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ JAVA_CTREMagEncoder_SmartDash
+
+
+
+
+
+ org.eclipse.jdt.core.javabuilder
+
+
+
+
+
+ org.eclipse.jdt.core.javanature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/JAVA_CtreMagEncoder_SmartDash/src/org/usfirst/frc/team3539/robot/Robot.java b/JAVA_CtreMagEncoder_SmartDash/src/org/usfirst/frc/team3539/robot/Robot.java
index 3393509..9466788 100644
--- a/JAVA_CtreMagEncoder_SmartDash/src/org/usfirst/frc/team3539/robot/Robot.java
+++ b/JAVA_CtreMagEncoder_SmartDash/src/org/usfirst/frc/team3539/robot/Robot.java
@@ -1,99 +1,99 @@
/**
- * @brief A quick example on higher resolution plotting a sensor for testing.
+ * @brief A quick example on higher resolu ion plo ing a sensor for es ing.
*
- * Simple example for plotting sensor
- * Sensor is a CTRE Magnetic Encoder plugged into a Talon SRX via Gadgeteer Ribbon Cable.
- * Robot should be propped up on blocks so that the wheels spin free (if testing a drive train sensor).
+ * Simple example for plo ing sensor
+ * Sensor is a CTRE Magne ic Encoder plugged in o a Talon SRX via Gadge eer Ribbon Cable.
+ * Robo should be propped up on blocks so ha he wheels spin free (if es ing a drive rain sensor).
*
* Talon SRX ...
- * http://www.ctr-electronics.com/talon-srx.html
- * Magnetic Encoder...
- * http://www.ctr-electronics.com/srx-magnetic-encoder.html
+ * h p://www.c r-elec ronics.com/ alon-srx.h ml
+ * Magne ic Encoder...
+ * h p://www.c r-elec ronics.com/srx-magne ic-encoder.h ml
* Cables...
- * http://www.ctr-electronics.com/talon-srx-data-cable-4-pack.html#product_tabs_related_tabbed
- * http://www.ctr-electronics.com/talon-srx-data-cable-kit-new-product.html
+ * h p://www.c r-elec ronics.com/ alon-srx-da a-cable-4-pack.h ml#produc _ abs_rela ed_ abbed
+ * h p://www.c r-elec ronics.com/ alon-srx-da a-cable-ki -new-produc .h ml
*
- * SmartDashboard (SD) setup.
- * [1] Open Smartdashboard (I typically (re)select the Dashboard Type in DriverStation if the SD doesn't pop up).
- * [2] Deploy software and enable.
- * [3] Find the text entry in the SD for "spd".
- * [4] View =>Editable should be checked.
- * [5] Right-click on "spd" label and "Change to..." the Line Plot.
+ * Smar Dashboard (SD) se up.
+ * [1] Open Smar dashboard (I ypically (re)selec he Dashboard Type in DriverS a ion if he SD doesn' pop up).
+ * [2] Deploy sof ware and enable.
+ * [3] Find he ex en ry in he SD for "spd".
+ * [4] View =>Edi able should be checked.
+ * [5] Righ -click on "spd" label and "Change o..." he Line Plo .
*
- * A few details regarding Smartdashboard in general...
- * [1] Constant data does not render new plot points. So if the signal being measured doesn't change value, the plot stops.
- * Once the signal changes again the plot resumes but the time gap between is truncated in the plot.
- * [2] Changing the window of samples is done by View=>Editable=>Check, then right click-properties on the plot.
- * Then change "Buffer Size" in the popup. I find myself changing this often as I learn more about the signal I am viewing.
- * [3] Zoom features will cause the plot to stop updating and I haven't found a quick way to get the plot to resume plotting. So
- * I've been avoiding Zoom-In/Zoom-Out for now.
- * [4] Right-click properties on the plot does different things depending on if View=>Editable is checked.
+ * A few de ails regarding Smar dashboard in general...
+ * [1] Cons an da a does no render new plo poin s. So if he signal being measured doesn' change value, he plo s ops.
+ * Once he signal changes again he plo resumes bu he ime gap be ween is runca ed in he plo .
+ * [2] Changing he window of samples is done by View=>Edi able=>Check, hen righ click-proper ies on he plo .
+ * Then change "Buffer Size" in he popup. I find myself changing his of en as I learn more abou he signal I am viewing.
+ * [3] Zoom fea ures will cause he plo o s op upda ing and I haven' found a quick way o ge he plo o resume plo ing. So
+ * I've been avoiding Zoom-In/Zoom-Ou for now.
+ * [4] Righ -click proper ies on he plo does differen hings depending on if View=>Edi able is checked.
*
- * @author Ozrien
+ * @au hor Ozrien
*/
-package org.usfirst.frc.team3539.robot; // bulldogs!
+package org.usfirs .frc. eam3539.robo ; // bulldogs!
-import com.ctre.CANTalon;
-import com.ctre.CANTalon.FeedbackDevice;
-import com.ctre.CANTalon.StatusFrameRate;
-import com.ctre.CANTalon.TalonControlMode;
-import edu.wpi.first.wpilibj.IterativeRobot;
-import edu.wpi.first.wpilibj.networktables.NetworkTable;
-import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+impor com.c re.CANTalon;
+impor com.c re.CANTalon.FeedbackDevice;
+impor com.c re.CANTalon.S a usFrameRa e;
+impor com.c re.CANTalon.TalonCon rolMode;
+impor edu.wpi.firs .wpilibj.I era iveRobo ;
+impor edu.wpi.firs .wpilibj.ne work ables.Ne workTable;
+impor edu.wpi.firs .wpilibj.smar dashboard.Smar Dashboard;
-public class Robot extends IterativeRobot {
-
- CANTalon _tal1 = new CANTalon(1); //!< Just a follower
- CANTalon _tal3 = new CANTalon(3);
- PlotThread _plotThread;
-
- public void teleopInit() {
- /* Tal1 will follow Tal3 */
- _tal1.changeControlMode(TalonControlMode.Follower);
- _tal1.set(3);
-
- /* new frame every 1ms, since this is a test project use up as
- * much bandwidth as possible for the purpose of this test. */
- _tal3.setStatusFrameRateMs(StatusFrameRate.Feedback, 1);
- _tal3.setFeedbackDevice(FeedbackDevice.CtreMagEncoder_Relative);
-
- /* fire the plotter */
- _plotThread = new PlotThread(this);
- new Thread(_plotThread).start();
- }
+public class Robo ex ends I era iveRobo {
+
+ CANTalon _ al1 = new CANTalon(1); //!< Jus a follower
+ CANTalon _ al3 = new CANTalon(3);
+ Plo Thread _plo Thread;
+
+ public void eleopIni () {
+ /* Tal1 will follow Tal3 */
+ _ al1.changeCon rolMode(TalonCon rolMode.Follower);
+ _ al1.se (3);
+
+ /* new frame every 1ms, since his is a es projec use up as
+ * much bandwid h as possible for he purpose of his es . */
+ _ al3.se S a usFrameRa eMs(S a usFrameRa e.Feedback, 1);
+ _ al3.se FeedbackDevice(FeedbackDevice.C reMagEncoder_Rela ive);
+
+ /* fire he plo er */
+ _plo Thread = new Plo Thread( his);
+ new Thread(_plo Thread).s ar ();
+ }
- public void teleopPeriodic() {
- /* Shooting for ~200RPM, which is ~300ms per rotation.
- *
- * If there is mechanical deflection, eccentricity, or damage in the sensor
- * it should be revealed in the plot.
- *
- * For example, an optical encoder with a partially damaged ring will reveal a
- * periodic dip in the sensed velocity synchronous with each rotation.
- *
- * This can also be wired to a gamepad to test velocity sweeping.
- * */
- _tal3.set(0.4);
- }
-
- /** quick and dirty threaded plotter */
- class PlotThread implements Runnable {
- Robot robot;
- public PlotThread(Robot robot) { this.robot = robot; }
+ public void eleopPeriodic() {
+ /* Shoo ing for ~200RPM, which is ~300ms per ro a ion.
+ *
+ * If here is mechanical deflec ion, eccen rici y, or damage in he sensor
+ * i should be revealed in he plo .
+ *
+ * For example, an op ical encoder wi h a par ially damaged ring will reveal a
+ * periodic dip in he sensed veloci y synchronous wi h each ro a ion.
+ *
+ * This can also be wired o a gamepad o es veloci y sweeping.
+ * */
+ _ al3.se (0.4);
+ }
+
+ /** quick and dir y hreaded plo er */
+ class Plo Thread implemen s Runnable {
+ Robo robo ;
+ public Plo Thread(Robo robo ) { his.robo = robo ; }
- public void run() {
- /* speed up network tables, this is a test project so eat up all
- * of the network possible for the purpose of this test.
- */
- NetworkTable.setUpdateRate(0.010); /* this suggests each time unit is 10ms in the plot */
- while (true) {
- /* yield for a ms or so - this is not meant to be accurate */
- try { Thread.sleep(1); } catch (Exception e) { }
- /* grab the last signal update from our 1ms frame update */
- double speed = this.robot._tal3.getSpeed();
- SmartDashboard.putNumber("spd", speed);
- }
- }
- }
+ public void run() {
+ /* speed up ne work ables, his is a es projec so ea up all
+ * of he ne work possible for he purpose of his es .
+ */
+ Ne workTable.se Upda eRa e(0.010); /* his sugges s each ime uni is 10ms in he plo */
+ while ( rue) {
+ /* yield for a ms or so - his is no mean o be accura e */
+ ry { Thread.sleep(1); } ca ch (Excep ion e) { }
+ /* grab he las signal upda e from our 1ms frame upda e */
+ double speed = his.robo ._ al3.ge Speed();
+ Smar Dashboard.pu Number("spd", speed);
+ }
+ }
+ }
}
diff --git a/JAVA_MotionMagicExample/.classpath b/JAVA_MotionMagicExample/.classpath
index 616c997..fd17558 100644
--- a/JAVA_MotionMagicExample/.classpath
+++ b/JAVA_MotionMagicExample/.classpath
@@ -1,11 +1,11 @@
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
diff --git a/JAVA_MotionMagicExample/.project b/JAVA_MotionMagicExample/.project
index b4a091b..abc3bb0 100644
--- a/JAVA_MotionMagicExample/.project
+++ b/JAVA_MotionMagicExample/.project
@@ -1,18 +1,18 @@
- JAVA_MotionMagicExample
-
-
-
-
-
- org.eclipse.jdt.core.javabuilder
-
-
-
-
-
- org.eclipse.jdt.core.javanature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ JAVA_MotionMagicExample
+
+
+
+
+
+ org.eclipse.jdt.core.javabuilder
+
+
+
+
+
+ org.eclipse.jdt.core.javanature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/JAVA_MotionMagicExample/src/org/usfirst/frc/team217/robot/Instrum.java b/JAVA_MotionMagicExample/src/org/usfirst/frc/team217/robot/Instrum.java
index 06f6059..f8f992a 100644
--- a/JAVA_MotionMagicExample/src/org/usfirst/frc/team217/robot/Instrum.java
+++ b/JAVA_MotionMagicExample/src/org/usfirst/frc/team217/robot/Instrum.java
@@ -1,30 +1,30 @@
-package org.usfirst.frc.team217.robot;
-import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
-import com.ctre.CANTalon;
-import com.ctre.CANTalon.TalonControlMode;
+package org.usfirs .frc. eam217.robo ;
+impor edu.wpi.firs .wpilibj.smar dashboard.Smar Dashboard;
+impor com.c re.CANTalon;
+impor com.c re.CANTalon.TalonCon rolMode;
-public class Instrum {
+public class Ins rum {
- private static int _loops = 0;
-
- public static void Process(CANTalon tal, StringBuilder sb)
- {
- /* smart dash plots */
- SmartDashboard.putNumber("RPM", tal.getSpeed());
- SmartDashboard.putNumber("Pos", tal.getPosition());
- SmartDashboard.putNumber("AppliedThrottle", (tal.getOutputVoltage()/tal.getBusVoltage())*1023);
- SmartDashboard.putNumber("ClosedLoopError", tal.getClosedLoopError());
- if (tal.getControlMode() == TalonControlMode.MotionMagic) {
- //These API calls will be added in our next release.
- //SmartDashboard.putNumber("ActTrajVelocity", tal.getMotionMagicActTrajVelocity());
- //SmartDashboard.putNumber("ActTrajPosition", tal.getMotionMagicActTrajPosition());
- }
- /* periodically print to console */
+ priva e s a ic in _loops = 0;
+
+ public s a ic void Process(CANTalon al, S ringBuilder sb)
+ {
+ /* smar dash plo s */
+ Smar Dashboard.pu Number("RPM", al.ge Speed());
+ Smar Dashboard.pu Number("Pos", al.ge Posi ion());
+ Smar Dashboard.pu Number("AppliedThro le", ( al.ge Ou pu Vol age()/ al.ge BusVol age())*1023);
+ Smar Dashboard.pu Number("ClosedLoopError", al.ge ClosedLoopError());
+ if ( al.ge Con rolMode() == TalonCon rolMode.Mo ionMagic) {
+ //These API calls will be added in our nex release.
+ //Smar Dashboard.pu Number("Ac TrajVeloci y", al.ge Mo ionMagicAc TrajVeloci y());
+ //Smar Dashboard.pu Number("Ac TrajPosi ion", al.ge Mo ionMagicAc TrajPosi ion());
+ }
+ /* periodically prin o console */
if(++_loops >= 10) {
- _loops = 0;
- System.out.println(sb.toString());
+ _loops = 0;
+ Sys em.ou .prin ln(sb. oS ring());
}
/* clear line cache */
- sb.setLength(0);
- }
+ sb.se Leng h(0);
+ }
}
diff --git a/JAVA_MotionMagicExample/src/org/usfirst/frc/team217/robot/Robot.java b/JAVA_MotionMagicExample/src/org/usfirst/frc/team217/robot/Robot.java
index 30695cc..30e70b0 100644
--- a/JAVA_MotionMagicExample/src/org/usfirst/frc/team217/robot/Robot.java
+++ b/JAVA_MotionMagicExample/src/org/usfirst/frc/team217/robot/Robot.java
@@ -1,91 +1,91 @@
/**
- * Example demonstrating the motion magic control mode.
- * Tested with Logitech F710 USB Gamepad inserted into Driver Station.
+ * Example demons ra ing he mo ion magic con rol mode.
+ * Tes ed wi h Logi ech F710 USB Gamepad inser ed in o Driver S a ion.
*
- * Be sure to select the correct feedback sensor using SetFeedbackDevice() below.
+ * Be sure o selec he correc feedback sensor using Se FeedbackDevice() below.
*
- * After deploying/debugging this to your RIO, first use the left Y-stick
- * to throttle the Talon manually. This will confirm your hardware setup/sensors
- * and will allow you to take initial measurements.
+ * Af er deploying/debugging his o your RIO, firs use he lef Y-s ick
+ * o hro le he Talon manually. This will confirm your hardware se up/sensors
+ * and will allow you o ake ini ial measuremen s.
*
- * Be sure to confirm that when the Talon is driving forward (green) the
- * position sensor is moving in a positive direction. If this is not the
- * cause, flip the boolean input to the reverseSensor() call below.
+ * Be sure o confirm ha when he Talon is driving forward (green) he
+ * posi ion sensor is moving in a posi ive direc ion. If his is no he
+ * cause, flip he boolean inpu o he reverseSensor() call below.
*
- * Once you've ensured your feedback device is in-phase with the motor,
- * and followed the walk-through in the Talon SRX Software Reference Manual,
- * use button1 to motion-magic servo to target position specified by the gamepad stick.
+ * Once you've ensured your feedback device is in-phase wi h he mo or,
+ * and followed he walk- hrough in he Talon SRX Sof ware Reference Manual,
+ * use bu on1 o mo ion-magic servo o arge posi ion specified by he gamepad s ick.
*/
-package org.usfirst.frc.team217.robot;
+package org.usfirs .frc. eam217.robo ;
-import edu.wpi.first.wpilibj.IterativeRobot;
-import edu.wpi.first.wpilibj.Joystick;
-import edu.wpi.first.wpilibj.Joystick.*;
-import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
-import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
-import com.ctre.CANTalon;
-import com.ctre.CANTalon.*;
+impor edu.wpi.firs .wpilibj.I era iveRobo ;
+impor edu.wpi.firs .wpilibj.Joys ick;
+impor edu.wpi.firs .wpilibj.Joys ick.*;
+impor edu.wpi.firs .wpilibj.smar dashboard.SendableChooser;
+impor edu.wpi.firs .wpilibj.smar dashboard.Smar Dashboard;
+impor com.c re.CANTalon;
+impor com.c re.CANTalon.*;
-public class Robot extends IterativeRobot {
- CANTalon _talon = new CANTalon(3);
- Joystick _joy = new Joystick(0);
- StringBuilder _sb = new StringBuilder();
+public class Robo ex ends I era iveRobo {
+ CANTalon _ alon = new CANTalon(3);
+ Joys ick _joy = new Joys ick(0);
+ S ringBuilder _sb = new S ringBuilder();
- public void robotInit() {
- /* first choose the sensor */
- _talon.setFeedbackDevice(FeedbackDevice.CtreMagEncoder_Relative);
- _talon.reverseSensor(true);
- // _talon.configEncoderCodesPerRev(XXX), // if using
- // FeedbackDevice.QuadEncoder
- // _talon.configPotentiometerTurns(XXX), // if using
- // FeedbackDevice.AnalogEncoder or AnalogPot
+ public void robo Ini () {
+ /* firs choose he sensor */
+ _ alon.se FeedbackDevice(FeedbackDevice.C reMagEncoder_Rela ive);
+ _ alon.reverseSensor( rue);
+ // _ alon.configEncoderCodesPerRev(XXX), // if using
+ // FeedbackDevice.QuadEncoder
+ // _ alon.configPo en iome erTurns(XXX), // if using
+ // FeedbackDevice.AnalogEncoder or AnalogPo
- /* set the peak and nominal outputs, 12V means full */
- _talon.configNominalOutputVoltage(+0.0f, -0.0f);
- _talon.configPeakOutputVoltage(+12.0f, -12.0f);
- /* set closed loop gains in slot0 - see documentation */
- _talon.setProfile(0);
- _talon.setF(0);
- _talon.setP(0);
- _talon.setI(0);
- _talon.setD(0);
- /* set acceleration and vcruise velocity - see documentation */
- _talon.setMotionMagicCruiseVelocity(0);
- _talon.setMotionMagicAcceleration(0);
- }
+ /* se he peak and nominal ou pu s, 12V means full */
+ _ alon.configNominalOu pu Vol age(+0.0f, -0.0f);
+ _ alon.configPeakOu pu Vol age(+12.0f, -12.0f);
+ /* se closed loop gains in slo 0 - see documen a ion */
+ _ alon.se Profile(0);
+ _ alon.se F(0);
+ _ alon.se P(0);
+ _ alon.se I(0);
+ _ alon.se D(0);
+ /* se accelera ion and vcruise veloci y - see documen a ion */
+ _ alon.se Mo ionMagicCruiseVeloci y(0);
+ _ alon.se Mo ionMagicAccelera ion(0);
+ }
- /**
- * This function is called periodically during operator control
- */
- public void teleopPeriodic() {
- /* get gamepad axis - forward stick is positive */
- double leftYstick = -1.0 * _joy.getAxis(AxisType.kY);
- /* calculate the percent motor output */
- double motorOutput = _talon.getOutputVoltage() / _talon.getBusVoltage();
- /* prepare line to print */
- _sb.append("\tout:");
- _sb.append(motorOutput);
- _sb.append("\tspd:");
- _sb.append(_talon.getSpeed());
+ /**
+ * This func ion is called periodically during opera or con rol
+ */
+ public void eleopPeriodic() {
+ /* ge gamepad axis - forward s ick is posi ive */
+ double lef Ys ick = -1.0 * _joy.ge Axis(AxisType.kY);
+ /* calcula e he percen mo or ou pu */
+ double mo orOu pu = _ alon.ge Ou pu Vol age() / _ alon.ge BusVol age();
+ /* prepare line o prin */
+ _sb.append("\ ou :");
+ _sb.append(mo orOu pu );
+ _sb.append("\ spd:");
+ _sb.append(_ alon.ge Speed());
- if (_joy.getRawButton(1)) {
- /* Motion Magic */
- double targetPos = leftYstick
- * 10.0; /* 10 Rotations in either direction */
- _talon.changeControlMode(TalonControlMode.MotionMagic);
- _talon.set(targetPos);
+ if (_joy.ge RawBu on(1)) {
+ /* Mo ion Magic */
+ double arge Pos = lef Ys ick
+ * 10.0; /* 10 Ro a ions in ei her direc ion */
+ _ alon.changeCon rolMode(TalonCon rolMode.Mo ionMagic);
+ _ alon.se ( arge Pos);
- /* append more signals to print when in speed mode. */
- _sb.append("\terr:");
- _sb.append(_talon.getClosedLoopError());
- _sb.append("\ttrg:");
- _sb.append(targetPos);
- } else {
- /* Percent voltage mode */
- _talon.changeControlMode(TalonControlMode.PercentVbus);
- _talon.set(leftYstick);
- }
- /* instrumentation */
- Instrum.Process(_talon, _sb);
- }
+ /* append more signals o prin when in speed mode. */
+ _sb.append("\ err:");
+ _sb.append(_ alon.ge ClosedLoopError());
+ _sb.append("\ rg:");
+ _sb.append( arge Pos);
+ } else {
+ /* Percen vol age mode */
+ _ alon.changeCon rolMode(TalonCon rolMode.Percen Vbus);
+ _ alon.se (lef Ys ick);
+ }
+ /* ins rumen a ion */
+ Ins rum.Process(_ alon, _sb);
+ }
}
diff --git a/JAVA_MotionProfileExample/.classpath b/JAVA_MotionProfileExample/.classpath
index 8e0a2e6..bbb3a94 100644
--- a/JAVA_MotionProfileExample/.classpath
+++ b/JAVA_MotionProfileExample/.classpath
@@ -1,11 +1,11 @@
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
diff --git a/JAVA_MotionProfileExample/.project b/JAVA_MotionProfileExample/.project
index 93ce4df..bf0f391 100644
--- a/JAVA_MotionProfileExample/.project
+++ b/JAVA_MotionProfileExample/.project
@@ -1,18 +1,18 @@
- JAVA_MotionProfileExample
-
-
-
-
-
- org.eclipse.jdt.core.javabuilder
-
-
-
-
-
- org.eclipse.jdt.core.javanature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ JAVA_MotionProfileExample
+
+
+
+
+
+ org.eclipse.jdt.core.javabuilder
+
+
+
+
+
+ org.eclipse.jdt.core.javanature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/JAVA_MotionProfileExample/src/org/usfirst/frc/team3539/robot/GeneratedMotionProfile.java b/JAVA_MotionProfileExample/src/org/usfirst/frc/team3539/robot/GeneratedMotionProfile.java
index ae4a26e..daa1d98 100644
--- a/JAVA_MotionProfileExample/src/org/usfirst/frc/team3539/robot/GeneratedMotionProfile.java
+++ b/JAVA_MotionProfileExample/src/org/usfirst/frc/team3539/robot/GeneratedMotionProfile.java
@@ -1,410 +1,410 @@
-
-package org.usfirst.frc.team3539.robot;
-public class GeneratedMotionProfile {
- public static final int kNumPoints =185;
- // Position (rotations) Velocity (RPM) Duration (ms)
- public static double [][]Points = new double[][]{
- {0, 0 ,10},
- {0.00004761904762, 0.5714285714 ,10},
- {0.0002142857143, 1.428571429 ,10},
- {0.0005476190476, 2.571428571 ,10},
- {0.001095238095, 4 ,10},
- {0.001904761905, 5.714285714 ,10},
- {0.003023809524, 7.714285714 ,10},
- {0.0045, 10 ,10},
- {0.006380952381, 12.57142857 ,10},
- {0.008714285714, 15.42857143 ,10},
- {0.01154761905, 18.57142857 ,10},
- {0.01492857143, 22 ,10},
- {0.0189047619, 25.71428571 ,10},
- {0.02352380952, 29.71428571 ,10},
- {0.02883333333, 34 ,10},
- {0.03488095238, 38.57142857 ,10},
- {0.04171428571, 43.42857143 ,10},
- {0.04938095238, 48.57142857 ,10},
- {0.05792857143, 54 ,10},
- {0.0674047619, 59.71428571 ,10},
- {0.07785714286, 65.71428571 ,10},
- {0.08930952381, 71.71428571 ,10},
- {0.1017619048, 77.71428571 ,10},
- {0.1152142857, 83.71428571 ,10},
- {0.1296666667, 89.71428571 ,10},
- {0.1451190476, 95.71428571 ,10},
- {0.1615714286, 101.7142857 ,10},
- {0.1790238095, 107.7142857 ,10},
- {0.1974761905, 113.7142857 ,10},
- {0.2169285714, 119.7142857 ,10},
- {0.2373809524, 125.7142857 ,10},
- {0.2588333333, 131.7142857 ,10},
- {0.2812857143, 137.7142857 ,10},
- {0.3047380952, 143.7142857 ,10},
- {0.3291904762, 149.7142857 ,10},
- {0.3546428571, 155.7142857 ,10},
- {0.3810952381, 161.7142857 ,10},
- {0.408547619, 167.7142857 ,10},
- {0.437, 173.7142857 ,10},
- {0.466452381, 179.7142857 ,10},
- {0.4969047619, 185.7142857 ,10},
- {0.5283095238, 191.1428571 ,10},
- {0.5605952381, 196.2857143 ,10},
- {0.5937142857, 201.1428571 ,10},
- {0.6276190476, 205.7142857 ,10},
- {0.6622619048, 210 ,10},
- {0.6975952381, 214 ,10},
- {0.7335714286, 217.7142857 ,10},
- {0.7701428571, 221.1428571 ,10},
- {0.8072619048, 224.2857143 ,10},
- {0.8448809524, 227.1428571 ,10},
- {0.882952381, 229.7142857 ,10},
- {0.9214285714, 232 ,10},
- {0.9602619048, 234 ,10},
- {0.9994047619, 235.7142857 ,10},
- {1.038809524, 237.1428571 ,10},
- {1.078428571, 238.2857143 ,10},
- {1.118214286, 239.1428571 ,10},
- {1.158119048, 239.7142857 ,10},
- {1.198095238, 240 ,10},
- {1.238095238, 240 ,10},
- {1.278095238, 240 ,10},
- {1.318095238, 240 ,10},
- {1.358095238, 240 ,10},
- {1.398095238, 240 ,10},
- {1.438095238, 240 ,10},
- {1.478095238, 240 ,10},
- {1.518095238, 240 ,10},
- {1.558095238, 240 ,10},
- {1.598095238, 240 ,10},
- {1.638095238, 240 ,10},
- {1.678095238, 240 ,10},
- {1.718095238, 240 ,10},
- {1.758095238, 240 ,10},
- {1.798095238, 240 ,10},
- {1.838095238, 240 ,10},
- {1.878095238, 240 ,10},
- {1.918095238, 240 ,10},
- {1.958095238, 240 ,10},
- {1.998095238, 240 ,10},
- {2.038095238, 240 ,10},
- {2.078095238, 240 ,10},
- {2.118095238, 240 ,10},
- {2.158095238, 240 ,10},
- {2.198095238, 240 ,10},
- {2.238095238, 240 ,10},
- {2.278095238, 240 ,10},
- {2.318095238, 240 ,10},
- {2.358095238, 240 ,10},
- {2.398095238, 240 ,10},
- {2.438095238, 240 ,10},
- {2.478095238, 240 ,10},
- {2.518095238, 240 ,10},
- {2.558095238, 240 ,10},
- {2.598095238, 240 ,10},
- {2.638095238, 240 ,10},
- {2.678095238, 240 ,10},
- {2.718095238, 240 ,10},
- {2.758095238, 240 ,10},
- {2.798095238, 240 ,10},
- {2.838095238, 240 ,10},
- {2.878095238, 240 ,10},
- {2.918095238, 240 ,10},
- {2.958095238, 240 ,10},
- {2.998095238, 240 ,10},
- {3.038095238, 240 ,10},
- {3.078095238, 240 ,10},
- {3.118095238, 240 ,10},
- {3.158095238, 240 ,10},
- {3.198095238, 240 ,10},
- {3.238095238, 240 ,10},
- {3.278095238, 240 ,10},
- {3.318095238, 240 ,10},
- {3.358095238, 240 ,10},
- {3.398095238, 240 ,10},
- {3.438095238, 240 ,10},
- {3.478095238, 240 ,10},
- {3.518095238, 240 ,10},
- {3.558095238, 240 ,10},
- {3.598095238, 240 ,10},
- {3.638095238, 240 ,10},
- {3.678095238, 240 ,10},
- {3.718095238, 240 ,10},
- {3.758095238, 240 ,10},
- {3.798095238, 240 ,10},
- {3.838095238, 240 ,10},
- {3.878047619, 239.4285714 ,10},
- {3.917880952, 238.5714286 ,10},
- {3.957547619, 237.4285714 ,10},
- {3.997, 236 ,10},
- {4.036190476, 234.2857143 ,10},
- {4.075071429, 232.2857143 ,10},
- {4.113595238, 230 ,10},
- {4.151714286, 227.4285714 ,10},
- {4.189380952, 224.5714286 ,10},
- {4.226547619, 221.4285714 ,10},
- {4.263166667, 218 ,10},
- {4.299190476, 214.2857143 ,10},
- {4.334571429, 210.2857143 ,10},
- {4.369261905, 206 ,10},
- {4.403214286, 201.4285714 ,10},
- {4.436380952, 196.5714286 ,10},
- {4.468714286, 191.4285714 ,10},
- {4.500166667, 186 ,10},
- {4.530690476, 180.2857143 ,10},
- {4.560238095, 174.2857143 ,10},
- {4.588785714, 168.2857143 ,10},
- {4.616333333, 162.2857143 ,10},
- {4.642880952, 156.2857143 ,10},
- {4.668428571, 150.2857143 ,10},
- {4.69297619, 144.2857143 ,10},
- {4.71652381, 138.2857143 ,10},
- {4.739071429, 132.2857143 ,10},
- {4.760619048, 126.2857143 ,10},
- {4.781166667, 120.2857143 ,10},
- {4.800714286, 114.2857143 ,10},
- {4.819261905, 108.2857143 ,10},
- {4.836809524, 102.2857143 ,10},
- {4.853357143, 96.28571429 ,10},
- {4.868904762, 90.28571429 ,10},
- {4.883452381, 84.28571429 ,10},
- {4.897, 78.28571429 ,10},
- {4.909547619, 72.28571429 ,10},
- {4.921095238, 66.28571429 ,10},
- {4.931642857, 60.28571429 ,10},
- {4.941190476, 54.28571429 ,10},
- {4.949785714, 48.85714286 ,10},
- {4.9575, 43.71428571 ,10},
- {4.964380952, 38.85714286 ,10},
- {4.97047619, 34.28571429 ,10},
- {4.975833333, 30 ,10},
- {4.9805, 26 ,10},
- {4.98452381, 22.28571429 ,10},
- {4.987952381, 18.85714286 ,10},
- {4.990833333, 15.71428571 ,10},
- {4.993214286, 12.85714286 ,10},
- {4.995142857, 10.28571429 ,10},
- {4.996666667, 8 ,10},
- {4.997833333, 6 ,10},
- {4.998690476, 4.285714286 ,10},
- {4.999285714, 2.857142857 ,10},
- {4.999666667, 1.714285714 ,10},
- {4.999880952, 0.8571428571 ,10},
- {4.99997619, 0.2857142857 ,10},
- {5, 0 ,10}};
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-}
\ No newline at end of file
+
+package org.usfirs .frc. eam3539.robo ;
+public class Genera edMo ionProfile {
+ public s a ic final in kNumPoin s =185;
+ // Posi ion (ro a ions) Veloci y (RPM) Dura ion (ms)
+ public s a ic double [][]Poin s = new double[][]{
+ {0, 0 ,10},
+ {0.00004761904762, 0.5714285714 ,10},
+ {0.0002142857143, 1.428571429 ,10},
+ {0.0005476190476, 2.571428571 ,10},
+ {0.001095238095, 4 ,10},
+ {0.001904761905, 5.714285714 ,10},
+ {0.003023809524, 7.714285714 ,10},
+ {0.0045, 10 ,10},
+ {0.006380952381, 12.57142857 ,10},
+ {0.008714285714, 15.42857143 ,10},
+ {0.01154761905, 18.57142857 ,10},
+ {0.01492857143, 22 ,10},
+ {0.0189047619, 25.71428571 ,10},
+ {0.02352380952, 29.71428571 ,10},
+ {0.02883333333, 34 ,10},
+ {0.03488095238, 38.57142857 ,10},
+ {0.04171428571, 43.42857143 ,10},
+ {0.04938095238, 48.57142857 ,10},
+ {0.05792857143, 54 ,10},
+ {0.0674047619, 59.71428571 ,10},
+ {0.07785714286, 65.71428571 ,10},
+ {0.08930952381, 71.71428571 ,10},
+ {0.1017619048, 77.71428571 ,10},
+ {0.1152142857, 83.71428571 ,10},
+ {0.1296666667, 89.71428571 ,10},
+ {0.1451190476, 95.71428571 ,10},
+ {0.1615714286, 101.7142857 ,10},
+ {0.1790238095, 107.7142857 ,10},
+ {0.1974761905, 113.7142857 ,10},
+ {0.2169285714, 119.7142857 ,10},
+ {0.2373809524, 125.7142857 ,10},
+ {0.2588333333, 131.7142857 ,10},
+ {0.2812857143, 137.7142857 ,10},
+ {0.3047380952, 143.7142857 ,10},
+ {0.3291904762, 149.7142857 ,10},
+ {0.3546428571, 155.7142857 ,10},
+ {0.3810952381, 161.7142857 ,10},
+ {0.408547619, 167.7142857 ,10},
+ {0.437, 173.7142857 ,10},
+ {0.466452381, 179.7142857 ,10},
+ {0.4969047619, 185.7142857 ,10},
+ {0.5283095238, 191.1428571 ,10},
+ {0.5605952381, 196.2857143 ,10},
+ {0.5937142857, 201.1428571 ,10},
+ {0.6276190476, 205.7142857 ,10},
+ {0.6622619048, 210 ,10},
+ {0.6975952381, 214 ,10},
+ {0.7335714286, 217.7142857 ,10},
+ {0.7701428571, 221.1428571 ,10},
+ {0.8072619048, 224.2857143 ,10},
+ {0.8448809524, 227.1428571 ,10},
+ {0.882952381, 229.7142857 ,10},
+ {0.9214285714, 232 ,10},
+ {0.9602619048, 234 ,10},
+ {0.9994047619, 235.7142857 ,10},
+ {1.038809524, 237.1428571 ,10},
+ {1.078428571, 238.2857143 ,10},
+ {1.118214286, 239.1428571 ,10},
+ {1.158119048, 239.7142857 ,10},
+ {1.198095238, 240 ,10},
+ {1.238095238, 240 ,10},
+ {1.278095238, 240 ,10},
+ {1.318095238, 240 ,10},
+ {1.358095238, 240 ,10},
+ {1.398095238, 240 ,10},
+ {1.438095238, 240 ,10},
+ {1.478095238, 240 ,10},
+ {1.518095238, 240 ,10},
+ {1.558095238, 240 ,10},
+ {1.598095238, 240 ,10},
+ {1.638095238, 240 ,10},
+ {1.678095238, 240 ,10},
+ {1.718095238, 240 ,10},
+ {1.758095238, 240 ,10},
+ {1.798095238, 240 ,10},
+ {1.838095238, 240 ,10},
+ {1.878095238, 240 ,10},
+ {1.918095238, 240 ,10},
+ {1.958095238, 240 ,10},
+ {1.998095238, 240 ,10},
+ {2.038095238, 240 ,10},
+ {2.078095238, 240 ,10},
+ {2.118095238, 240 ,10},
+ {2.158095238, 240 ,10},
+ {2.198095238, 240 ,10},
+ {2.238095238, 240 ,10},
+ {2.278095238, 240 ,10},
+ {2.318095238, 240 ,10},
+ {2.358095238, 240 ,10},
+ {2.398095238, 240 ,10},
+ {2.438095238, 240 ,10},
+ {2.478095238, 240 ,10},
+ {2.518095238, 240 ,10},
+ {2.558095238, 240 ,10},
+ {2.598095238, 240 ,10},
+ {2.638095238, 240 ,10},
+ {2.678095238, 240 ,10},
+ {2.718095238, 240 ,10},
+ {2.758095238, 240 ,10},
+ {2.798095238, 240 ,10},
+ {2.838095238, 240 ,10},
+ {2.878095238, 240 ,10},
+ {2.918095238, 240 ,10},
+ {2.958095238, 240 ,10},
+ {2.998095238, 240 ,10},
+ {3.038095238, 240 ,10},
+ {3.078095238, 240 ,10},
+ {3.118095238, 240 ,10},
+ {3.158095238, 240 ,10},
+ {3.198095238, 240 ,10},
+ {3.238095238, 240 ,10},
+ {3.278095238, 240 ,10},
+ {3.318095238, 240 ,10},
+ {3.358095238, 240 ,10},
+ {3.398095238, 240 ,10},
+ {3.438095238, 240 ,10},
+ {3.478095238, 240 ,10},
+ {3.518095238, 240 ,10},
+ {3.558095238, 240 ,10},
+ {3.598095238, 240 ,10},
+ {3.638095238, 240 ,10},
+ {3.678095238, 240 ,10},
+ {3.718095238, 240 ,10},
+ {3.758095238, 240 ,10},
+ {3.798095238, 240 ,10},
+ {3.838095238, 240 ,10},
+ {3.878047619, 239.4285714 ,10},
+ {3.917880952, 238.5714286 ,10},
+ {3.957547619, 237.4285714 ,10},
+ {3.997, 236 ,10},
+ {4.036190476, 234.2857143 ,10},
+ {4.075071429, 232.2857143 ,10},
+ {4.113595238, 230 ,10},
+ {4.151714286, 227.4285714 ,10},
+ {4.189380952, 224.5714286 ,10},
+ {4.226547619, 221.4285714 ,10},
+ {4.263166667, 218 ,10},
+ {4.299190476, 214.2857143 ,10},
+ {4.334571429, 210.2857143 ,10},
+ {4.369261905, 206 ,10},
+ {4.403214286, 201.4285714 ,10},
+ {4.436380952, 196.5714286 ,10},
+ {4.468714286, 191.4285714 ,10},
+ {4.500166667, 186 ,10},
+ {4.530690476, 180.2857143 ,10},
+ {4.560238095, 174.2857143 ,10},
+ {4.588785714, 168.2857143 ,10},
+ {4.616333333, 162.2857143 ,10},
+ {4.642880952, 156.2857143 ,10},
+ {4.668428571, 150.2857143 ,10},
+ {4.69297619, 144.2857143 ,10},
+ {4.71652381, 138.2857143 ,10},
+ {4.739071429, 132.2857143 ,10},
+ {4.760619048, 126.2857143 ,10},
+ {4.781166667, 120.2857143 ,10},
+ {4.800714286, 114.2857143 ,10},
+ {4.819261905, 108.2857143 ,10},
+ {4.836809524, 102.2857143 ,10},
+ {4.853357143, 96.28571429 ,10},
+ {4.868904762, 90.28571429 ,10},
+ {4.883452381, 84.28571429 ,10},
+ {4.897, 78.28571429 ,10},
+ {4.909547619, 72.28571429 ,10},
+ {4.921095238, 66.28571429 ,10},
+ {4.931642857, 60.28571429 ,10},
+ {4.941190476, 54.28571429 ,10},
+ {4.949785714, 48.85714286 ,10},
+ {4.9575, 43.71428571 ,10},
+ {4.964380952, 38.85714286 ,10},
+ {4.97047619, 34.28571429 ,10},
+ {4.975833333, 30 ,10},
+ {4.9805, 26 ,10},
+ {4.98452381, 22.28571429 ,10},
+ {4.987952381, 18.85714286 ,10},
+ {4.990833333, 15.71428571 ,10},
+ {4.993214286, 12.85714286 ,10},
+ {4.995142857, 10.28571429 ,10},
+ {4.996666667, 8 ,10},
+ {4.997833333, 6 ,10},
+ {4.998690476, 4.285714286 ,10},
+ {4.999285714, 2.857142857 ,10},
+ {4.999666667, 1.714285714 ,10},
+ {4.999880952, 0.8571428571 ,10},
+ {4.99997619, 0.2857142857 ,10},
+ {5, 0 ,10}};
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+}
diff --git a/JAVA_MotionProfileExample/src/org/usfirst/frc/team3539/robot/MotionProfileExample.java b/JAVA_MotionProfileExample/src/org/usfirst/frc/team3539/robot/MotionProfileExample.java
index e993817..f876896 100644
--- a/JAVA_MotionProfileExample/src/org/usfirst/frc/team3539/robot/MotionProfileExample.java
+++ b/JAVA_MotionProfileExample/src/org/usfirst/frc/team3539/robot/MotionProfileExample.java
@@ -1,300 +1,300 @@
/**
- * Example logic for firing and managing motion profiles.
- * This example sends MPs, waits for them to finish
- * Although this code uses a CANTalon, nowhere in this module do we changeMode() or call set() to change the output.
- * This is done in Robot.java to demonstrate how to change control modes on the fly.
+ * Example logic for firing and managing mo ion profiles.
+ * This example sends MPs, wai s for hem o finish
+ * Al hough his code uses a CANTalon, nowhere in his module do we changeMode() or call se () o change he ou pu .
+ * This is done in Robo .java o demons ra e how o change con rol modes on he fly.
*
- * The only routines we call on Talon are....
+ * The only rou ines we call on Talon are....
*
- * changeMotionControlFramePeriod
+ * changeMo ionCon rolFramePeriod
*
- * getMotionProfileStatus
- * clearMotionProfileHasUnderrun to get status and potentially clear the error flag.
+ * ge Mo ionProfileS a us
+ * clearMo ionProfileHasUnderrun o ge s a us and po en ially clear he error flag.
*
- * pushMotionProfileTrajectory
- * clearMotionProfileTrajectories
- * processMotionProfileBuffer, to push/clear, and process the trajectory points.
+ * pushMo ionProfileTrajec ory
+ * clearMo ionProfileTrajec ories
+ * processMo ionProfileBuffer, o push/clear, and process he rajec ory poin s.
*
- * getControlMode, to check if we are in Motion Profile Control mode.
+ * ge Con rolMode, o check if we are in Mo ion Profile Con rol mode.
*
- * Example of advanced features not demonstrated here...
- * [1] Calling pushMotionProfileTrajectory() continuously while the Talon executes the motion profile, thereby keeping it going indefinitely.
- * [2] Instead of setting the sensor position to zero at the start of each MP, the program could offset the MP's position based on current position.
+ * Example of advanced fea ures no demons ra ed here...
+ * [1] Calling pushMo ionProfileTrajec ory() con inuously while he Talon execu es he mo ion profile, hereby keeping i going indefini ely.
+ * [2] Ins ead of se ing he sensor posi ion o zero a he s ar of each MP, he program could offse he MP's posi ion based on curren posi ion.
*/
-package org.usfirst.frc.team3539.robot;
+package org.usfirs .frc. eam3539.robo ;
-import com.ctre.CANTalon;
-import edu.wpi.first.wpilibj.Notifier;
-import com.ctre.CANTalon.TalonControlMode;
+impor com.c re.CANTalon;
+impor edu.wpi.firs .wpilibj.No ifier;
+impor com.c re.CANTalon.TalonCon rolMode;
-public class MotionProfileExample {
+public class Mo ionProfileExample {
- /**
- * The status of the motion profile executer and buffer inside the Talon.
- * Instead of creating a new one every time we call getMotionProfileStatus,
- * keep one copy.
- */
- private CANTalon.MotionProfileStatus _status = new CANTalon.MotionProfileStatus();
+ /**
+ * The s a us of he mo ion profile execu er and buffer inside he Talon.
+ * Ins ead of crea ing a new one every ime we call ge Mo ionProfileS a us,
+ * keep one copy.
+ */
+ priva e CANTalon.Mo ionProfileS a us _s a us = new CANTalon.Mo ionProfileS a us();
- /**
- * reference to the talon we plan on manipulating. We will not changeMode()
- * or call set(), just get motion profile status and make decisions based on
- * motion profile.
- */
- private CANTalon _talon;
- /**
- * State machine to make sure we let enough of the motion profile stream to
- * talon before we fire it.
- */
- private int _state = 0;
- /**
- * Any time you have a state machine that waits for external events, its a
- * good idea to add a timeout. Set to -1 to disable. Set to nonzero to count
- * down to '0' which will print an error message. Counting loops is not a
- * very accurate method of tracking timeout, but this is just conservative
- * timeout. Getting time-stamps would certainly work too, this is just
- * simple (no need to worry about timer overflows).
- */
- private int _loopTimeout = -1;
- /**
- * If start() gets called, this flag is set and in the control() we will
- * service it.
- */
- private boolean _bStart = false;
+ /**
+ * reference o he alon we plan on manipula ing. We will no changeMode()
+ * or call se (), jus ge mo ion profile s a us and make decisions based on
+ * mo ion profile.
+ */
+ priva e CANTalon _ alon;
+ /**
+ * S a e machine o make sure we le enough of he mo ion profile s ream o
+ * alon before we fire i .
+ */
+ priva e in _s a e = 0;
+ /**
+ * Any ime you have a s a e machine ha wai s for ex ernal even s, i s a
+ * good idea o add a imeou . Se o -1 o disable. Se o nonzero o coun
+ * down o '0' which will prin an error message. Coun ing loops is no a
+ * very accura e me hod of racking imeou , bu his is jus conserva ive
+ * imeou . Ge ing ime-s amps would cer ainly work oo, his is jus
+ * simple (no need o worry abou imer overflows).
+ */
+ priva e in _loopTimeou = -1;
+ /**
+ * If s ar () ge s called, his flag is se and in he con rol() we will
+ * service i .
+ */
+ priva e boolean _bS ar = false;
- /**
- * Since the CANTalon.set() routine is mode specific, deduce what we want
- * the set value to be and let the calling module apply it whenever we
- * decide to switch to MP mode.
- */
- private CANTalon.SetValueMotionProfile _setValue = CANTalon.SetValueMotionProfile.Disable;
- /**
- * How many trajectory points do we wait for before firing the motion
- * profile.
- */
- private static final int kMinPointsInTalon = 5;
- /**
- * Just a state timeout to make sure we don't get stuck anywhere. Each loop
- * is about 20ms.
- */
- private static final int kNumLoopsTimeout = 10;
-
- /**
- * Lets create a periodic task to funnel our trajectory points into our talon.
- * It doesn't need to be very accurate, just needs to keep pace with the motion
- * profiler executer. Now if you're trajectory points are slow, there is no need
- * to do this, just call _talon.processMotionProfileBuffer() in your teleop loop.
- * Generally speaking you want to call it at least twice as fast as the duration
- * of your trajectory points. So if they are firing every 20ms, you should call
- * every 10ms.
- */
- class PeriodicRunnable implements java.lang.Runnable {
- public void run() { _talon.processMotionProfileBuffer(); }
- }
- Notifier _notifer = new Notifier(new PeriodicRunnable());
-
+ /**
+ * Since he CANTalon.se () rou ine is mode specific, deduce wha we wan
+ * he se value o be and le he calling module apply i whenever we
+ * decide o swi ch o MP mode.
+ */
+ priva e CANTalon.Se ValueMo ionProfile _se Value = CANTalon.Se ValueMo ionProfile.Disable;
+ /**
+ * How many rajec ory poin s do we wai for before firing he mo ion
+ * profile.
+ */
+ priva e s a ic final in kMinPoin sInTalon = 5;
+ /**
+ * Jus a s a e imeou o make sure we don' ge s uck anywhere. Each loop
+ * is abou 20ms.
+ */
+ priva e s a ic final in kNumLoopsTimeou = 10;
+
+ /**
+ * Le s crea e a periodic ask o funnel our rajec ory poin s in o our alon.
+ * I doesn' need o be very accura e, jus needs o keep pace wi h he mo ion
+ * profiler execu er. Now if you're rajec ory poin s are slow, here is no need
+ * o do his, jus call _ alon.processMo ionProfileBuffer() in your eleop loop.
+ * Generally speaking you wan o call i a leas wice as fas as he dura ion
+ * of your rajec ory poin s. So if hey are firing every 20ms, you should call
+ * every 10ms.
+ */
+ class PeriodicRunnable implemen s java.lang.Runnable {
+ public void run() { _ alon.processMo ionProfileBuffer(); }
+ }
+ No ifier _no ifer = new No ifier(new PeriodicRunnable());
+
- /**
- * C'tor
- *
- * @param talon
- * reference to Talon object to fetch motion profile status from.
- */
- public MotionProfileExample(CANTalon talon) {
- _talon = talon;
- /*
- * since our MP is 10ms per point, set the control frame rate and the
- * notifer to half that
- */
- _talon.changeMotionControlFramePeriod(5);
- _notifer.startPeriodic(0.005);
- }
+ /**
+ * C' or
+ *
+ * @param alon
+ * reference o Talon objec o fe ch mo ion profile s a us from.
+ */
+ public Mo ionProfileExample(CANTalon alon) {
+ _ alon = alon;
+ /*
+ * since our MP is 10ms per poin , se he con rol frame ra e and he
+ * no ifer o half ha
+ */
+ _ alon.changeMo ionCon rolFramePeriod(5);
+ _no ifer.s ar Periodic(0.005);
+ }
- /**
- * Called to clear Motion profile buffer and reset state info during
- * disabled and when Talon is not in MP control mode.
- */
- public void reset() {
- /*
- * Let's clear the buffer just in case user decided to disable in the
- * middle of an MP, and now we have the second half of a profile just
- * sitting in memory.
- */
- _talon.clearMotionProfileTrajectories();
- /* When we do re-enter motionProfile control mode, stay disabled. */
- _setValue = CANTalon.SetValueMotionProfile.Disable;
- /* When we do start running our state machine start at the beginning. */
- _state = 0;
- _loopTimeout = -1;
- /*
- * If application wanted to start an MP before, ignore and wait for next
- * button press
- */
- _bStart = false;
- }
+ /**
+ * Called o clear Mo ion profile buffer and rese s a e info during
+ * disabled and when Talon is no in MP con rol mode.
+ */
+ public void rese () {
+ /*
+ * Le 's clear he buffer jus in case user decided o disable in he
+ * middle of an MP, and now we have he second half of a profile jus
+ * si ing in memory.
+ */
+ _ alon.clearMo ionProfileTrajec ories();
+ /* When we do re-en er mo ionProfile con rol mode, s ay disabled. */
+ _se Value = CANTalon.Se ValueMo ionProfile.Disable;
+ /* When we do s ar running our s a e machine s ar a he beginning. */
+ _s a e = 0;
+ _loopTimeou = -1;
+ /*
+ * If applica ion wan ed o s ar an MP before, ignore and wai for nex
+ * bu on press
+ */
+ _bS ar = false;
+ }
- /**
- * Called every loop.
- */
- public void control() {
- /* Get the motion profile status every loop */
- _talon.getMotionProfileStatus(_status);
+ /**
+ * Called every loop.
+ */
+ public void con rol() {
+ /* Ge he mo ion profile s a us every loop */
+ _ alon.ge Mo ionProfileS a us(_s a us);
- /*
- * track time, this is rudimentary but that's okay, we just want to make
- * sure things never get stuck.
- */
- if (_loopTimeout < 0) {
- /* do nothing, timeout is disabled */
- } else {
- /* our timeout is nonzero */
- if (_loopTimeout == 0) {
- /*
- * something is wrong. Talon is not present, unplugged, breaker
- * tripped
- */
- instrumentation.OnNoProgress();
- } else {
- --_loopTimeout;
- }
- }
+ /*
+ * rack ime, his is rudimen ary bu ha 's okay, we jus wan o make
+ * sure hings never ge s uck.
+ */
+ if (_loopTimeou < 0) {
+ /* do no hing, imeou is disabled */
+ } else {
+ /* our imeou is nonzero */
+ if (_loopTimeou == 0) {
+ /*
+ * some hing is wrong. Talon is no presen , unplugged, breaker
+ * ripped
+ */
+ ins rumen a ion.OnNoProgress();
+ } else {
+ --_loopTimeou ;
+ }
+ }
- /* first check if we are in MP mode */
- if (_talon.getControlMode() != TalonControlMode.MotionProfile) {
- /*
- * we are not in MP mode. We are probably driving the robot around
- * using gamepads or some other mode.
- */
- _state = 0;
- _loopTimeout = -1;
- } else {
- /*
- * we are in MP control mode. That means: starting Mps, checking Mp
- * progress, and possibly interrupting MPs if thats what you want to
- * do.
- */
- switch (_state) {
- case 0: /* wait for application to tell us to start an MP */
- if (_bStart) {
- _bStart = false;
-
- _setValue = CANTalon.SetValueMotionProfile.Disable;
- startFilling();
- /*
- * MP is being sent to CAN bus, wait a small amount of time
- */
- _state = 1;
- _loopTimeout = kNumLoopsTimeout;
- }
- break;
- case 1: /*
- * wait for MP to stream to Talon, really just the first few
- * points
- */
- /* do we have a minimum numberof points in Talon */
- if (_status.btmBufferCnt > kMinPointsInTalon) {
- /* start (once) the motion profile */
- _setValue = CANTalon.SetValueMotionProfile.Enable;
- /* MP will start once the control frame gets scheduled */
- _state = 2;
- _loopTimeout = kNumLoopsTimeout;
- }
- break;
- case 2: /* check the status of the MP */
- /*
- * if talon is reporting things are good, keep adding to our
- * timeout. Really this is so that you can unplug your talon in
- * the middle of an MP and react to it.
- */
- if (_status.isUnderrun == false) {
- _loopTimeout = kNumLoopsTimeout;
- }
- /*
- * If we are executing an MP and the MP finished, start loading
- * another. We will go into hold state so robot servo's
- * position.
- */
- if (_status.activePointValid && _status.activePoint.isLastPoint) {
- /*
- * because we set the last point's isLast to true, we will
- * get here when the MP is done
- */
- _setValue = CANTalon.SetValueMotionProfile.Hold;
- _state = 0;
- _loopTimeout = -1;
- }
- break;
- }
- }
- /* printfs and/or logging */
- instrumentation.process(_status);
- }
+ /* firs check if we are in MP mode */
+ if (_ alon.ge Con rolMode() != TalonCon rolMode.Mo ionProfile) {
+ /*
+ * we are no in MP mode. We are probably driving he robo around
+ * using gamepads or some o her mode.
+ */
+ _s a e = 0;
+ _loopTimeou = -1;
+ } else {
+ /*
+ * we are in MP con rol mode. Tha means: s ar ing Mps, checking Mp
+ * progress, and possibly in errup ing MPs if ha s wha you wan o
+ * do.
+ */
+ swi ch (_s a e) {
+ case 0: /* wai for applica ion o ell us o s ar an MP */
+ if (_bS ar ) {
+ _bS ar = false;
+
+ _se Value = CANTalon.Se ValueMo ionProfile.Disable;
+ s ar Filling();
+ /*
+ * MP is being sen o CAN bus, wai a small amoun of ime
+ */
+ _s a e = 1;
+ _loopTimeou = kNumLoopsTimeou ;
+ }
+ break;
+ case 1: /*
+ * wai for MP o s ream o Talon, really jus he firs few
+ * poin s
+ */
+ /* do we have a minimum numberof poin s in Talon */
+ if (_s a us.b mBufferCn > kMinPoin sInTalon) {
+ /* s ar (once) he mo ion profile */
+ _se Value = CANTalon.Se ValueMo ionProfile.Enable;
+ /* MP will s ar once he con rol frame ge s scheduled */
+ _s a e = 2;
+ _loopTimeou = kNumLoopsTimeou ;
+ }
+ break;
+ case 2: /* check he s a us of he MP */
+ /*
+ * if alon is repor ing hings are good, keep adding o our
+ * imeou . Really his is so ha you can unplug your alon in
+ * he middle of an MP and reac o i .
+ */
+ if (_s a us.isUnderrun == false) {
+ _loopTimeou = kNumLoopsTimeou ;
+ }
+ /*
+ * If we are execu ing an MP and he MP finished, s ar loading
+ * ano her. We will go in o hold s a e so robo servo's
+ * posi ion.
+ */
+ if (_s a us.ac ivePoin Valid && _s a us.ac ivePoin .isLas Poin ) {
+ /*
+ * because we se he las poin 's isLas o rue, we will
+ * ge here when he MP is done
+ */
+ _se Value = CANTalon.Se ValueMo ionProfile.Hold;
+ _s a e = 0;
+ _loopTimeou = -1;
+ }
+ break;
+ }
+ }
+ /* prin fs and/or logging */
+ ins rumen a ion.process(_s a us);
+ }
- /** Start filling the MPs to all of the involved Talons. */
- private void startFilling() {
- /* since this example only has one talon, just update that one */
- startFilling(GeneratedMotionProfile.Points, GeneratedMotionProfile.kNumPoints);
- }
+ /** S ar filling he MPs o all of he involved Talons. */
+ priva e void s ar Filling() {
+ /* since his example only has one alon, jus upda e ha one */
+ s ar Filling(Genera edMo ionProfile.Poin s, Genera edMo ionProfile.kNumPoin s);
+ }
- private void startFilling(double[][] profile, int totalCnt) {
+ priva e void s ar Filling(double[][] profile, in o alCn ) {
- /* create an empty point */
- CANTalon.TrajectoryPoint point = new CANTalon.TrajectoryPoint();
+ /* crea e an emp y poin */
+ CANTalon.Trajec oryPoin poin = new CANTalon.Trajec oryPoin ();
- /* did we get an underrun condition since last time we checked ? */
- if (_status.hasUnderrun) {
- /* better log it so we know about it */
- instrumentation.OnUnderrun();
- /*
- * clear the error. This flag does not auto clear, this way
- * we never miss logging it.
- */
- _talon.clearMotionProfileHasUnderrun();
- }
- /*
- * just in case we are interrupting another MP and there is still buffer
- * points in memory, clear it.
- */
- _talon.clearMotionProfileTrajectories();
+ /* did we ge an underrun condi ion since las ime we checked ? */
+ if (_s a us.hasUnderrun) {
+ /* be er log i so we know abou i */
+ ins rumen a ion.OnUnderrun();
+ /*
+ * clear he error. This flag does no au o clear, his way
+ * we never miss logging i .
+ */
+ _ alon.clearMo ionProfileHasUnderrun();
+ }
+ /*
+ * jus in case we are in errup ing ano her MP and here is s ill buffer
+ * poin s in memory, clear i .
+ */
+ _ alon.clearMo ionProfileTrajec ories();
- /* This is fast since it's just into our TOP buffer */
- for (int i = 0; i < totalCnt; ++i) {
- /* for each point, fill our structure and pass it to API */
- point.position = profile[i][0];
- point.velocity = profile[i][1];
- point.timeDurMs = (int) profile[i][2];
- point.profileSlotSelect = 0; /* which set of gains would you like to use? */
- point.velocityOnly = false; /* set true to not do any position
- * servo, just velocity feedforward
- */
- point.zeroPos = false;
- if (i == 0)
- point.zeroPos = true; /* set this to true on the first point */
+ /* This is fas since i 's jus in o our TOP buffer */
+ for (in i = 0; i < o alCn ; ++i) {
+ /* for each poin , fill our s ruc ure and pass i o API */
+ poin .posi ion = profile[i][0];
+ poin .veloci y = profile[i][1];
+ poin . imeDurMs = (in ) profile[i][2];
+ poin .profileSlo Selec = 0; /* which se of gains would you like o use? */
+ poin .veloci yOnly = false; /* se rue o no do any posi ion
+ * servo, jus veloci y feedforward
+ */
+ poin .zeroPos = false;
+ if (i == 0)
+ poin .zeroPos = rue; /* se his o rue on he firs poin */
- point.isLastPoint = false;
- if ((i + 1) == totalCnt)
- point.isLastPoint = true; /* set this to true on the last point */
+ poin .isLas Poin = false;
+ if ((i + 1) == o alCn )
+ poin .isLas Poin = rue; /* se his o rue on he las poin */
- _talon.pushMotionProfileTrajectory(point);
- }
- }
+ _ alon.pushMo ionProfileTrajec ory(poin );
+ }
+ }
- /**
- * Called by application to signal Talon to start the buffered MP (when it's
- * able to).
- */
- void startMotionProfile() {
- _bStart = true;
- }
+ /**
+ * Called by applica ion o signal Talon o s ar he buffered MP (when i 's
+ * able o).
+ */
+ void s ar Mo ionProfile() {
+ _bS ar = rue;
+ }
- /**
- *
- * @return the output value to pass to Talon's set() routine. 0 for disable
- * motion-profile output, 1 for enable motion-profile, 2 for hold
- * current motion profile trajectory point.
- */
- CANTalon.SetValueMotionProfile getSetValue() {
- return _setValue;
- }
+ /**
+ *
+ * @re urn he ou pu value o pass o Talon's se () rou ine. 0 for disable
+ * mo ion-profile ou pu , 1 for enable mo ion-profile, 2 for hold
+ * curren mo ion profile rajec ory poin .
+ */
+ CANTalon.Se ValueMo ionProfile ge Se Value() {
+ re urn _se Value;
+ }
}
diff --git a/JAVA_MotionProfileExample/src/org/usfirst/frc/team3539/robot/Robot.java b/JAVA_MotionProfileExample/src/org/usfirst/frc/team3539/robot/Robot.java
index 8f612c1..f810095 100644
--- a/JAVA_MotionProfileExample/src/org/usfirst/frc/team3539/robot/Robot.java
+++ b/JAVA_MotionProfileExample/src/org/usfirst/frc/team3539/robot/Robot.java
@@ -1,114 +1,114 @@
/**
- * This Java FRC robot application is meant to demonstrate an example using the Motion Profile control mode
- * in Talon SRX. The CANTalon class gives us the ability to buffer up trajectory points and execute them
- * as the roboRIO streams them into the Talon SRX.
+ * This Java FRC robo applica ion is mean o demons ra e an example using he Mo ion Profile con rol mode
+ * in Talon SRX. The CANTalon class gives us he abili y o buffer up rajec ory poin s and execu e hem
+ * as he roboRIO s reams hem in o he Talon SRX.
*
- * There are many valid ways to use this feature and this example does not sufficiently demonstrate every possible
- * method. Motion Profile streaming can be as complex as the developer needs it to be for advanced applications,
- * or it can be used in a simple fashion for fire-and-forget actions that require precise timing.
+ * There are many valid ways o use his fea ure and his example does no sufficien ly demons ra e every possible
+ * me hod. Mo ion Profile s reaming can be as complex as he developer needs i o be for advanced applica ions,
+ * or i can be used in a simple fashion for fire-and-forge ac ions ha require precise iming.
*
- * This application is an IterativeRobot project to demonstrate a minimal implementation not requiring the command
- * framework, however these code excerpts could be moved into a command-based project.
+ * This applica ion is an I era iveRobo projec o demons ra e a minimal implemen a ion no requiring he command
+ * framework, however hese code excerp s could be moved in o a command-based projec .
*
- * The project also includes instrumentation.java which simply has debug printfs, and a MotionProfile.java which is generated
- * in @link https://docs.google.com/spreadsheets/d/1PgT10EeQiR92LNXEOEe3VGn737P7WDP4t0CQxQgC8k0/edit#gid=1813770630&vpid=A1
+ * The projec also includes ins rumen a ion.java which simply has debug prin fs, and a Mo ionProfile.java which is genera ed
+ * in @link h ps://docs.google.com/spreadshee s/d/1PgT10EeQiR92LNXEOEe3VGn737P7WDP4 0CQxQgC8k0/edi #gid=1813770630&vpid=A1
*
- * Logitech Gamepad mapping, use left y axis to drive Talon normally.
- * Press and hold top-left-shoulder-button5 to put Talon into motion profile control mode.
- * This will start sending Motion Profile to Talon while Talon is neutral.
+ * Logi ech Gamepad mapping, use lef y axis o drive Talon normally.
+ * Press and hold op-lef -shoulder-bu on5 o pu Talon in o mo ion profile con rol mode.
+ * This will s ar sending Mo ion Profile o Talon while Talon is neu ral.
*
- * While holding top-left-shoulder-button5, tap top-right-shoulder-button6.
- * This will signal Talon to fire MP. When MP is done, Talon will "hold" the last setpoint position
- * and wait for another button6 press to fire again.
+ * While holding op-lef -shoulder-bu on5, ap op-righ -shoulder-bu on6.
+ * This will signal Talon o fire MP. When MP is done, Talon will "hold" he las se poin posi ion
+ * and wai for ano her bu on6 press o fire again.
*
- * Release button5 to allow OpenVoltage control with left y axis.
+ * Release bu on5 o allow OpenVol age con rol wi h lef y axis.
*/
-package org.usfirst.frc.team3539.robot;
+package org.usfirs .frc. eam3539.robo ;
-import com.ctre.CANTalon;
-import com.ctre.CANTalon.TalonControlMode;
-import edu.wpi.first.wpilibj.IterativeRobot;
-import edu.wpi.first.wpilibj.Joystick;
+impor com.c re.CANTalon;
+impor com.c re.CANTalon.TalonCon rolMode;
+impor edu.wpi.firs .wpilibj.I era iveRobo ;
+impor edu.wpi.firs .wpilibj.Joys ick;
-public class Robot extends IterativeRobot {
+public class Robo ex ends I era iveRobo {
- /** The Talon we want to motion profile. */
- CANTalon _talon = new CANTalon(0);
+ /** The Talon we wan o mo ion profile. */
+ CANTalon _ alon = new CANTalon(0);
- /** some example logic on how one can manage an MP */
- MotionProfileExample _example = new MotionProfileExample(_talon);
-
- /** joystick for testing */
- Joystick _joy= new Joystick(0);
+ /** some example logic on how one can manage an MP */
+ Mo ionProfileExample _example = new Mo ionProfileExample(_ alon);
+
+ /** joys ick for es ing */
+ Joys ick _joy= new Joys ick(0);
- /** cache last buttons so we can detect press events. In a command-based project you can leverage the on-press event
- * but for this simple example, lets just do quick compares to prev-btn-states */
- boolean [] _btnsLast = {false,false,false,false,false,false,false,false,false,false};
+ /** cache las bu ons so we can de ec press even s. In a command-based projec you can leverage he on-press even
+ * bu for his simple example, le s jus do quick compares o prev-b n-s a es */
+ boolean [] _b nsLas = {false,false,false,false,false,false,false,false,false,false};
- public Robot() { // could also use RobotInit()
- _talon.setFeedbackDevice(CANTalon.FeedbackDevice.CtreMagEncoder_Relative);
- _talon.reverseSensor(false); /* keep sensor and motor in phase */
- }
- /** function is called periodically during operator control */
- public void teleopPeriodic() {
- /* get buttons */
- boolean [] btns= new boolean [_btnsLast.length];
- for(int i=1;i<_btnsLast.length;++i)
- btns[i] = _joy.getRawButton(i);
+ public Robo () { // could also use Robo Ini ()
+ _ alon.se FeedbackDevice(CANTalon.FeedbackDevice.C reMagEncoder_Rela ive);
+ _ alon.reverseSensor(false); /* keep sensor and mo or in phase */
+ }
+ /** func ion is called periodically during opera or con rol */
+ public void eleopPeriodic() {
+ /* ge bu ons */
+ boolean [] b ns= new boolean [_b nsLas .leng h];
+ for(in i=1;i<_b nsLas .leng h;++i)
+ b ns[i] = _joy.ge RawBu on(i);
- /* get the left joystick axis on Logitech Gampead */
- double leftYjoystick = -1 * _joy.getY(); /* multiple by -1 so joystick forward is positive */
+ /* ge he lef joys ick axis on Logi ech Gampead */
+ double lef Yjoys ick = -1 * _joy.ge Y(); /* mul iple by -1 so joys ick forward is posi ive */
- /* call this periodically, and catch the output. Only apply it if user wants to run MP. */
- _example.control();
-
- if (btns[5] == false) { /* Check button 5 (top left shoulder on the logitech gamead). */
- /*
- * If it's not being pressed, just do a simple drive. This
- * could be a RobotDrive class or custom drivetrain logic.
- * The point is we want the switch in and out of MP Control mode.*/
-
- /* button5 is off so straight drive */
- _talon.changeControlMode(TalonControlMode.Voltage);
- _talon.set(12.0 * leftYjoystick);
+ /* call his periodically, and ca ch he ou pu . Only apply i if user wan s o run MP. */
+ _example.con rol();
+
+ if (b ns[5] == false) { /* Check bu on 5 ( op lef shoulder on he logi ech gamead). */
+ /*
+ * If i 's no being pressed, jus do a simple drive. This
+ * could be a Robo Drive class or cus om drive rain logic.
+ * The poin is we wan he swi ch in and ou of MP Con rol mode.*/
+
+ /* bu on5 is off so s raigh drive */
+ _ alon.changeCon rolMode(TalonCon rolMode.Vol age);
+ _ alon.se (12.0 * lef Yjoys ick);
- _example.reset();
- } else {
- /* Button5 is held down so switch to motion profile control mode => This is done in MotionProfileControl.
- * When we transition from no-press to press,
- * pass a "true" once to MotionProfileControl.
- */
- _talon.changeControlMode(TalonControlMode.MotionProfile);
-
- CANTalon.SetValueMotionProfile setOutput = _example.getSetValue();
-
- _talon.set(setOutput.value);
+ _example.rese ();
+ } else {
+ /* Bu on5 is held down so swi ch o mo ion profile con rol mode => This is done in Mo ionProfileCon rol.
+ * When we ransi ion from no-press o press,
+ * pass a " rue" once o Mo ionProfileCon rol.
+ */
+ _ alon.changeCon rolMode(TalonCon rolMode.Mo ionProfile);
+
+ CANTalon.Se ValueMo ionProfile se Ou pu = _example.ge Se Value();
+
+ _ alon.se (se Ou pu .value);
- /* if btn is pressed and was not pressed last time,
- * In other words we just detected the on-press event.
- * This will signal the robot to start a MP */
- if( (btns[6] == true) && (_btnsLast[6] == false) ) {
- /* user just tapped button 6 */
- _example.startMotionProfile();
- }
- }
+ /* if b n is pressed and was no pressed las ime,
+ * In o her words we jus de ec ed he on-press even .
+ * This will signal he robo o s ar a MP */
+ if( (b ns[6] == rue) && (_b nsLas [6] == false) ) {
+ /* user jus apped bu on 6 */
+ _example.s ar Mo ionProfile();
+ }
+ }
- /* save buttons states for on-press detection */
- for(int i=1;i<10;++i)
- _btnsLast[i] = btns[i];
+ /* save bu ons s a es for on-press de ec ion */
+ for(in i=1;i<10;++i)
+ _b nsLas [i] = b ns[i];
- }
- /** function is called periodically during disable */
- public void disabledPeriodic() {
- /* it's generally a good idea to put motor controllers back
- * into a known state when robot is disabled. That way when you
- * enable the robot doesn't just continue doing what it was doing before.
- * BUT if that's what the application/testing requires than modify this accordingly */
- _talon.changeControlMode(TalonControlMode.PercentVbus);
- _talon.set( 0 );
- /* clear our buffer and put everything into a known state */
- _example.reset();
- }
+ }
+ /** func ion is called periodically during disable */
+ public void disabledPeriodic() {
+ /* i 's generally a good idea o pu mo or con rollers back
+ * in o a known s a e when robo is disabled. Tha way when you
+ * enable he robo doesn' jus con inue doing wha i was doing before.
+ * BUT if ha 's wha he applica ion/ es ing requires han modify his accordingly */
+ _ alon.changeCon rolMode(TalonCon rolMode.Percen Vbus);
+ _ alon.se ( 0 );
+ /* clear our buffer and pu every hing in o a known s a e */
+ _example.rese ();
+ }
}
diff --git a/JAVA_MotionProfileExample/src/org/usfirst/frc/team3539/robot/instrumentation.java b/JAVA_MotionProfileExample/src/org/usfirst/frc/team3539/robot/instrumentation.java
index 2940b12..6ba2ea5 100644
--- a/JAVA_MotionProfileExample/src/org/usfirst/frc/team3539/robot/instrumentation.java
+++ b/JAVA_MotionProfileExample/src/org/usfirst/frc/team3539/robot/instrumentation.java
@@ -1,10 +1,10 @@
/**
- * Since this example focuses on Motion Control, lets print everything related to MP in a clean
- * format. Expect to see something like......
+ * Since his example focuses on Mo ion Con rol, le s prin every hing rela ed o MP in a clean
+ * forma . Expec o see some hing like......
*
* Hold 2048 0 0 1 5.0 0.0
* Hold 2048 0 0 1 5.0 0.0
- * outputEnable topBufferRem topBufferCnt btmBufferCnt IsValid HasUnderrun IsUnderrun IsLast VelOnly targPos targVel
+ * ou pu Enable opBufferRem opBufferCn b mBufferCn IsValid HasUnderrun IsUnderrun IsLas VelOnly argPos argVel
* Hold 2048 0 0 1 5.0 0.0
* Hold 2048 0 0 1 5.0 0.0
* Hold 2048 0 0 1 5.0 0.0
@@ -12,83 +12,83 @@
* Hold 2048 0 0 1 5.0 0.0
* Hold 2048 0 0 1 5.0 0.0
* Hold 2048 0 0 1 5.0 0.0
- * outputEnable topBufferRem topBufferCnt btmBufferCnt IsValid HasUnderrun IsUnderrun IsLast VelOnly targPos targVel
+ * ou pu Enable opBufferRem opBufferCn b mBufferCn IsValid HasUnderrun IsUnderrun IsLas VelOnly argPos argVel
* Hold 2048 0 0 1 5.0 0.0
* Hold 2048 0 0 1 5.0 0.0
* Hold 2048 0 0 1 5.0 0.0
*
- * ...where the columns are reprinted occasionally so you know whats up.
+ * ...where he columns are reprin ed occasionally so you know wha s up.
*
*
*
*/
-package org.usfirst.frc.team3539.robot;
-import com.ctre.CANTalon;
+package org.usfirs .frc. eam3539.robo ;
+impor com.c re.CANTalon;
-public class instrumentation {
+public class ins rumen a ion {
- static double timeout = 0;
- static int count = 0;
+ s a ic double imeou = 0;
+ s a ic in coun = 0;
- private static final String []_table = {" Dis "," En ","Hold "};
-
- public static void OnUnderrun() {
- System.out.format("%s\n", "UNDERRUN");
- }
- public static void OnNoProgress() {
- System.out.format("%s\n", "NOPROGRESS");
- }
- static private String StrOutputEnable(CANTalon.SetValueMotionProfile sv)
- {
- if(sv == null)
- return "null";
- if(sv.value > 3)
- return "Inval";
- return _table[sv.value];
- }
- /** round to six decimal places */
- static private double round(double toround)
- {
- long whole = (long)(toround * 1000000.0 + 0.5);
- return ((double)whole) * 0.000001;
- }
- public static void process(CANTalon.MotionProfileStatus status1) {
- double now = edu.wpi.first.wpilibj.Timer.getFPGATimestamp();
+ priva e s a ic final S ring []_ able = {" Dis "," En ","Hold "};
+
+ public s a ic void OnUnderrun() {
+ Sys em.ou .forma ("%s\n", "UNDERRUN");
+ }
+ public s a ic void OnNoProgress() {
+ Sys em.ou .forma ("%s\n", "NOPROGRESS");
+ }
+ s a ic priva e S ring S rOu pu Enable(CANTalon.Se ValueMo ionProfile sv)
+ {
+ if(sv == null)
+ re urn "null";
+ if(sv.value > 3)
+ re urn "Inval";
+ re urn _ able[sv.value];
+ }
+ /** round o six decimal places */
+ s a ic priva e double round(double oround)
+ {
+ long whole = (long)( oround * 1000000.0 + 0.5);
+ re urn ((double)whole) * 0.000001;
+ }
+ public s a ic void process(CANTalon.Mo ionProfileS a us s a us1) {
+ double now = edu.wpi.firs .wpilibj.Timer.ge FPGATimes amp();
- if((now-timeout) > 0.2){
- timeout = now;
- /* fire a loop every 200ms */
+ if((now- imeou ) > 0.2){
+ imeou = now;
+ /* fire a loop every 200ms */
- if(--count <= 0){
- count = 8;
- /* every 8 loops, print our columns */
-
- System.out.format("%-9s\t", "topCnt");
- System.out.format("%-9s\t", "btmCnt");
- System.out.format("%-9s\t", "set val");
- System.out.format("%-9s\t", "HasUnder");
- System.out.format("%-9s\t", "IsUnder");
- System.out.format("%-9s\t", "IsValid");
- System.out.format("%-9s\t", "IsLast");
- System.out.format("%-9s\t", "VelOnly");
- System.out.format("%-9s\t", "Pos");
- System.out.format("%-9s\t", "Vel");
+ if(--coun <= 0){
+ coun = 8;
+ /* every 8 loops, prin our columns */
+
+ Sys em.ou .forma ("%-9s\ ", " opCn ");
+ Sys em.ou .forma ("%-9s\ ", "b mCn ");
+ Sys em.ou .forma ("%-9s\ ", "se val");
+ Sys em.ou .forma ("%-9s\ ", "HasUnder");
+ Sys em.ou .forma ("%-9s\ ", "IsUnder");
+ Sys em.ou .forma ("%-9s\ ", "IsValid");
+ Sys em.ou .forma ("%-9s\ ", "IsLas ");
+ Sys em.ou .forma ("%-9s\ ", "VelOnly");
+ Sys em.ou .forma ("%-9s\ ", "Pos");
+ Sys em.ou .forma ("%-9s\ ", "Vel");
- System.out.format("\n");
- }
- /* every loop, print our values */
- System.out.format("%-9s\t", status1.topBufferCnt);
- System.out.format("%-9s\t", status1.btmBufferCnt);
- System.out.format("%-9s\t", StrOutputEnable(status1.outputEnable));
- System.out.format("%-9s\t", (status1.hasUnderrun ? "1" : ""));
- System.out.format("%-9s\t", (status1.isUnderrun ? "1" : ""));
- System.out.format("%-9s\t", (status1.activePointValid ? "1" : ""));
- System.out.format("%-9s\t", (status1.activePoint.isLastPoint ? "1" : ""));
- System.out.format("%-9s\t", (status1.activePoint.velocityOnly ? "1" : ""));
- System.out.format("%-9s\t", round(status1.activePoint.position));
- System.out.format("%-9s\t", round(status1.activePoint.velocity));
+ Sys em.ou .forma ("\n");
+ }
+ /* every loop, prin our values */
+ Sys em.ou .forma ("%-9s\ ", s a us1. opBufferCn );
+ Sys em.ou .forma ("%-9s\ ", s a us1.b mBufferCn );
+ Sys em.ou .forma ("%-9s\ ", S rOu pu Enable(s a us1.ou pu Enable));
+ Sys em.ou .forma ("%-9s\ ", (s a us1.hasUnderrun ? "1" : ""));
+ Sys em.ou .forma ("%-9s\ ", (s a us1.isUnderrun ? "1" : ""));
+ Sys em.ou .forma ("%-9s\ ", (s a us1.ac ivePoin Valid ? "1" : ""));
+ Sys em.ou .forma ("%-9s\ ", (s a us1.ac ivePoin .isLas Poin ? "1" : ""));
+ Sys em.ou .forma ("%-9s\ ", (s a us1.ac ivePoin .veloci yOnly ? "1" : ""));
+ Sys em.ou .forma ("%-9s\ ", round(s a us1.ac ivePoin .posi ion));
+ Sys em.ou .forma ("%-9s\ ", round(s a us1.ac ivePoin .veloci y));
- System.out.format("\n");
- }
- }
+ Sys em.ou .forma ("\n");
+ }
+ }
}
diff --git a/JAVA_Pigeon_StraightServo_Example/.classpath b/JAVA_Pigeon_StraightServo_Example/.classpath
index faa5b6f..3711bc8 100644
--- a/JAVA_Pigeon_StraightServo_Example/.classpath
+++ b/JAVA_Pigeon_StraightServo_Example/.classpath
@@ -1,12 +1,12 @@
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
diff --git a/JAVA_Pigeon_StraightServo_Example/.project b/JAVA_Pigeon_StraightServo_Example/.project
index bd88159..344d3e0 100644
--- a/JAVA_Pigeon_StraightServo_Example/.project
+++ b/JAVA_Pigeon_StraightServo_Example/.project
@@ -1,18 +1,18 @@
- JAVA_Pigeon_StraightServo_Example
-
-
-
-
-
- org.eclipse.jdt.core.javabuilder
-
-
-
-
-
- org.eclipse.jdt.core.javanature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ JAVA_Pigeon_StraightServo_Example
+
+
+
+
+
+ org.eclipse.jdt.core.javabuilder
+
+
+
+
+
+ org.eclipse.jdt.core.javanature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/JAVA_Pigeon_StraightServo_Example/src/org/usfirst/frc/team3539/robot/Robot.java b/JAVA_Pigeon_StraightServo_Example/src/org/usfirst/frc/team3539/robot/Robot.java
index 867c038..b9397a3 100644
--- a/JAVA_Pigeon_StraightServo_Example/src/org/usfirst/frc/team3539/robot/Robot.java
+++ b/JAVA_Pigeon_StraightServo_Example/src/org/usfirst/frc/team3539/robot/Robot.java
@@ -1,230 +1,230 @@
/**
- * A bare-bones test project using Pigeon for "Go-Straight" servo-ing.
- * The goal is for a basic robot with left/right side drive
- * to automatically hold a heading while driver is holding the top-left
- * shoulder button (Logitech Gamepad).
+ * A bare-bones es projec using Pigeon for "Go-S raigh " servo-ing.
+ * The goal is for a basic robo wi h lef /righ side drive
+ * o au oma ically hold a heading while driver is holding he op-lef
+ * shoulder bu on (Logi ech Gamepad).
*
- * If Pigeon is present on CANbus, or ribbon-cabled to a CAN-Talon, the robot will use the IMU to servo.
- * If Pigeon is not present, robot will simply apply the same throttle to both sides.
+ * If Pigeon is presen on CANbus, or ribbon-cabled o a CAN-Talon, he robo will use he IMU o servo.
+ * If Pigeon is no presen , robo will simply apply he same hro le o bo h sides.
*
- * When developing robot applications with IMUs, it's important to design in what happens if
- * the IMU is disconnected or un-powered.
+ * When developing robo applica ions wi h IMUs, i 's impor an o design in wha happens if
+ * he IMU is disconnec ed or un-powered.
*/
-package org.usfirst.frc.team3539.robot;
+package org.usfirs .frc. eam3539.robo ;
-import com.ctre.CANTalon;
-import com.ctre.PigeonImu;
-import com.ctre.PigeonImu.PigeonState;
+impor com.c re.CANTalon;
+impor com.c re.PigeonImu;
+impor com.c re.PigeonImu.PigeonS a e;
-import edu.wpi.first.wpilibj.IterativeRobot;
-import edu.wpi.first.wpilibj.Joystick;
-import edu.wpi.first.wpilibj.Joystick.AxisType;
+impor edu.wpi.firs .wpilibj.I era iveRobo ;
+impor edu.wpi.firs .wpilibj.Joys ick;
+impor edu.wpi.firs .wpilibj.Joys ick.AxisType;
-public class Robot extends IterativeRobot {
+public class Robo ex ends I era iveRobo {
- /* robot peripherals */
- CANTalon _leftFront;
- CANTalon _rightFront;
- CANTalon _leftRear;
- CANTalon _rightRear;
- CANTalon _spareTalon; /* spare talon, remove if not necessary, Pigeon can be placed on CANbus or plugged into a Talon. */
- PigeonImu _pidgey;
- Joystick _driveStick; /* Joystick object on USB port 1 */
-
- /** state for tracking whats controlling the drivetrain */
- enum GoStraight
- {
- Off, UsePigeon, SameThrottle
- };
-
- GoStraight _goStraight = GoStraight.Off;
-
- /*
- * Some gains for heading servo, these were tweaked by using the web-based
- * config (CAN Talon) and pressing gamepad button 6 to load them.
- */
- double kPgain = 0.04; /* percent throttle per degree of error */
- double kDgain = 0.0004; /* percent throttle per angular velocity dps */
- double kMaxCorrectionRatio = 0.30; /* cap corrective turning throttle to 30 percent of forward throttle */
- /** holds the current angle to servo to */
- double _targetAngle = 0;
- /** count loops to print every second or so */
- int _printLoops = 0;
-
- public Robot() {
- _leftFront = new CANTalon(6);
- _rightFront = new CANTalon(3);
- _leftRear = new CANTalon(4);
- _rightRear = new CANTalon(1);
- _spareTalon = new CANTalon(2);
-
- /* choose which cabling method for Pigeon */
- //_pidgey = new PigeonImu(0); /* Pigeon is on CANBus (powered from ~12V, and has a device ID of zero */
- _pidgey = new PigeonImu(_spareTalon); /* Pigeon is ribbon cabled to the specified CANTalon. */
-
- /* Define joystick being used at USB port #0 on the Drivers Station */
- _driveStick = new Joystick(0);
- }
-
- public void teleopInit() {
- _pidgey.SetFusedHeading(0.0); /* reset heading, angle measurement wraps at plus/minus 23,040 degrees (64 rotations) */
- _goStraight = GoStraight.Off;
+ /* robo peripherals */
+ CANTalon _lef Fron ;
+ CANTalon _righ Fron ;
+ CANTalon _lef Rear;
+ CANTalon _righ Rear;
+ CANTalon _spareTalon; /* spare alon, remove if no necessary, Pigeon can be placed on CANbus or plugged in o a Talon. */
+ PigeonImu _pidgey;
+ Joys ick _driveS ick; /* Joys ick objec on USB por 1 */
+
+ /** s a e for racking wha s con rolling he drive rain */
+ enum GoS raigh
+ {
+ Off, UsePigeon, SameThro le
+ };
+
+ GoS raigh _goS raigh = GoS raigh .Off;
+
+ /*
+ * Some gains for heading servo, hese were weaked by using he web-based
+ * config (CAN Talon) and pressing gamepad bu on 6 o load hem.
+ */
+ double kPgain = 0.04; /* percen hro le per degree of error */
+ double kDgain = 0.0004; /* percen hro le per angular veloci y dps */
+ double kMaxCorrec ionRa io = 0.30; /* cap correc ive urning hro le o 30 percen of forward hro le */
+ /** holds he curren angle o servo o */
+ double _ arge Angle = 0;
+ /** coun loops o prin every second or so */
+ in _prin Loops = 0;
+
+ public Robo () {
+ _lef Fron = new CANTalon(6);
+ _righ Fron = new CANTalon(3);
+ _lef Rear = new CANTalon(4);
+ _righ Rear = new CANTalon(1);
+ _spareTalon = new CANTalon(2);
+
+ /* choose which cabling me hod for Pigeon */
+ //_pidgey = new PigeonImu(0); /* Pigeon is on CANBus (powered from ~12V, and has a device ID of zero */
+ _pidgey = new PigeonImu(_spareTalon); /* Pigeon is ribbon cabled o he specified CANTalon. */
+
+ /* Define joys ick being used a USB por #0 on he Drivers S a ion */
+ _driveS ick = new Joys ick(0);
+ }
+
+ public void eleopIni () {
+ _pidgey.Se FusedHeading(0.0); /* rese heading, angle measuremen wraps a plus/minus 23,040 degrees (64 ro a ions) */
+ _goS raigh = GoS raigh .Off;
+ }
+
+ /**
+ * This func ion is called periodically during opera or con rol
+ */
+ public void eleopPeriodic() {
+ /* some emps for Pigeon API */
+ PigeonImu.GeneralS a us genS a us = new PigeonImu.GeneralS a us();
+ PigeonImu.FusionS a us fusionS a us = new PigeonImu.FusionS a us();
+ double [] xyz_dps = new double [3];
+ /* grab some inpu da a from Pigeon and gamepad*/
+ _pidgey.Ge GeneralS a us(genS a us);
+ _pidgey.Ge RawGyro(xyz_dps);
+ double curren Angle = _pidgey.Ge FusedHeading(fusionS a us);
+ boolean angleIsGood = (_pidgey.Ge S a e() == PigeonS a e.Ready) ? rue : false;
+ double curren AngularRa e = xyz_dps[2];
+ /* ge inpu from gamepad */
+ boolean userWan sGoS raigh = _driveS ick.ge RawBu on(5); /* op lef shoulder bu on */
+ double forwardThro le = _driveS ick.ge Axis(AxisType.kY) * -1.0; /* sign so ha posi ive is forward */
+ double urnThro le = _driveS ick.ge Axis(AxisType.kTwis ) * -1.0; /* sign so ha posi ive means urn lef */
+ /* deadbands so cen ering joys icks always resul s in zero ou pu */
+ forwardThro le = Db(forwardThro le);
+ urnThro le = Db( urnThro le);
+ /* simple s a e machine o upda e our goS raigh selec ion */
+ swi ch (_goS raigh ) {
+
+ /* go s raigh is off, be er check gamepad o see if we should enable he fea ure */
+ case Off:
+ if (userWan sGoS raigh == false) {
+ /* no hing o do */
+ } else if (angleIsGood == false) {
+ /* user wan s o servo bu Pigeon isn' connec ed? */
+ _goS raigh = GoS raigh .SameThro le; /* jus apply same hro le o bo h sides */
+ } else {
+ /* user wan s o servo, save he curren heading so we know where o servo o. */
+ _goS raigh = GoS raigh .UsePigeon;
+ _ arge Angle = curren Angle;
+ }
+ break;
+
+ /* we are servo-ing heading wi h Pigeon */
+ case UsePigeon:
+ if (userWan sGoS raigh == false) {
+ _goS raigh = GoS raigh .Off; /* user le go, urn off he fea ure */
+ } else if (angleIsGood == false) {
+ _goS raigh = GoS raigh .SameThro le; /* we were servoing wi h pidgy, bu we los connec ion? Check wiring and deviceID se up */
+ } else {
+ /* user s ill wan s o drive s raigh , keep doing i */
+ }
+ break;
+
+ /* we are simply applying he same hro le o bo h sides, apparen ly Pigeon is no connec ed */
+ case SameThro le:
+ if (userWan sGoS raigh == false) {
+ _goS raigh = GoS raigh .Off; /* user le go, urn off he fea ure */
+ } else {
+ /* user s ill wan s o drive s raigh , keep doing i */
+ }
+ break;
+ }
+
+ /* if we can servo wi h IMU, do he ma h here */
+ if (_goS raigh == GoS raigh .UsePigeon) {
+ /* very simple Propor ional and Deriva ive (PD) loop wi h a cap,
+ * replace wi h favori e close loop s ra egy or leverage fu ure Talon <=> Pigeon fea ures. */
+ urnThro le = (_ arge Angle - curren Angle) * kPgain - (curren AngularRa e) * kDgain;
+ /* he max correc ion is he forward hro le imes a scalar,
+ * This can be done a number of ways bu basically only apply small urning correc ion when we are moving slow
+ * and larger correc ion he fas er we move. O herwise you may need s iffer pgain a higher veloci ies. */
+ double maxThro = MaxCorrec ion(forwardThro le, kMaxCorrec ionRa io);
+ urnThro le = Cap( urnThro le, maxThro );
+ } else if (_goS raigh == GoS raigh .SameThro le) {
+ /* clear he urn hro le, jus apply same hro le o bo h sides */
+ urnThro le = 0;
+ } else {
+ /* do no hing */
+ }
+
+ /* posi ive urnThro le means urn o he lef , his can be replaced wi h ArcadeDrive objec , or eams drive rain objec */
+ double lef = forwardThro le - urnThro le;
+ double righ = forwardThro le + urnThro le;
+ lef = Cap(lef , 1.0);
+ righ = Cap(righ , 1.0);
+
+ /* my righ side mo ors need o drive nega ive o move robo forward */
+ _lef Fron .se (lef );
+ _lef Rear.se (lef );
+ _righ Fron .se (-1. * righ );
+ _righ Rear.se (-1. * righ );
+
+ /* some prin ing for easy debugging */
+ if (++_prin Loops > 50){
+ _prin Loops = 0;
+
+ Sys em.ou .prin ln("------------------------------------------");
+ Sys em.ou .prin ln("error: " + (_ arge Angle - curren Angle) );
+ Sys em.ou .prin ln("angle: "+ curren Angle);
+ Sys em.ou .prin ln("ra e: "+ curren AngularRa e);
+ Sys em.ou .prin ln("noMo ionBiasCoun : "+ genS a us.noMo ionBiasCoun );
+ Sys em.ou .prin ln(" empCompensa ionCoun : "+ genS a us. empCompensa ionCoun );
+ Sys em.ou .prin ln( angleIsGood ? "Angle is good" : "Angle is NOT GOOD");
+ Sys em.ou .prin ln("------------------------------------------");
+ }
+
+ /* press b n 6, op righ shoulder, o apply gains from webdash. This can
+ * be replaced wi h your favori e means of changing gains. */
+ if (_driveS ick.ge RawBu on(6)) {
+ Upda Gains();
+ }
+ }
+ /** @re urn 10% deadband */
+ double Db(double axisVal) {
+ if (axisVal < -0.10)
+ re urn axisVal;
+ if (axisVal > +0.10)
+ re urn axisVal;
+ re urn 0;
+ }
+ /** @param value o cap.
+ * @param peak posi ive double represen ing he maximum (peak) value.
+ * @re urn a capped value.
+ */
+ double Cap(double value, double peak) {
+ if (value < -peak)
+ re urn -peak;
+ if (value > +peak)
+ re urn +peak;
+ re urn value;
+ }
+ /**
+ * As a simple rick, le s ake he spare alon and use he web-based
+ * config o easily change he gains we use for he Pigeon servo.
+ * The alon isn' being used for closed-loop, jus use i as a convenien
+ * s orage for gains.
+ */
+ void Upda Gains() {
+ kPgain = _spareTalon.ge P();
+ kDgain = _spareTalon.ge D();
+ kMaxCorrec ionRa io = _spareTalon.ge F();
}
-
/**
- * This function is called periodically during operator control
+ * Given he robo forward hro le and ra io, re urn he max
+ * correc ive urning hro le o adjus for heading. This is
+ * a simple me hod of avoiding using differen gains for
+ * low speed, high speed, and no-speed (zero urns).
*/
- public void teleopPeriodic() {
- /* some temps for Pigeon API */
- PigeonImu.GeneralStatus genStatus = new PigeonImu.GeneralStatus();
- PigeonImu.FusionStatus fusionStatus = new PigeonImu.FusionStatus();
- double [] xyz_dps = new double [3];
- /* grab some input data from Pigeon and gamepad*/
- _pidgey.GetGeneralStatus(genStatus);
- _pidgey.GetRawGyro(xyz_dps);
- double currentAngle = _pidgey.GetFusedHeading(fusionStatus);
- boolean angleIsGood = (_pidgey.GetState() == PigeonState.Ready) ? true : false;
- double currentAngularRate = xyz_dps[2];
- /* get input from gamepad */
- boolean userWantsGoStraight = _driveStick.getRawButton(5); /* top left shoulder button */
- double forwardThrottle = _driveStick.getAxis(AxisType.kY) * -1.0; /* sign so that positive is forward */
- double turnThrottle = _driveStick.getAxis(AxisType.kTwist) * -1.0; /* sign so that positive means turn left */
- /* deadbands so centering joysticks always results in zero output */
- forwardThrottle = Db(forwardThrottle);
- turnThrottle = Db(turnThrottle);
- /* simple state machine to update our goStraight selection */
- switch (_goStraight) {
-
- /* go straight is off, better check gamepad to see if we should enable the feature */
- case Off:
- if (userWantsGoStraight == false) {
- /* nothing to do */
- } else if (angleIsGood == false) {
- /* user wants to servo but Pigeon isn't connected? */
- _goStraight = GoStraight.SameThrottle; /* just apply same throttle to both sides */
- } else {
- /* user wants to servo, save the current heading so we know where to servo to. */
- _goStraight = GoStraight.UsePigeon;
- _targetAngle = currentAngle;
- }
- break;
-
- /* we are servo-ing heading with Pigeon */
- case UsePigeon:
- if (userWantsGoStraight == false) {
- _goStraight = GoStraight.Off; /* user let go, turn off the feature */
- } else if (angleIsGood == false) {
- _goStraight = GoStraight.SameThrottle; /* we were servoing with pidgy, but we lost connection? Check wiring and deviceID setup */
- } else {
- /* user still wants to drive straight, keep doing it */
- }
- break;
-
- /* we are simply applying the same throttle to both sides, apparently Pigeon is not connected */
- case SameThrottle:
- if (userWantsGoStraight == false) {
- _goStraight = GoStraight.Off; /* user let go, turn off the feature */
- } else {
- /* user still wants to drive straight, keep doing it */
- }
- break;
- }
-
- /* if we can servo with IMU, do the math here */
- if (_goStraight == GoStraight.UsePigeon) {
- /* very simple Proportional and Derivative (PD) loop with a cap,
- * replace with favorite close loop strategy or leverage future Talon <=> Pigeon features. */
- turnThrottle = (_targetAngle - currentAngle) * kPgain - (currentAngularRate) * kDgain;
- /* the max correction is the forward throttle times a scalar,
- * This can be done a number of ways but basically only apply small turning correction when we are moving slow
- * and larger correction the faster we move. Otherwise you may need stiffer pgain at higher velocities. */
- double maxThrot = MaxCorrection(forwardThrottle, kMaxCorrectionRatio);
- turnThrottle = Cap(turnThrottle, maxThrot);
- } else if (_goStraight == GoStraight.SameThrottle) {
- /* clear the turn throttle, just apply same throttle to both sides */
- turnThrottle = 0;
- } else {
- /* do nothing */
- }
-
- /* positive turnThrottle means turn to the left, this can be replaced with ArcadeDrive object, or teams drivetrain object */
- double left = forwardThrottle - turnThrottle;
- double right = forwardThrottle + turnThrottle;
- left = Cap(left, 1.0);
- right = Cap(right, 1.0);
-
- /* my right side motors need to drive negative to move robot forward */
- _leftFront.set(left);
- _leftRear.set(left);
- _rightFront.set(-1. * right);
- _rightRear.set(-1. * right);
-
- /* some printing for easy debugging */
- if (++_printLoops > 50){
- _printLoops = 0;
-
- System.out.println("------------------------------------------");
- System.out.println("error: " + (_targetAngle - currentAngle) );
- System.out.println("angle: "+ currentAngle);
- System.out.println("rate: "+ currentAngularRate);
- System.out.println("noMotionBiasCount: "+ genStatus.noMotionBiasCount);
- System.out.println("tempCompensationCount: "+ genStatus.tempCompensationCount);
- System.out.println( angleIsGood ? "Angle is good" : "Angle is NOT GOOD");
- System.out.println("------------------------------------------");
- }
-
- /* press btn 6, top right shoulder, to apply gains from webdash. This can
- * be replaced with your favorite means of changing gains. */
- if (_driveStick.getRawButton(6)) {
- UpdatGains();
- }
+ double MaxCorrec ion(double forwardThro , double scalor) {
+ /* make i posi ive */
+ if(forwardThro < 0) {forwardThro = -forwardThro ;}
+ /* max correc ion is he curren forward hro le scaled down */
+ forwardThro *= scalor;
+ /* ensure caller is allowed a leas 10% hro le,
+ * regardless of forward hro le */
+ if(forwardThro < 0.10)
+ re urn 0.10;
+ re urn forwardThro ;
}
- /** @return 10% deadband */
- double Db(double axisVal) {
- if (axisVal < -0.10)
- return axisVal;
- if (axisVal > +0.10)
- return axisVal;
- return 0;
- }
- /** @param value to cap.
- * @param peak positive double representing the maximum (peak) value.
- * @return a capped value.
- */
- double Cap(double value, double peak) {
- if (value < -peak)
- return -peak;
- if (value > +peak)
- return +peak;
- return value;
- }
- /**
- * As a simple trick, lets take the spare talon and use the web-based
- * config to easily change the gains we use for the Pigeon servo.
- * The talon isn't being used for closed-loop, just use it as a convenient
- * storage for gains.
- */
- void UpdatGains() {
- kPgain = _spareTalon.getP();
- kDgain = _spareTalon.getD();
- kMaxCorrectionRatio = _spareTalon.getF();
- }
- /**
- * Given the robot forward throttle and ratio, return the max
- * corrective turning throttle to adjust for heading. This is
- * a simple method of avoiding using different gains for
- * low speed, high speed, and no-speed (zero turns).
- */
- double MaxCorrection(double forwardThrot, double scalor) {
- /* make it positive */
- if(forwardThrot < 0) {forwardThrot = -forwardThrot;}
- /* max correction is the current forward throttle scaled down */
- forwardThrot *= scalor;
- /* ensure caller is allowed at least 10% throttle,
- * regardless of forward throttle */
- if(forwardThrot < 0.10)
- return 0.10;
- return forwardThrot;
- }
}
diff --git a/JAVA_PositionClosedLoop/.classpath b/JAVA_PositionClosedLoop/.classpath
index ebdff27..bff10ac 100644
--- a/JAVA_PositionClosedLoop/.classpath
+++ b/JAVA_PositionClosedLoop/.classpath
@@ -1,13 +1,13 @@
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
diff --git a/JAVA_PositionClosedLoop/.project b/JAVA_PositionClosedLoop/.project
index 2486367..2ee0ee9 100644
--- a/JAVA_PositionClosedLoop/.project
+++ b/JAVA_PositionClosedLoop/.project
@@ -1,18 +1,18 @@
- java50_VelocityClosedLoop
-
-
-
-
-
- org.eclipse.jdt.core.javabuilder
-
-
-
-
-
- org.eclipse.jdt.core.javanature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ java50_VelocityClosedLoop
+
+
+
+
+
+ org.eclipse.jdt.core.javabuilder
+
+
+
+
+
+ org.eclipse.jdt.core.javanature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/JAVA_PositionClosedLoop/src/org/usfirst/frc/team469/robot/Robot.java b/JAVA_PositionClosedLoop/src/org/usfirst/frc/team469/robot/Robot.java
index 638701b..fb2ae34 100644
--- a/JAVA_PositionClosedLoop/src/org/usfirst/frc/team469/robot/Robot.java
+++ b/JAVA_PositionClosedLoop/src/org/usfirst/frc/team469/robot/Robot.java
@@ -1,110 +1,110 @@
/**
- * Example demonstrating the Position closed-loop servo.
- * Tested with Logitech F350 USB Gamepad inserted into Driver Station]
+ * Example demons ra ing he Posi ion closed-loop servo.
+ * Tes ed wi h Logi ech F350 USB Gamepad inser ed in o Driver S a ion]
*
- * Be sure to select the correct feedback sensor using SetFeedbackDevice() below.
+ * Be sure o selec he correc feedback sensor using Se FeedbackDevice() below.
*
- * After deploying/debugging this to your RIO, first use the left Y-stick
- * to throttle the Talon manually. This will confirm your hardware setup.
- * Be sure to confirm that when the Talon is driving forward (green) the
- * position sensor is moving in a positive direction. If this is not the cause
- * flip the boolean input to the reverseSensor() call below.
+ * Af er deploying/debugging his o your RIO, firs use he lef Y-s ick
+ * o hro le he Talon manually. This will confirm your hardware se up.
+ * Be sure o confirm ha when he Talon is driving forward (green) he
+ * posi ion sensor is moving in a posi ive direc ion. If his is no he cause
+ * flip he boolean inpu o he reverseSensor() call below.
*
- * Once you've ensured your feedback device is in-phase with the motor,
- * use the button shortcuts to servo to target position.
+ * Once you've ensured your feedback device is in-phase wi h he mo or,
+ * use he bu on shor cu s o servo o arge posi ion.
*
- * Tweak the PID gains accordingly.
+ * Tweak he PID gains accordingly.
*/
-package org.usfirst.frc.team469.robot;
-import com.ctre.CANTalon;
-import edu.wpi.first.wpilibj.IterativeRobot;
-import edu.wpi.first.wpilibj.Joystick;
-import edu.wpi.first.wpilibj.Joystick.AxisType;
-import com.ctre.CANTalon.FeedbackDevice;
-import com.ctre.CANTalon.StatusFrameRate;
-import com.ctre.CANTalon.TalonControlMode;
+package org.usfirs .frc. eam469.robo ;
+impor com.c re.CANTalon;
+impor edu.wpi.firs .wpilibj.I era iveRobo ;
+impor edu.wpi.firs .wpilibj.Joys ick;
+impor edu.wpi.firs .wpilibj.Joys ick.AxisType;
+impor com.c re.CANTalon.FeedbackDevice;
+impor com.c re.CANTalon.S a usFrameRa e;
+impor com.c re.CANTalon.TalonCon rolMode;
-public class Robot extends IterativeRobot {
+public class Robo ex ends I era iveRobo {
- CANTalon _talon = new CANTalon(0);
- Joystick _joy = new Joystick(0);
- StringBuilder _sb = new StringBuilder();
- int _loops = 0;
- boolean _lastButton1 = false;
- /** save the target position to servo to */
- double targetPositionRotations;
-
- public void robotInit() {
- /* lets grab the 360 degree position of the MagEncoder's absolute position */
- int absolutePosition = _talon.getPulseWidthPosition() & 0xFFF; /* mask out the bottom12 bits, we don't care about the wrap arounds */
- /* use the low level API to set the quad encoder signal */
- _talon.setEncPosition(absolutePosition);
+ CANTalon _ alon = new CANTalon(0);
+ Joys ick _joy = new Joys ick(0);
+ S ringBuilder _sb = new S ringBuilder();
+ in _loops = 0;
+ boolean _las Bu on1 = false;
+ /** save he arge posi ion o servo o */
+ double arge Posi ionRo a ions;
+
+ public void robo Ini () {
+ /* le s grab he 360 degree posi ion of he MagEncoder's absolu e posi ion */
+ in absolu ePosi ion = _ alon.ge PulseWid hPosi ion() & 0xFFF; /* mask ou he bo om12 bi s, we don' care abou he wrap arounds */
+ /* use he low level API o se he quad encoder signal */
+ _ alon.se EncPosi ion(absolu ePosi ion);
- /* choose the sensor and sensor direction */
- _talon.setFeedbackDevice(FeedbackDevice.CtreMagEncoder_Relative);
- _talon.reverseSensor(false);
- //_talon.configEncoderCodesPerRev(XXX), // if using FeedbackDevice.QuadEncoder
- //_talon.configPotentiometerTurns(XXX), // if using FeedbackDevice.AnalogEncoder or AnalogPot
+ /* choose he sensor and sensor direc ion */
+ _ alon.se FeedbackDevice(FeedbackDevice.C reMagEncoder_Rela ive);
+ _ alon.reverseSensor(false);
+ //_ alon.configEncoderCodesPerRev(XXX), // if using FeedbackDevice.QuadEncoder
+ //_ alon.configPo en iome erTurns(XXX), // if using FeedbackDevice.AnalogEncoder or AnalogPo
- /* set the peak and nominal outputs, 12V means full */
- _talon.configNominalOutputVoltage(+0f, -0f);
- _talon.configPeakOutputVoltage(+12f, -12f);
- /* set the allowable closed-loop error,
- * Closed-Loop output will be neutral within this range.
- * See Table in Section 17.2.1 for native units per rotation.
+ /* se he peak and nominal ou pu s, 12V means full */
+ _ alon.configNominalOu pu Vol age(+0f, -0f);
+ _ alon.configPeakOu pu Vol age(+12f, -12f);
+ /* se he allowable closed-loop error,
+ * Closed-Loop ou pu will be neu ral wi hin his range.
+ * See Table in Sec ion 17.2.1 for na ive uni s per ro a ion.
*/
- _talon.setAllowableClosedLoopErr(0); /* always servo */
- /* set closed loop gains in slot0 */
- _talon.setProfile(0);
- _talon.setF(0.0);
- _talon.setP(0.1);
- _talon.setI(0.0);
- _talon.setD(0.0);
+ _ alon.se AllowableClosedLoopErr(0); /* always servo */
+ /* se closed loop gains in slo 0 */
+ _ alon.se Profile(0);
+ _ alon.se F(0.0);
+ _ alon.se P(0.1);
+ _ alon.se I(0.0);
+ _ alon.se D(0.0);
- }
+ }
/**
- * This function is called periodically during operator control
+ * This func ion is called periodically during opera or con rol
*/
- public void teleopPeriodic() {
- /* get gamepad axis */
- double leftYstick = _joy.getAxis(AxisType.kY);
- double motorOutput = _talon.getOutputVoltage() / _talon.getBusVoltage();
- boolean button1 = _joy.getRawButton(1);
- boolean button2 = _joy.getRawButton(2);
- /* prepare line to print */
- _sb.append("\tout:");
- _sb.append(motorOutput);
- _sb.append("\tpos:");
- _sb.append(_talon.getPosition() );
- /* on button1 press enter closed-loop mode on target position */
- if(!_lastButton1 && button1) {
- /* Position mode - button just pressed */
- targetPositionRotations = leftYstick * 50.0; /* 50 Rotations in either direction */
- _talon.changeControlMode(TalonControlMode.Position);
- _talon.set(targetPositionRotations); /* 50 rotations in either direction */
+ public void eleopPeriodic() {
+ /* ge gamepad axis */
+ double lef Ys ick = _joy.ge Axis(AxisType.kY);
+ double mo orOu pu = _ alon.ge Ou pu Vol age() / _ alon.ge BusVol age();
+ boolean bu on1 = _joy.ge RawBu on(1);
+ boolean bu on2 = _joy.ge RawBu on(2);
+ /* prepare line o prin */
+ _sb.append("\ ou :");
+ _sb.append(mo orOu pu );
+ _sb.append("\ pos:");
+ _sb.append(_ alon.ge Posi ion() );
+ /* on bu on1 press en er closed-loop mode on arge posi ion */
+ if(!_las Bu on1 && bu on1) {
+ /* Posi ion mode - bu on jus pressed */
+ arge Posi ionRo a ions = lef Ys ick * 50.0; /* 50 Ro a ions in ei her direc ion */
+ _ alon.changeCon rolMode(TalonCon rolMode.Posi ion);
+ _ alon.se ( arge Posi ionRo a ions); /* 50 ro a ions in ei her direc ion */
}
- /* on button2 just straight drive */
- if(button2) {
- /* Percent voltage mode */
- _talon.changeControlMode(TalonControlMode.PercentVbus);
- _talon.set(leftYstick);
+ /* on bu on2 jus s raigh drive */
+ if(bu on2) {
+ /* Percen vol age mode */
+ _ alon.changeCon rolMode(TalonCon rolMode.Percen Vbus);
+ _ alon.se (lef Ys ick);
}
- /* if Talon is in position closed-loop, print some more info */
- if( _talon.getControlMode() == TalonControlMode.Position) {
- /* append more signals to print when in speed mode. */
- _sb.append("\terrNative:");
- _sb.append(_talon.getClosedLoopError());
- _sb.append("\ttrg:");
- _sb.append(targetPositionRotations);
+ /* if Talon is in posi ion closed-loop, prin some more info */
+ if( _ alon.ge Con rolMode() == TalonCon rolMode.Posi ion) {
+ /* append more signals o prin when in speed mode. */
+ _sb.append("\ errNa ive:");
+ _sb.append(_ alon.ge ClosedLoopError());
+ _sb.append("\ rg:");
+ _sb.append( arge Posi ionRo a ions);
}
- /* print every ten loops, printing too much too fast is generally bad for performance */
+ /* prin every en loops, prin ing oo much oo fas is generally bad for performance */
if(++_loops >= 10) {
- _loops = 0;
- System.out.println(_sb.toString());
+ _loops = 0;
+ Sys em.ou .prin ln(_sb. oS ring());
}
- _sb.setLength(0);
- /* save button state for on press detect */
- _lastButton1 = button1;
+ _sb.se Leng h(0);
+ /* save bu on s a e for on press de ec */
+ _las Bu on1 = bu on1;
}
}
diff --git a/JAVA_Six_CANTalon_ArcadeDrive/.project b/JAVA_Six_CANTalon_ArcadeDrive/.project
index 831ea88..9103111 100644
--- a/JAVA_Six_CANTalon_ArcadeDrive/.project
+++ b/JAVA_Six_CANTalon_ArcadeDrive/.project
@@ -1,18 +1,18 @@
- JAVA_Six_CANTalon_ArcadeDrive
-
-
-
-
-
- org.eclipse.jdt.core.javabuilder
-
-
-
-
-
- org.eclipse.jdt.core.javanature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ JAVA_Six_CANTalon_ArcadeDrive
+
+
+
+
+
+ org.eclipse.jdt.core.javabuilder
+
+
+
+
+
+ org.eclipse.jdt.core.javanature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/JAVA_Six_CANTalon_ArcadeDrive/org/usfirst/frc/team469/robot/Robot.java b/JAVA_Six_CANTalon_ArcadeDrive/org/usfirst/frc/team469/robot/Robot.java
index de9ccc4..3a2e583 100644
--- a/JAVA_Six_CANTalon_ArcadeDrive/org/usfirst/frc/team469/robot/Robot.java
+++ b/JAVA_Six_CANTalon_ArcadeDrive/org/usfirst/frc/team469/robot/Robot.java
@@ -1,58 +1,58 @@
-package org.usfirst.frc.team469.robot;
-import com.ctre.CANTalon;
-import edu.wpi.first.wpilibj.IterativeRobot;
-import edu.wpi.first.wpilibj.Joystick;
-import edu.wpi.first.wpilibj.Joystick.AxisType;
-import edu.wpi.first.wpilibj.RobotDrive;
-import edu.wpi.first.wpilibj.RobotDrive.MotorType;
-import com.ctre.CANTalon.TalonControlMode;
+package org.usfirs .frc. eam469.robo ;
+impor com.c re.CANTalon;
+impor edu.wpi.firs .wpilibj.I era iveRobo ;
+impor edu.wpi.firs .wpilibj.Joys ick;
+impor edu.wpi.firs .wpilibj.Joys ick.AxisType;
+impor edu.wpi.firs .wpilibj.Robo Drive;
+impor edu.wpi.firs .wpilibj.Robo Drive.Mo orType;
+impor com.c re.CANTalon.TalonCon rolMode;
/**
- * The VM is configured to automatically run this class, and to call the
- * functions corresponding to each mode, as described in the IterativeRobot
- * documentation. If you change the name of this class or the package after
- * creating this project, you must also update the manifest file in the resource
- * directory.
+ * The VM is configured o au oma ically run his class, and o call he
+ * func ions corresponding o each mode, as described in he I era iveRobo
+ * documen a ion. If you change he name of his class or he package af er
+ * crea ing his projec , you mus also upda e he manifes file in he resource
+ * direc ory.
*/
-public class Robot extends IterativeRobot {
+public class Robo ex ends I era iveRobo {
- /* talons for arcade drive */
- CANTalon _frontLeftMotor = new CANTalon(11); /* device IDs here (1 of 2) */
- CANTalon _rearLeftMotor = new CANTalon(13);
- CANTalon _frontRightMotor = new CANTalon(14);
- CANTalon _rearRightMotor = new CANTalon(15);
+ /* alons for arcade drive */
+ CANTalon _fron Lef Mo or = new CANTalon(11); /* device IDs here (1 of 2) */
+ CANTalon _rearLef Mo or = new CANTalon(13);
+ CANTalon _fron Righ Mo or = new CANTalon(14);
+ CANTalon _rearRigh Mo or = new CANTalon(15);
- /* extra talons for six motor drives */
- CANTalon _leftSlave = new CANTalon(16);
- CANTalon _rightSlave = new CANTalon(17);
-
- RobotDrive _drive = new RobotDrive(_frontLeftMotor, _rearLeftMotor, _frontRightMotor, _rearRightMotor);
-
- Joystick _joy = new Joystick(0);
+ /* ex ra alons for six mo or drives */
+ CANTalon _lef Slave = new CANTalon(16);
+ CANTalon _righ Slave = new CANTalon(17);
+
+ Robo Drive _drive = new Robo Drive(_fron Lef Mo or, _rearLef Mo or, _fron Righ Mo or, _rearRigh Mo or);
+
+ Joys ick _joy = new Joys ick(0);
/**
- * This function is run when the robot is first started up and should be
- * used for any initialization code.
+ * This func ion is run when he robo is firs s ar ed up and should be
+ * used for any ini ializa ion code.
*/
- public void robotInit() {
- /* take our extra talons and just have them follow the Talons updated in arcadeDrive */
- _leftSlave.changeControlMode(TalonControlMode.Follower);
- _rightSlave.changeControlMode(TalonControlMode.Follower);
- _leftSlave.set(11); /* device IDs here (2 of 2) */
- _rightSlave.set(14);
-
- /* the Talons on the left-side of my robot needs to drive reverse(red) to move robot forward.
- * Since _leftSlave just follows frontLeftMotor, no need to invert it anywhere. */
- _drive.setInvertedMotor(MotorType.kFrontLeft, true);
- _drive.setInvertedMotor(MotorType.kRearLeft, true);
+ public void robo Ini () {
+ /* ake our ex ra alons and jus have hem follow he Talons upda ed in arcadeDrive */
+ _lef Slave.changeCon rolMode(TalonCon rolMode.Follower);
+ _righ Slave.changeCon rolMode(TalonCon rolMode.Follower);
+ _lef Slave.se (11); /* device IDs here (2 of 2) */
+ _righ Slave.se (14);
+
+ /* he Talons on he lef -side of my robo needs o drive reverse(red) o move robo forward.
+ * Since _lef Slave jus follows fron Lef Mo or, no need o inver i anywhere. */
+ _drive.se Inver edMo or(Mo orType.kFron Lef , rue);
+ _drive.se Inver edMo or(Mo orType.kRearLef , rue);
}
/**
- * This function is called periodically during operator control
+ * This func ion is called periodically during opera or con rol
*/
- public void teleopPeriodic() {
- double forward = _joy.getRawAxis(1); // logitech gampad left X, positive is forward
- double turn = _joy.getRawAxis(2); //logitech gampad right X, positive means turn right
- _drive.arcadeDrive(forward, turn);
+ public void eleopPeriodic() {
+ double forward = _joy.ge RawAxis(1); // logi ech gampad lef X, posi ive is forward
+ double urn = _joy.ge RawAxis(2); //logi ech gampad righ X, posi ive means urn righ
+ _drive.arcadeDrive(forward, urn);
}
}
diff --git a/JAVA_VelocityClosedLoop/.classpath b/JAVA_VelocityClosedLoop/.classpath
index 9e787aa..dea58b7 100644
--- a/JAVA_VelocityClosedLoop/.classpath
+++ b/JAVA_VelocityClosedLoop/.classpath
@@ -1,11 +1,11 @@
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
diff --git a/JAVA_VelocityClosedLoop/.project b/JAVA_VelocityClosedLoop/.project
index 2486367..2ee0ee9 100644
--- a/JAVA_VelocityClosedLoop/.project
+++ b/JAVA_VelocityClosedLoop/.project
@@ -1,18 +1,18 @@
- java50_VelocityClosedLoop
-
-
-
-
-
- org.eclipse.jdt.core.javabuilder
-
-
-
-
-
- org.eclipse.jdt.core.javanature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ java50_VelocityClosedLoop
+
+
+
+
+
+ org.eclipse.jdt.core.javabuilder
+
+
+
+
+
+ org.eclipse.jdt.core.javanature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/JAVA_VelocityClosedLoop/src/org/usfirst/frc/team469/robot/Robot.java b/JAVA_VelocityClosedLoop/src/org/usfirst/frc/team469/robot/Robot.java
index 67a6ae7..ead4f9e 100644
--- a/JAVA_VelocityClosedLoop/src/org/usfirst/frc/team469/robot/Robot.java
+++ b/JAVA_VelocityClosedLoop/src/org/usfirst/frc/team469/robot/Robot.java
@@ -1,86 +1,86 @@
/**
- * Example demonstrating the velocity closed-loop servo.
- * Tested with Logitech F350 USB Gamepad inserted into Driver Station]
+ * Example demons ra ing he veloci y closed-loop servo.
+ * Tes ed wi h Logi ech F350 USB Gamepad inser ed in o Driver S a ion]
*
- * Be sure to select the correct feedback sensor using SetFeedbackDevice() below.
+ * Be sure o selec he correc feedback sensor using Se FeedbackDevice() below.
*
- * After deploying/debugging this to your RIO, first use the left Y-stick
- * to throttle the Talon manually. This will confirm your hardware setup.
- * Be sure to confirm that when the Talon is driving forward (green) the
- * position sensor is moving in a positive direction. If this is not the cause
- * flip the boolena input to the SetSensorDirection() call below.
+ * Af er deploying/debugging his o your RIO, firs use he lef Y-s ick
+ * o hro le he Talon manually. This will confirm your hardware se up.
+ * Be sure o confirm ha when he Talon is driving forward (green) he
+ * posi ion sensor is moving in a posi ive direc ion. If his is no he cause
+ * flip he boolena inpu o he Se SensorDirec ion() call below.
*
- * Once you've ensured your feedback device is in-phase with the motor,
- * use the button shortcuts to servo to target velocity.
+ * Once you've ensured your feedback device is in-phase wi h he mo or,
+ * use he bu on shor cu s o servo o arge veloci y.
*
- * Tweak the PID gains accordingly.
+ * Tweak he PID gains accordingly.
*/
-package org.usfirst.frc.team469.robot;
-import com.ctre.CANTalon;
-import edu.wpi.first.wpilibj.IterativeRobot;
-import edu.wpi.first.wpilibj.Joystick;
-import edu.wpi.first.wpilibj.Joystick.AxisType;
-import com.ctre.CANTalon.FeedbackDevice;
-import com.ctre.CANTalon.TalonControlMode;
+package org.usfirs .frc. eam469.robo ;
+impor com.c re.CANTalon;
+impor edu.wpi.firs .wpilibj.I era iveRobo ;
+impor edu.wpi.firs .wpilibj.Joys ick;
+impor edu.wpi.firs .wpilibj.Joys ick.AxisType;
+impor com.c re.CANTalon.FeedbackDevice;
+impor com.c re.CANTalon.TalonCon rolMode;
-public class Robot extends IterativeRobot {
+public class Robo ex ends I era iveRobo {
- CANTalon _talon = new CANTalon(0);
- Joystick _joy = new Joystick(0);
- StringBuilder _sb = new StringBuilder();
- int _loops = 0;
-
- public void robotInit() {
- /* first choose the sensor */
- _talon.setFeedbackDevice(FeedbackDevice.CtreMagEncoder_Relative);
- _talon.reverseSensor(false);
- //_talon.configEncoderCodesPerRev(XXX), // if using FeedbackDevice.QuadEncoder
- //_talon.configPotentiometerTurns(XXX), // if using FeedbackDevice.AnalogEncoder or AnalogPot
+ CANTalon _ alon = new CANTalon(0);
+ Joys ick _joy = new Joys ick(0);
+ S ringBuilder _sb = new S ringBuilder();
+ in _loops = 0;
+
+ public void robo Ini () {
+ /* firs choose he sensor */
+ _ alon.se FeedbackDevice(FeedbackDevice.C reMagEncoder_Rela ive);
+ _ alon.reverseSensor(false);
+ //_ alon.configEncoderCodesPerRev(XXX), // if using FeedbackDevice.QuadEncoder
+ //_ alon.configPo en iome erTurns(XXX), // if using FeedbackDevice.AnalogEncoder or AnalogPo
- /* set the peak and nominal outputs, 12V means full */
- _talon.configNominalOutputVoltage(+0.0f, -0.0f);
- _talon.configPeakOutputVoltage(+12.0f, -12.0f);
- /* set closed loop gains in slot0 */
- _talon.setProfile(0);
- _talon.setF(0.1097);
- _talon.setP(0.22);
- _talon.setI(0);
- _talon.setD(0);
- }
+ /* se he peak and nominal ou pu s, 12V means full */
+ _ alon.configNominalOu pu Vol age(+0.0f, -0.0f);
+ _ alon.configPeakOu pu Vol age(+12.0f, -12.0f);
+ /* se closed loop gains in slo 0 */
+ _ alon.se Profile(0);
+ _ alon.se F(0.1097);
+ _ alon.se P(0.22);
+ _ alon.se I(0);
+ _ alon.se D(0);
+ }
/**
- * This function is called periodically during operator control
+ * This func ion is called periodically during opera or con rol
*/
- public void teleopPeriodic() {
- /* get gamepad axis */
- double leftYstick = _joy.getAxis(AxisType.kY);
- double motorOutput = _talon.getOutputVoltage() / _talon.getBusVoltage();
- /* prepare line to print */
- _sb.append("\tout:");
- _sb.append(motorOutput);
- _sb.append("\tspd:");
- _sb.append(_talon.getSpeed() );
+ public void eleopPeriodic() {
+ /* ge gamepad axis */
+ double lef Ys ick = _joy.ge Axis(AxisType.kY);
+ double mo orOu pu = _ alon.ge Ou pu Vol age() / _ alon.ge BusVol age();
+ /* prepare line o prin */
+ _sb.append("\ ou :");
+ _sb.append(mo orOu pu );
+ _sb.append("\ spd:");
+ _sb.append(_ alon.ge Speed() );
- if(_joy.getRawButton(1)){
- /* Speed mode */
- double targetSpeed = leftYstick * 1500.0; /* 1500 RPM in either direction */
- _talon.changeControlMode(TalonControlMode.Speed);
- _talon.set(targetSpeed); /* 1500 RPM in either direction */
+ if(_joy.ge RawBu on(1)){
+ /* Speed mode */
+ double arge Speed = lef Ys ick * 1500.0; /* 1500 RPM in ei her direc ion */
+ _ alon.changeCon rolMode(TalonCon rolMode.Speed);
+ _ alon.se ( arge Speed); /* 1500 RPM in ei her direc ion */
- /* append more signals to print when in speed mode. */
- _sb.append("\terr:");
- _sb.append(_talon.getClosedLoopError());
- _sb.append("\ttrg:");
- _sb.append(targetSpeed);
+ /* append more signals o prin when in speed mode. */
+ _sb.append("\ err:");
+ _sb.append(_ alon.ge ClosedLoopError());
+ _sb.append("\ rg:");
+ _sb.append( arge Speed);
} else {
- /* Percent voltage mode */
- _talon.changeControlMode(TalonControlMode.PercentVbus);
- _talon.set(leftYstick);
+ /* Percen vol age mode */
+ _ alon.changeCon rolMode(TalonCon rolMode.Percen Vbus);
+ _ alon.se (lef Ys ick);
}
if(++_loops >= 10) {
- _loops = 0;
- System.out.println(_sb.toString());
+ _loops = 0;
+ Sys em.ou .prin ln(_sb. oS ring());
}
- _sb.setLength(0);
+ _sb.se Leng h(0);
}
}
diff --git a/LabVIEW Motion Magic Example/FRC Simulated.xml b/LabVIEW Motion Magic Example/FRC Simulated.xml
index d99a6ad..97bb019 100644
--- a/LabVIEW Motion Magic Example/FRC Simulated.xml
+++ b/LabVIEW Motion Magic Example/FRC Simulated.xml
@@ -7622,14 +7622,14 @@
Parameters
-[FMax] 20
-[Fudge Factor] 1
-[Bounce] 0
-[CFM] 0.00001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.6
-[Stop CFM] 0.00001
+[FMax] 20
+[Fudge Factor] 1
+[Bounce] 0
+[CFM] 0.00001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.6
+[Stop CFM] 0.00001
Draw Mode
@@ -7747,14 +7747,14 @@
Parameters
-[FMax] 20
-[Fudge Factor] 1
-[Bounce] 0
-[CFM] 0.00001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.6
-[Stop CFM] 0.00001
+[FMax] 20
+[Fudge Factor] 1
+[Bounce] 0
+[CFM] 0.00001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.6
+[Stop CFM] 0.00001
Draw Mode
@@ -7872,14 +7872,14 @@
Parameters
-[FMax] 20
-[Fudge Factor] 1
-[Bounce] 0
-[CFM] 0.00001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.6
-[Stop CFM] 0.00001
+[FMax] 20
+[Fudge Factor] 1
+[Bounce] 0
+[CFM] 0.00001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.6
+[Stop CFM] 0.00001
Draw Mode
@@ -7997,14 +7997,14 @@
Parameters
-[FMax] 20
-[Fudge Factor] 1
-[Bounce] 0
-[CFM] 0.00001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.6
-[Stop CFM] 0.00001
+[FMax] 20
+[Fudge Factor] 1
+[Bounce] 0
+[CFM] 0.00001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.6
+[Stop CFM] 0.00001
Draw Mode
@@ -8122,7 +8122,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8240,7 +8240,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8358,7 +8358,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8476,7 +8476,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8594,7 +8594,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8712,14 +8712,14 @@
Parameters
-[FMax] 2.5
-[Fudge Factor] 0.1
-[Bounce] 0
-[CFM] 0.001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.8
-[Stop CFM] 0.001
+[FMax] 2.5
+[Fudge Factor] 0.1
+[Bounce] 0
+[CFM] 0.001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.8
+[Stop CFM] 0.001
Draw Mode
@@ -8837,7 +8837,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8955,7 +8955,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -9073,7 +9073,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -9191,7 +9191,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
diff --git a/LabVIEW Motion Magic Example/LabVIEW Motion Magic Example.lvproj b/LabVIEW Motion Magic Example/LabVIEW Motion Magic Example.lvproj
index 3cfa254..9da9016 100644
--- a/LabVIEW Motion Magic Example/LabVIEW Motion Magic Example.lvproj
+++ b/LabVIEW Motion Magic Example/LabVIEW Motion Magic Example.lvproj
@@ -1,78 +1,78 @@
- true
-
- -
- 3
- true
- true
- false
- 0
- My Computer/VI Server
- My Computer/VI Server
- true
- true
- false
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- Target
- roboRIO-217-FRC.local
- OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
- 76F2
- ARMLinux
- true
- 5000
- 1000
- 8
- 8
- false
- true
- 300
- 80
- 60
-
- 100
- false
- 10000
- 0
- 0
- true
- true
- true
- 8001
- /home/lvuser/natinst/bin/startup.rtexe
- true
- +*
- true
- /home/lvuser/natinst/bin
- true
- true
- +*
- false
- true
- 3363
- Main Application Instance/VI Server
- Main Application Instance/VI Server
- +*
- true
- true
- Listen 8000
+ true
+
+
-
+ 3
+ true
+ true
+ false
+ 0
+ My Computer/VI Server
+ My Computer/VI Server
+ true
+ true
+ false
+
-
+
-
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ Target
+ roboRIO-217-FRC.local
+ OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
+ 76F2
+ ARMLinux
+ true
+ 5000
+ 1000
+ 8
+ 8
+ false
+ true
+ 300
+ 80
+ 60
+
+ 100
+ false
+ 10000
+ 0
+ 0
+ true
+ true
+ true
+ 8001
+ /home/lvuser/natinst/bin/startup.rtexe
+ true
+ +*
+ true
+ /home/lvuser/natinst/bin
+ true
+ true
+ +*
+ false
+ true
+ 3363
+ Main Application Instance/VI Server
+ Main Application Instance/VI Server
+ +*
+ true
+ true
+ Listen 8000
NI.ServerName default
DocumentRoot "$LVSERVER_DOCROOT"
@@ -100,456 +100,456 @@ AddOutputFilter chunkFilter
- false
- false
- /c/ni-rt/system/www/www.log
- 80
- /c/ni-rt/system/www
- c+*
- 60
- +*
- PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
- 15
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
-
- -
-
-
- {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
- {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
- 8002
- http://www.NI.com
- true
- {8C1C8770-D686-4931-835E-3A364C203F20}
- Build Robot Main.vi into an EXE that will run at startup on the roboRIO
- FRC Robot Boot-up Deployment
- 0
- true
- true
- /D/Users/JCapp/Documents/LabVIEW Data/LabVIEW Motion Magic Example/Builds
- <none>
- true
- {6782B190-04E1-4A41-93AB-3F357B35791E}
- /home/lvuser/natinst/bin
- 1
- startup.rtexe
- /home/lvuser/natinst/bin/startup.rtexe
- <none>
- App
- Support Directory
- /home/lvuser/natinst/bin/data
- <none>
- 2
- {DB01CD21-4447-4671-A00A-D774E7A6FDE1}
- Container
- 0
- /Target/Robot Main.vi
- TopLevel
- VI
- 2
- NI
- FRC Robot Boot-up Deployment
- FRC Robot Boot-up Deployment
- Copyright © 2013 NI
- FRC Robot Boot-up Deployment
- {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
- startup.rtexe
-
-
-
+ false
+ false
+ /c/ni-rt/system/www/www.log
+ 80
+ /c/ni-rt/system/www
+ c+*
+ 60
+ +*
+ PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
+ 15
+ -
+
+
+ -
+
+
+
+
+
+
+
+
+
+
+
+ -
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+
+ -
+
-
+ {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
+ {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
+ 8002
+ http://www.NI.com
+ true
+ {8C1C8770-D686-4931-835E-3A364C203F20}
+ Build Robot Main.vi into an EXE that will run at startup on the roboRIO
+ FRC Robot Boot-up Deployment
+ 0
+ true
+ true
+ /D/Users/JCapp/Documents/LabVIEW Data/LabVIEW Motion Magic Example/Builds
+ <none>
+ true
+ {6782B190-04E1-4A41-93AB-3F357B35791E}
+ /home/lvuser/natinst/bin
+ 1
+ startup.rtexe
+ /home/lvuser/natinst/bin/startup.rtexe
+ <none>
+ App
+ Support Directory
+ /home/lvuser/natinst/bin/data
+ <none>
+ 2
+ {DB01CD21-4447-4671-A00A-D774E7A6FDE1}
+ Container
+ 0
+ /Target/Robot Main.vi
+ TopLevel
+ VI
+ 2
+ NI
+ FRC Robot Boot-up Deployment
+ FRC Robot Boot-up Deployment
+ Copyright © 2013 NI
+ FRC Robot Boot-up Deployment
+ {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
+ startup.rtexe
+
+
+
diff --git a/LabVIEW Position Closed Loop/Position Closed Loop.lvproj b/LabVIEW Position Closed Loop/Position Closed Loop.lvproj
index dd7258d..854e576 100644
--- a/LabVIEW Position Closed Loop/Position Closed Loop.lvproj
+++ b/LabVIEW Position Closed Loop/Position Closed Loop.lvproj
@@ -1,77 +1,77 @@
- true
-
- -
- 3
- true
- true
- false
- 0
- My Computer/VI Server
- My Computer/VI Server
- true
- true
- false
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- Target
- roboRIO-217-frc.local
- OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
- 76F2
- ARMLinux
- true
- 5000
- 1000
- 8
- 8
- false
- true
- 300
- 80
- 60
-
- 100
- false
- 10000
- 0
- 0
- true
- true
- true
- 8001
- /home/lvuser/natinst/bin/startup.rtexe
- true
- +*
- true
- /home/lvuser/natinst/bin
- true
- true
- +*
- false
- true
- 3363
- Main Application Instance/VI Server
- Main Application Instance/VI Server
- +*
- true
- true
- Listen 8000
+ true
+
+
-
+ 3
+ true
+ true
+ false
+ 0
+ My Computer/VI Server
+ My Computer/VI Server
+ true
+ true
+ false
+
-
+
-
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ Target
+ roboRIO-217-frc.local
+ OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
+ 76F2
+ ARMLinux
+ true
+ 5000
+ 1000
+ 8
+ 8
+ false
+ true
+ 300
+ 80
+ 60
+
+ 100
+ false
+ 10000
+ 0
+ 0
+ true
+ true
+ true
+ 8001
+ /home/lvuser/natinst/bin/startup.rtexe
+ true
+ +*
+ true
+ /home/lvuser/natinst/bin
+ true
+ true
+ +*
+ false
+ true
+ 3363
+ Main Application Instance/VI Server
+ Main Application Instance/VI Server
+ +*
+ true
+ true
+ Listen 8000
NI.ServerName default
DocumentRoot "$LVSERVER_DOCROOT"
@@ -99,433 +99,433 @@ AddOutputFilter chunkFilter
- false
- false
- /c/ni-rt/system/www/www.log
- 80
- /c/ni-rt/system/www
- c+*
- 60
- +*
- PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
- 15
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
-
- -
-
-
- {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
- {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
- 8002
- http://www.NI.com
- true
- {8C1C8770-D686-4931-835E-3A364C203F20}
- Build Robot Main.vi into an EXE that will run at startup on the roboRIO
- FRC Robot Boot-up Deployment
- 0
- true
- true
- ../Builds
- relativeToProject
- true
- {6782B190-04E1-4A41-93AB-3F357B35791E}
- /home/lvuser/natinst/bin
- 1
- 1
- startup.rtexe
- /home/lvuser/natinst/bin/startup.rtexe
- <none>
- App
- Support Directory
- /home/lvuser/natinst/bin/data
- <none>
- 2
- {058BAC78-4D97-4F8D-8829-224DDB5D1B28}
- Container
- 0
- /Target/Robot Main.vi
- TopLevel
- VI
- 2
- NI
- FRC Robot Boot-up Deployment
- FRC Robot Boot-up Deployment
- Copyright © 2013 NI
- FRC Robot Boot-up Deployment
- {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
- startup.rtexe
-
-
-
+ false
+ false
+ /c/ni-rt/system/www/www.log
+ 80
+ /c/ni-rt/system/www
+ c+*
+ 60
+ +*
+ PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
+ 15
+ -
+
+
+ -
+
+
+
+
+
+
+
+
+
+
+
+ -
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+
+ -
+
-
+ {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
+ {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
+ 8002
+ http://www.NI.com
+ true
+ {8C1C8770-D686-4931-835E-3A364C203F20}
+ Build Robot Main.vi into an EXE that will run at startup on the roboRIO
+ FRC Robot Boot-up Deployment
+ 0
+ true
+ true
+ ../Builds
+ relativeToProject
+ true
+ {6782B190-04E1-4A41-93AB-3F357B35791E}
+ /home/lvuser/natinst/bin
+ 1
+ 1
+ startup.rtexe
+ /home/lvuser/natinst/bin/startup.rtexe
+ <none>
+ App
+ Support Directory
+ /home/lvuser/natinst/bin/data
+ <none>
+ 2
+ {058BAC78-4D97-4F8D-8829-224DDB5D1B28}
+ Container
+ 0
+ /Target/Robot Main.vi
+ TopLevel
+ VI
+ 2
+ NI
+ FRC Robot Boot-up Deployment
+ FRC Robot Boot-up Deployment
+ Copyright © 2013 NI
+ FRC Robot Boot-up Deployment
+ {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
+ startup.rtexe
+
+
+
diff --git a/LabVIEW Simple Arcade Drive Example/FRC Simulated.xml b/LabVIEW Simple Arcade Drive Example/FRC Simulated.xml
index d99a6ad..97bb019 100644
--- a/LabVIEW Simple Arcade Drive Example/FRC Simulated.xml
+++ b/LabVIEW Simple Arcade Drive Example/FRC Simulated.xml
@@ -7622,14 +7622,14 @@
Parameters
-[FMax] 20
-[Fudge Factor] 1
-[Bounce] 0
-[CFM] 0.00001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.6
-[Stop CFM] 0.00001
+[FMax] 20
+[Fudge Factor] 1
+[Bounce] 0
+[CFM] 0.00001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.6
+[Stop CFM] 0.00001
Draw Mode
@@ -7747,14 +7747,14 @@
Parameters
-[FMax] 20
-[Fudge Factor] 1
-[Bounce] 0
-[CFM] 0.00001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.6
-[Stop CFM] 0.00001
+[FMax] 20
+[Fudge Factor] 1
+[Bounce] 0
+[CFM] 0.00001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.6
+[Stop CFM] 0.00001
Draw Mode
@@ -7872,14 +7872,14 @@
Parameters
-[FMax] 20
-[Fudge Factor] 1
-[Bounce] 0
-[CFM] 0.00001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.6
-[Stop CFM] 0.00001
+[FMax] 20
+[Fudge Factor] 1
+[Bounce] 0
+[CFM] 0.00001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.6
+[Stop CFM] 0.00001
Draw Mode
@@ -7997,14 +7997,14 @@
Parameters
-[FMax] 20
-[Fudge Factor] 1
-[Bounce] 0
-[CFM] 0.00001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.6
-[Stop CFM] 0.00001
+[FMax] 20
+[Fudge Factor] 1
+[Bounce] 0
+[CFM] 0.00001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.6
+[Stop CFM] 0.00001
Draw Mode
@@ -8122,7 +8122,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8240,7 +8240,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8358,7 +8358,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8476,7 +8476,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8594,7 +8594,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8712,14 +8712,14 @@
Parameters
-[FMax] 2.5
-[Fudge Factor] 0.1
-[Bounce] 0
-[CFM] 0.001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.8
-[Stop CFM] 0.001
+[FMax] 2.5
+[Fudge Factor] 0.1
+[Bounce] 0
+[CFM] 0.001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.8
+[Stop CFM] 0.001
Draw Mode
@@ -8837,7 +8837,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8955,7 +8955,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -9073,7 +9073,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -9191,7 +9191,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
diff --git a/LabVIEW Simple Arcade Drive Example/LabVIEW Simple Arcade Drive.lvproj b/LabVIEW Simple Arcade Drive Example/LabVIEW Simple Arcade Drive.lvproj
index c79210b..2b9e61d 100644
--- a/LabVIEW Simple Arcade Drive Example/LabVIEW Simple Arcade Drive.lvproj
+++ b/LabVIEW Simple Arcade Drive Example/LabVIEW Simple Arcade Drive.lvproj
@@ -1,78 +1,78 @@
- true
-
- -
- 3
- true
- true
- false
- 0
- My Computer/VI Server
- My Computer/VI Server
- true
- true
- false
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- Target
- roboRIO-217-FRC.local
- OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
- 76F2
- ARMLinux
- true
- 5000
- 1000
- 8
- 8
- false
- true
- 300
- 80
- 60
-
- 100
- false
- 10000
- 0
- 0
- true
- true
- true
- 8001
- /home/lvuser/natinst/bin/startup.rtexe
- true
- +*
- true
- /home/lvuser/natinst/bin
- true
- true
- +*
- false
- true
- 3363
- Main Application Instance/VI Server
- Main Application Instance/VI Server
- +*
- true
- true
- Listen 8000
+ true
+
+
-
+ 3
+ true
+ true
+ false
+ 0
+ My Computer/VI Server
+ My Computer/VI Server
+ true
+ true
+ false
+
-
+
-
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ Target
+ roboRIO-217-FRC.local
+ OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
+ 76F2
+ ARMLinux
+ true
+ 5000
+ 1000
+ 8
+ 8
+ false
+ true
+ 300
+ 80
+ 60
+
+ 100
+ false
+ 10000
+ 0
+ 0
+ true
+ true
+ true
+ 8001
+ /home/lvuser/natinst/bin/startup.rtexe
+ true
+ +*
+ true
+ /home/lvuser/natinst/bin
+ true
+ true
+ +*
+ false
+ true
+ 3363
+ Main Application Instance/VI Server
+ Main Application Instance/VI Server
+ +*
+ true
+ true
+ Listen 8000
NI.ServerName default
DocumentRoot "$LVSERVER_DOCROOT"
@@ -100,481 +100,481 @@ AddOutputFilter chunkFilter
- false
- false
- /c/ni-rt/system/www/www.log
- 80
- /c/ni-rt/system/www
- c+*
- 60
- +*
- PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
- 15
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
-
- -
-
-
- {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
- {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
- 8002
- http://www.NI.com
- true
- {8C1C8770-D686-4931-835E-3A364C203F20}
- Build Robot Main.vi into an EXE that will run at startup on the roboRIO
- FRC Robot Boot-up Deployment
- 0
- true
- true
- ../Builds
- relativeToProject
- true
- {6782B190-04E1-4A41-93AB-3F357B35791E}
- /home/lvuser/natinst/bin
- 2
- 1
- startup.rtexe
- /home/lvuser/natinst/bin/startup.rtexe
- <none>
- App
- Support Directory
- /home/lvuser/natinst/bin/data
- <none>
- 2
- {6769282A-C1AA-4303-B938-120EEF32313F}
- Container
- 0
- /Target/Robot Main.vi
- TopLevel
- VI
- 2
- NI
- FRC Robot Boot-up Deployment
- FRC Robot Boot-up Deployment
- Copyright © 2013 NI
- FRC Robot Boot-up Deployment
- {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
- startup.rtexe
-
-
-
+ false
+ false
+ /c/ni-rt/system/www/www.log
+ 80
+ /c/ni-rt/system/www
+ c+*
+ 60
+ +*
+ PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
+ 15
+ -
+
+
+ -
+
+
+
+
+
+
+
+
+
+
+
+ -
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+
+ -
+
-
+ {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
+ {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
+ 8002
+ http://www.NI.com
+ true
+ {8C1C8770-D686-4931-835E-3A364C203F20}
+ Build Robot Main.vi into an EXE that will run at startup on the roboRIO
+ FRC Robot Boot-up Deployment
+ 0
+ true
+ true
+ ../Builds
+ relativeToProject
+ true
+ {6782B190-04E1-4A41-93AB-3F357B35791E}
+ /home/lvuser/natinst/bin
+ 2
+ 1
+ startup.rtexe
+ /home/lvuser/natinst/bin/startup.rtexe
+ <none>
+ App
+ Support Directory
+ /home/lvuser/natinst/bin/data
+ <none>
+ 2
+ {6769282A-C1AA-4303-B938-120EEF32313F}
+ Container
+ 0
+ /Target/Robot Main.vi
+ TopLevel
+ VI
+ 2
+ NI
+ FRC Robot Boot-up Deployment
+ FRC Robot Boot-up Deployment
+ Copyright © 2013 NI
+ FRC Robot Boot-up Deployment
+ {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
+ startup.rtexe
+
+
+
diff --git a/LabVIEW Speed Closed Loop/Speed Closed Loop.lvproj b/LabVIEW Speed Closed Loop/Speed Closed Loop.lvproj
index 360bdad..cab1dac 100644
--- a/LabVIEW Speed Closed Loop/Speed Closed Loop.lvproj
+++ b/LabVIEW Speed Closed Loop/Speed Closed Loop.lvproj
@@ -1,77 +1,77 @@
- true
-
- -
- 3
- true
- true
- false
- 0
- My Computer/VI Server
- My Computer/VI Server
- true
- true
- false
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- Target
- roboRIO-217-frc.local
- OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
- 76F2
- ARMLinux
- true
- 5000
- 1000
- 8
- 8
- false
- true
- 300
- 80
- 60
-
- 100
- false
- 10000
- 0
- 0
- true
- true
- true
- 8001
- /home/lvuser/natinst/bin/startup.rtexe
- true
- +*
- true
- /home/lvuser/natinst/bin
- true
- true
- +*
- false
- true
- 3363
- Main Application Instance/VI Server
- Main Application Instance/VI Server
- +*
- true
- true
- Listen 8000
+ true
+
+
-
+ 3
+ true
+ true
+ false
+ 0
+ My Computer/VI Server
+ My Computer/VI Server
+ true
+ true
+ false
+
-
+
-
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ Target
+ roboRIO-217-frc.local
+ OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
+ 76F2
+ ARMLinux
+ true
+ 5000
+ 1000
+ 8
+ 8
+ false
+ true
+ 300
+ 80
+ 60
+
+ 100
+ false
+ 10000
+ 0
+ 0
+ true
+ true
+ true
+ 8001
+ /home/lvuser/natinst/bin/startup.rtexe
+ true
+ +*
+ true
+ /home/lvuser/natinst/bin
+ true
+ true
+ +*
+ false
+ true
+ 3363
+ Main Application Instance/VI Server
+ Main Application Instance/VI Server
+ +*
+ true
+ true
+ Listen 8000
NI.ServerName default
DocumentRoot "$LVSERVER_DOCROOT"
@@ -99,432 +99,432 @@ AddOutputFilter chunkFilter
- false
- false
- /c/ni-rt/system/www/www.log
- 80
- /c/ni-rt/system/www
- c+*
- 60
- +*
- PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
- 15
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
-
- -
-
-
- {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
- {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
- 8002
- http://www.NI.com
- true
- {8C1C8770-D686-4931-835E-3A364C203F20}
- Build Robot Main.vi into an EXE that will run at startup on the roboRIO
- FRC Robot Boot-up Deployment
- 0
- true
- true
- ../Builds
- relativeToProject
- true
- {6782B190-04E1-4A41-93AB-3F357B35791E}
- /home/lvuser/natinst/bin
- 1
- startup.rtexe
- /home/lvuser/natinst/bin/startup.rtexe
- <none>
- App
- Support Directory
- /home/lvuser/natinst/bin/data
- <none>
- 2
- {47491CC9-D45A-4AF1-BD57-972D0D1E5541}
- Container
- 0
- /Target/Robot Main.vi
- TopLevel
- VI
- 2
- NI
- FRC Robot Boot-up Deployment
- FRC Robot Boot-up Deployment
- Copyright © 2013 NI
- FRC Robot Boot-up Deployment
- {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
- startup.rtexe
-
-
-
+ false
+ false
+ /c/ni-rt/system/www/www.log
+ 80
+ /c/ni-rt/system/www
+ c+*
+ 60
+ +*
+ PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
+ 15
+ -
+
+
+ -
+
+
+
+
+
+
+
+
+
+
+
+ -
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+
+ -
+
-
+ {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
+ {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
+ 8002
+ http://www.NI.com
+ true
+ {8C1C8770-D686-4931-835E-3A364C203F20}
+ Build Robot Main.vi into an EXE that will run at startup on the roboRIO
+ FRC Robot Boot-up Deployment
+ 0
+ true
+ true
+ ../Builds
+ relativeToProject
+ true
+ {6782B190-04E1-4A41-93AB-3F357B35791E}
+ /home/lvuser/natinst/bin
+ 1
+ startup.rtexe
+ /home/lvuser/natinst/bin/startup.rtexe
+ <none>
+ App
+ Support Directory
+ /home/lvuser/natinst/bin/data
+ <none>
+ 2
+ {47491CC9-D45A-4AF1-BD57-972D0D1E5541}
+ Container
+ 0
+ /Target/Robot Main.vi
+ TopLevel
+ VI
+ 2
+ NI
+ FRC Robot Boot-up Deployment
+ FRC Robot Boot-up Deployment
+ Copyright © 2013 NI
+ FRC Robot Boot-up Deployment
+ {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
+ startup.rtexe
+
+
+
diff --git a/LabVIEW_CANTalonFollowerExample/CANTalon Follower Example.lvproj b/LabVIEW_CANTalonFollowerExample/CANTalon Follower Example.lvproj
index 3330a3c..6c8b622 100644
--- a/LabVIEW_CANTalonFollowerExample/CANTalon Follower Example.lvproj
+++ b/LabVIEW_CANTalonFollowerExample/CANTalon Follower Example.lvproj
@@ -1,78 +1,78 @@
- true
-
- -
- 3
- true
- true
- false
- 0
- My Computer/VI Server
- My Computer/VI Server
- true
- true
- false
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- Target
- roboRIO-469-FRC.local
- OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
- 76F2
- ARMLinux
- true
- 5000
- 1000
- 8
- 8
- false
- true
- 300
- 80
- 60
-
- 100
- false
- 10000
- 0
- 0
- true
- true
- true
- 8001
- /home/lvuser/natinst/bin/startup.rtexe
- true
- +*
- true
- /home/lvuser/natinst/bin
- true
- true
- +*
- false
- true
- 3363
- Main Application Instance/VI Server
- Main Application Instance/VI Server
- +*
- true
- true
- Listen 8000
+ true
+
+
-
+ 3
+ true
+ true
+ false
+ 0
+ My Computer/VI Server
+ My Computer/VI Server
+ true
+ true
+ false
+
-
+
-
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ Target
+ roboRIO-469-FRC.local
+ OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
+ 76F2
+ ARMLinux
+ true
+ 5000
+ 1000
+ 8
+ 8
+ false
+ true
+ 300
+ 80
+ 60
+
+ 100
+ false
+ 10000
+ 0
+ 0
+ true
+ true
+ true
+ 8001
+ /home/lvuser/natinst/bin/startup.rtexe
+ true
+ +*
+ true
+ /home/lvuser/natinst/bin
+ true
+ true
+ +*
+ false
+ true
+ 3363
+ Main Application Instance/VI Server
+ Main Application Instance/VI Server
+ +*
+ true
+ true
+ Listen 8000
NI.ServerName default
DocumentRoot "$LVSERVER_DOCROOT"
@@ -100,425 +100,425 @@ AddOutputFilter chunkFilter
- false
- false
- /c/ni-rt/system/www/www.log
- 80
- /c/ni-rt/system/www
- c+*
- 60
- +*
- PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
- 15
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
-
- -
-
-
- {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
- {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
- 8002
- http://www.NI.com
- true
- {8C1C8770-D686-4931-835E-3A364C203F20}
- Build Robot Main.vi into an EXE that will run at startup on the roboRIO
- FRC Robot Boot-up Deployment
- 0
- true
- true
- ../Builds
- relativeToProject
- true
- {6782B190-04E1-4A41-93AB-3F357B35791E}
- /home/lvuser/natinst/bin
- 1
- startup.rtexe
- /home/lvuser/natinst/bin/startup.rtexe
- <none>
- App
- Support Directory
- /home/lvuser/natinst/bin/data
- <none>
- 2
- {FA5E2B61-E8DD-4703-9C54-9EC6ADA53130}
- Container
- 0
- /Target/Robot Main.vi
- TopLevel
- VI
- 2
- NI
- FRC Robot Boot-up Deployment
- FRC Robot Boot-up Deployment
- Copyright © 2013 NI
- FRC Robot Boot-up Deployment
- {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
- startup.rtexe
-
-
-
+ false
+ false
+ /c/ni-rt/system/www/www.log
+ 80
+ /c/ni-rt/system/www
+ c+*
+ 60
+ +*
+ PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
+ 15
+ -
+
+
+ -
+
+
+
+
+
+
+
+
+
+
+
+ -
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+
+ -
+
-
+ {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
+ {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
+ 8002
+ http://www.NI.com
+ true
+ {8C1C8770-D686-4931-835E-3A364C203F20}
+ Build Robot Main.vi into an EXE that will run at startup on the roboRIO
+ FRC Robot Boot-up Deployment
+ 0
+ true
+ true
+ ../Builds
+ relativeToProject
+ true
+ {6782B190-04E1-4A41-93AB-3F357B35791E}
+ /home/lvuser/natinst/bin
+ 1
+ startup.rtexe
+ /home/lvuser/natinst/bin/startup.rtexe
+ <none>
+ App
+ Support Directory
+ /home/lvuser/natinst/bin/data
+ <none>
+ 2
+ {FA5E2B61-E8DD-4703-9C54-9EC6ADA53130}
+ Container
+ 0
+ /Target/Robot Main.vi
+ TopLevel
+ VI
+ 2
+ NI
+ FRC Robot Boot-up Deployment
+ FRC Robot Boot-up Deployment
+ Copyright © 2013 NI
+ FRC Robot Boot-up Deployment
+ {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
+ startup.rtexe
+
+
+
diff --git a/LabVIEW_Current Closed Loop/Current Closed Loop.lvproj b/LabVIEW_Current Closed Loop/Current Closed Loop.lvproj
index 7a12246..01217c5 100644
--- a/LabVIEW_Current Closed Loop/Current Closed Loop.lvproj
+++ b/LabVIEW_Current Closed Loop/Current Closed Loop.lvproj
@@ -1,78 +1,78 @@
- true
-
- -
- 3
- true
- true
- false
- 0
- My Computer/VI Server
- My Computer/VI Server
- true
- true
- false
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- Target
- roboRIO-469-FRC.local
- OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
- 76F2
- ARMLinux
- true
- 5000
- 1000
- 8
- 8
- false
- true
- 300
- 80
- 60
-
- 100
- false
- 10000
- 0
- 0
- true
- true
- true
- 8001
- /home/lvuser/natinst/bin/startup.rtexe
- true
- +*
- true
- /home/lvuser/natinst/bin
- true
- true
- +*
- false
- true
- 3363
- Main Application Instance/VI Server
- Main Application Instance/VI Server
- +*
- true
- true
- Listen 8000
+ true
+
+
-
+ 3
+ true
+ true
+ false
+ 0
+ My Computer/VI Server
+ My Computer/VI Server
+ true
+ true
+ false
+
-
+
-
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ Target
+ roboRIO-469-FRC.local
+ OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
+ 76F2
+ ARMLinux
+ true
+ 5000
+ 1000
+ 8
+ 8
+ false
+ true
+ 300
+ 80
+ 60
+
+ 100
+ false
+ 10000
+ 0
+ 0
+ true
+ true
+ true
+ 8001
+ /home/lvuser/natinst/bin/startup.rtexe
+ true
+ +*
+ true
+ /home/lvuser/natinst/bin
+ true
+ true
+ +*
+ false
+ true
+ 3363
+ Main Application Instance/VI Server
+ Main Application Instance/VI Server
+ +*
+ true
+ true
+ Listen 8000
NI.ServerName default
DocumentRoot "$LVSERVER_DOCROOT"
@@ -100,430 +100,430 @@ AddOutputFilter chunkFilter
- false
- false
- /c/ni-rt/system/www/www.log
- 80
- /c/ni-rt/system/www
- c+*
- 60
- +*
- PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
- 15
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
-
- -
-
-
- {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
- {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
- 8002
- http://www.NI.com
- true
- {8C1C8770-D686-4931-835E-3A364C203F20}
- Build Robot Main.vi into an EXE that will run at startup on the roboRIO
- FRC Robot Boot-up Deployment
- 0
- true
- true
- ../Builds
- relativeToProject
- true
- {6782B190-04E1-4A41-93AB-3F357B35791E}
- /home/lvuser/natinst/bin
- 1
- startup.rtexe
- /home/lvuser/natinst/bin/startup.rtexe
- <none>
- App
- Support Directory
- /home/lvuser/natinst/bin/data
- <none>
- 2
- {00E176E5-F52A-4538-A00A-FC01F16E136F}
- Container
- 0
- /Target/Robot Main.vi
- TopLevel
- VI
- 2
- NI
- FRC Robot Boot-up Deployment
- FRC Robot Boot-up Deployment
- Copyright © 2013 NI
- FRC Robot Boot-up Deployment
- {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
- startup.rtexe
-
-
-
+ false
+ false
+ /c/ni-rt/system/www/www.log
+ 80
+ /c/ni-rt/system/www
+ c+*
+ 60
+ +*
+ PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
+ 15
+ -
+
+
+ -
+
+
+
+
+
+
+
+
+
+
+
+ -
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+
+ -
+
-
+ {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
+ {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
+ 8002
+ http://www.NI.com
+ true
+ {8C1C8770-D686-4931-835E-3A364C203F20}
+ Build Robot Main.vi into an EXE that will run at startup on the roboRIO
+ FRC Robot Boot-up Deployment
+ 0
+ true
+ true
+ ../Builds
+ relativeToProject
+ true
+ {6782B190-04E1-4A41-93AB-3F357B35791E}
+ /home/lvuser/natinst/bin
+ 1
+ startup.rtexe
+ /home/lvuser/natinst/bin/startup.rtexe
+ <none>
+ App
+ Support Directory
+ /home/lvuser/natinst/bin/data
+ <none>
+ 2
+ {00E176E5-F52A-4538-A00A-FC01F16E136F}
+ Container
+ 0
+ /Target/Robot Main.vi
+ TopLevel
+ VI
+ 2
+ NI
+ FRC Robot Boot-up Deployment
+ FRC Robot Boot-up Deployment
+ Copyright © 2013 NI
+ FRC Robot Boot-up Deployment
+ {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
+ startup.rtexe
+
+
+
diff --git a/LabVIEW_MotionProfileExample/Motion Profile Example Talon SRX.lvproj b/LabVIEW_MotionProfileExample/Motion Profile Example Talon SRX.lvproj
index 3b2bc0f..932b3f9 100644
--- a/LabVIEW_MotionProfileExample/Motion Profile Example Talon SRX.lvproj
+++ b/LabVIEW_MotionProfileExample/Motion Profile Example Talon SRX.lvproj
@@ -1,77 +1,77 @@
- true
-
- -
- 3
- true
- true
- false
- 0
- My Computer/VI Server
- My Computer/VI Server
- true
- true
- false
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- Target
- roboRIO-469-FRC.local
- OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
- 76F2
- ARMLinux
- true
- 5000
- 1000
- 8
- 8
- false
- true
- 300
- 80
- 60
-
- 100
- false
- 10000
- 0
- 0
- true
- true
- true
- 8001
- /home/lvuser/natinst/bin/startup.rtexe
- true
- +*
- true
- /home/lvuser/natinst/bin
- true
- true
- +*
- false
- true
- 3363
- Main Application Instance/VI Server
- Main Application Instance/VI Server
- +*
- true
- true
- Listen 8000
+ true
+
+
-
+ 3
+ true
+ true
+ false
+ 0
+ My Computer/VI Server
+ My Computer/VI Server
+ true
+ true
+ false
+
-
+
-
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ Target
+ roboRIO-469-FRC.local
+ OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
+ 76F2
+ ARMLinux
+ true
+ 5000
+ 1000
+ 8
+ 8
+ false
+ true
+ 300
+ 80
+ 60
+
+ 100
+ false
+ 10000
+ 0
+ 0
+ true
+ true
+ true
+ 8001
+ /home/lvuser/natinst/bin/startup.rtexe
+ true
+ +*
+ true
+ /home/lvuser/natinst/bin
+ true
+ true
+ +*
+ false
+ true
+ 3363
+ Main Application Instance/VI Server
+ Main Application Instance/VI Server
+ +*
+ true
+ true
+ Listen 8000
NI.ServerName default
DocumentRoot "$LVSERVER_DOCROOT"
@@ -99,478 +99,478 @@ AddOutputFilter chunkFilter
- false
- false
- /c/ni-rt/system/www/www.log
- 80
- /c/ni-rt/system/www
- c+*
- 60
- +*
- PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
- 15
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
-
- -
-
-
- {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
- {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
- 8002
- http://www.NI.com
- true
- {8C1C8770-D686-4931-835E-3A364C203F20}
- Build Robot Main.vi into an EXE that will run at startup on the roboRIO
- FRC Robot Boot-up Deployment
- 0
- true
- true
- ../Builds
- relativeToProject
- true
- {6782B190-04E1-4A41-93AB-3F357B35791E}
- /home/lvuser/natinst/bin
- 1
- startup.rtexe
- /home/lvuser/natinst/bin/startup.rtexe
- <none>
- App
- Support Directory
- /home/lvuser/natinst/bin/data
- <none>
- 2
- {292A0AF5-3282-4328-9597-BE08B36793D4}
- Container
- 0
- /Target/Robot Main.vi
- TopLevel
- VI
- 2
- NI
- FRC Robot Boot-up Deployment
- FRC Robot Boot-up Deployment
- Copyright © 2013 NI
- FRC Robot Boot-up Deployment
- {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
- startup.rtexe
-
-
-
+ false
+ false
+ /c/ni-rt/system/www/www.log
+ 80
+ /c/ni-rt/system/www
+ c+*
+ 60
+ +*
+ PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
+ 15
+ -
+
+
+ -
+
+
+
+
+
+
+
+
+
+
+
+ -
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+
+ -
+
-
+ {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
+ {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
+ 8002
+ http://www.NI.com
+ true
+ {8C1C8770-D686-4931-835E-3A364C203F20}
+ Build Robot Main.vi into an EXE that will run at startup on the roboRIO
+ FRC Robot Boot-up Deployment
+ 0
+ true
+ true
+ ../Builds
+ relativeToProject
+ true
+ {6782B190-04E1-4A41-93AB-3F357B35791E}
+ /home/lvuser/natinst/bin
+ 1
+ startup.rtexe
+ /home/lvuser/natinst/bin/startup.rtexe
+ <none>
+ App
+ Support Directory
+ /home/lvuser/natinst/bin/data
+ <none>
+ 2
+ {292A0AF5-3282-4328-9597-BE08B36793D4}
+ Container
+ 0
+ /Target/Robot Main.vi
+ TopLevel
+ VI
+ 2
+ NI
+ FRC Robot Boot-up Deployment
+ FRC Robot Boot-up Deployment
+ Copyright © 2013 NI
+ FRC Robot Boot-up Deployment
+ {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
+ startup.rtexe
+
+
+
diff --git a/LabVIEW_Pigeon_StraightServo_Example/FRC Simulated.xml b/LabVIEW_Pigeon_StraightServo_Example/FRC Simulated.xml
index d99a6ad..97bb019 100644
--- a/LabVIEW_Pigeon_StraightServo_Example/FRC Simulated.xml
+++ b/LabVIEW_Pigeon_StraightServo_Example/FRC Simulated.xml
@@ -7622,14 +7622,14 @@
Parameters
-[FMax] 20
-[Fudge Factor] 1
-[Bounce] 0
-[CFM] 0.00001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.6
-[Stop CFM] 0.00001
+[FMax] 20
+[Fudge Factor] 1
+[Bounce] 0
+[CFM] 0.00001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.6
+[Stop CFM] 0.00001
Draw Mode
@@ -7747,14 +7747,14 @@
Parameters
-[FMax] 20
-[Fudge Factor] 1
-[Bounce] 0
-[CFM] 0.00001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.6
-[Stop CFM] 0.00001
+[FMax] 20
+[Fudge Factor] 1
+[Bounce] 0
+[CFM] 0.00001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.6
+[Stop CFM] 0.00001
Draw Mode
@@ -7872,14 +7872,14 @@
Parameters
-[FMax] 20
-[Fudge Factor] 1
-[Bounce] 0
-[CFM] 0.00001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.6
-[Stop CFM] 0.00001
+[FMax] 20
+[Fudge Factor] 1
+[Bounce] 0
+[CFM] 0.00001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.6
+[Stop CFM] 0.00001
Draw Mode
@@ -7997,14 +7997,14 @@
Parameters
-[FMax] 20
-[Fudge Factor] 1
-[Bounce] 0
-[CFM] 0.00001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.6
-[Stop CFM] 0.00001
+[FMax] 20
+[Fudge Factor] 1
+[Bounce] 0
+[CFM] 0.00001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.6
+[Stop CFM] 0.00001
Draw Mode
@@ -8122,7 +8122,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8240,7 +8240,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8358,7 +8358,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8476,7 +8476,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8594,7 +8594,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8712,14 +8712,14 @@
Parameters
-[FMax] 2.5
-[Fudge Factor] 0.1
-[Bounce] 0
-[CFM] 0.001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.8
-[Stop CFM] 0.001
+[FMax] 2.5
+[Fudge Factor] 0.1
+[Bounce] 0
+[CFM] 0.001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.8
+[Stop CFM] 0.001
Draw Mode
@@ -8837,7 +8837,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8955,7 +8955,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -9073,7 +9073,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -9191,7 +9191,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
diff --git a/LabVIEW_Pigeon_StraightServo_Example/Pigeon StraightServo Example.lvproj b/LabVIEW_Pigeon_StraightServo_Example/Pigeon StraightServo Example.lvproj
index 2fe0dac..071bbd4 100644
--- a/LabVIEW_Pigeon_StraightServo_Example/Pigeon StraightServo Example.lvproj
+++ b/LabVIEW_Pigeon_StraightServo_Example/Pigeon StraightServo Example.lvproj
@@ -1,78 +1,78 @@
- true
-
- -
- 3
- true
- true
- false
- 0
- My Computer/VI Server
- My Computer/VI Server
- true
- true
- false
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- Target
- roboRIO-217-FRC.local
- OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
- 76F2
- ARMLinux
- true
- 5000
- 1000
- 8
- 8
- false
- true
- 300
- 80
- 60
-
- 100
- false
- 10000
- 0
- 0
- true
- true
- true
- 8001
- /home/lvuser/natinst/bin/startup.rtexe
- true
- +*
- true
- /home/lvuser/natinst/bin
- true
- true
- +*
- false
- true
- 3363
- Main Application Instance/VI Server
- Main Application Instance/VI Server
- +*
- true
- true
- Listen 8000
+ true
+
+
-
+ 3
+ true
+ true
+ false
+ 0
+ My Computer/VI Server
+ My Computer/VI Server
+ true
+ true
+ false
+
-
+
-
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ Target
+ roboRIO-217-FRC.local
+ OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
+ 76F2
+ ARMLinux
+ true
+ 5000
+ 1000
+ 8
+ 8
+ false
+ true
+ 300
+ 80
+ 60
+
+ 100
+ false
+ 10000
+ 0
+ 0
+ true
+ true
+ true
+ 8001
+ /home/lvuser/natinst/bin/startup.rtexe
+ true
+ +*
+ true
+ /home/lvuser/natinst/bin
+ true
+ true
+ +*
+ false
+ true
+ 3363
+ Main Application Instance/VI Server
+ Main Application Instance/VI Server
+ +*
+ true
+ true
+ Listen 8000
NI.ServerName default
DocumentRoot "$LVSERVER_DOCROOT"
@@ -100,504 +100,504 @@ AddOutputFilter chunkFilter
- false
- false
- /c/ni-rt/system/www/www.log
- 80
- /c/ni-rt/system/www
- c+*
- 60
- +*
- PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
- 15
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
-
- -
-
-
- {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
- {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
- 8002
- http://www.NI.com
- true
- {8C1C8770-D686-4931-835E-3A364C203F20}
- Build Robot Main.vi into an EXE that will run at startup on the roboRIO
- FRC Robot Boot-up Deployment
- 0
- true
- true
- /D/CTR/FRC/FRC-Examples/LabVIEW_Pigeon_StraightServo_Example/Builds
- <none>
- true
- {6782B190-04E1-4A41-93AB-3F357B35791E}
- /home/lvuser/natinst/bin
- 1
- startup.rtexe
- /home/lvuser/natinst/bin/startup.rtexe
- <none>
- App
- Support Directory
- /home/lvuser/natinst/bin/data
- <none>
- 2
- {DB01CD21-4447-4671-A00A-D774E7A6FDE1}
- Container
- 0
- /Target/Robot Main.vi
- TopLevel
- VI
- 2
- NI
- FRC Robot Boot-up Deployment
- FRC Robot Boot-up Deployment
- Copyright © 2013 NI
- FRC Robot Boot-up Deployment
- {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
- startup.rtexe
-
-
-
+ false
+ false
+ /c/ni-rt/system/www/www.log
+ 80
+ /c/ni-rt/system/www
+ c+*
+ 60
+ +*
+ PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
+ 15
+ -
+
+
+ -
+
+
+
+
+
+
+
+
+
+
+
+ -
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+
+ -
+
-
+ {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
+ {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
+ 8002
+ http://www.NI.com
+ true
+ {8C1C8770-D686-4931-835E-3A364C203F20}
+ Build Robot Main.vi into an EXE that will run at startup on the roboRIO
+ FRC Robot Boot-up Deployment
+ 0
+ true
+ true
+ /D/CTR/FRC/FRC-Examples/LabVIEW_Pigeon_StraightServo_Example/Builds
+ <none>
+ true
+ {6782B190-04E1-4A41-93AB-3F357B35791E}
+ /home/lvuser/natinst/bin
+ 1
+ startup.rtexe
+ /home/lvuser/natinst/bin/startup.rtexe
+ <none>
+ App
+ Support Directory
+ /home/lvuser/natinst/bin/data
+ <none>
+ 2
+ {DB01CD21-4447-4671-A00A-D774E7A6FDE1}
+ Container
+ 0
+ /Target/Robot Main.vi
+ TopLevel
+ VI
+ 2
+ NI
+ FRC Robot Boot-up Deployment
+ FRC Robot Boot-up Deployment
+ Copyright © 2013 NI
+ FRC Robot Boot-up Deployment
+ {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
+ startup.rtexe
+
+
+
diff --git a/Season2016/CPP_Pigeon_StraightServo_Example/.cproject b/Season2016/CPP_Pigeon_StraightServo_Example/.cproject
index db25609..45ea7bd 100644
--- a/Season2016/CPP_Pigeon_StraightServo_Example/.cproject
+++ b/Season2016/CPP_Pigeon_StraightServo_Example/.cproject
@@ -1,288 +1,288 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/Season2016/CPP_Pigeon_StraightServo_Example/.project b/Season2016/CPP_Pigeon_StraightServo_Example/.project
index 992c486..2dcc99a 100644
--- a/Season2016/CPP_Pigeon_StraightServo_Example/.project
+++ b/Season2016/CPP_Pigeon_StraightServo_Example/.project
@@ -1,28 +1,28 @@
- CPP_Pigeon_StraightServo_Example
-
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.genmakebuilder
- clean,full,incremental,
-
-
-
-
- org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
- full,incremental,
-
-
-
-
-
- org.eclipse.cdt.core.cnature
- org.eclipse.cdt.core.ccnature
- org.eclipse.cdt.managedbuilder.core.managedBuildNature
- org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ CPP_Pigeon_StraightServo_Example
+
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.genmakebuilder
+ clean,full,incremental,
+
+
+
+
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder
+ full,incremental,
+
+
+
+
+
+ org.eclipse.cdt.core.cnature
+ org.eclipse.cdt.core.ccnature
+ org.eclipse.cdt.managedbuilder.core.managedBuildNature
+ org.eclipse.cdt.managedbuilder.core.ScannerConfigNature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/Season2016/CPP_Pigeon_StraightServo_Example/.settings/language.settings.xml b/Season2016/CPP_Pigeon_StraightServo_Example/.settings/language.settings.xml
index 09f9f36..d9f2f08 100644
--- a/Season2016/CPP_Pigeon_StraightServo_Example/.settings/language.settings.xml
+++ b/Season2016/CPP_Pigeon_StraightServo_Example/.settings/language.settings.xml
@@ -1,33 +1,33 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/Season2016/CPP_Pigeon_StraightServo_Example/src/PigeonImu.cpp b/Season2016/CPP_Pigeon_StraightServo_Example/src/PigeonImu.cpp
index 6c1c465..aa82f77 100644
--- a/Season2016/CPP_Pigeon_StraightServo_Example/src/PigeonImu.cpp
+++ b/Season2016/CPP_Pigeon_StraightServo_Example/src/PigeonImu.cpp
@@ -34,9 +34,9 @@
*/
PigeonImu::PigeonImu(int deviceNumber) : CtreCanMap(0)
{
- _deviceId = 0x15000000 | (int) deviceNumber;
+ _deviceId = 0x15000000 | (int) deviceNumber;
- SendCAN(CONTROL_1 | _deviceId, 0x00000000, 0, 100);
+ SendCAN(CONTROL_1 | _deviceId, 0x00000000, 0, 100);
}
/**
@@ -45,82 +45,82 @@ PigeonImu::PigeonImu(int deviceNumber) : CtreCanMap(0)
*/
PigeonImu::PigeonImu(CANTalon * talonSrx) : CtreCanMap(0)
{
- _deviceId = (int) 0x02000000 | (talonSrx->GetDeviceID());
+ _deviceId = (int) 0x02000000 | (talonSrx->GetDeviceID());
- SendCAN(CONTROL_1 | _deviceId, 0x00000000, 0, 100);
+ SendCAN(CONTROL_1 | _deviceId, 0x00000000, 0, 100);
}
//----------------------- Control Param routines -----------------------//
int PigeonImu::ConfigSetParameter(ParamEnum paramEnum, double paramValue)
{
- uint64_t frame;
- /* param specific encoders can be placed here */
- frame = (int32_t) paramValue;
- frame <<= 8;
- frame |= (uint8_t) paramEnum;
- int status = SendCAN(PARAM_SET | _deviceId, frame, 5, 0);
- return status;
+ uint64_t frame;
+ /* param specific encoders can be placed here */
+ frame = (int32_t) paramValue;
+ frame <<= 8;
+ frame |= (uint8_t) paramEnum;
+ int status = SendCAN(PARAM_SET | _deviceId, frame, 5, 0);
+ return status;
}
int PigeonImu::ConfigSetParameter(ParamEnum paramEnum, TareType tareType, double angleDeg)
{
- const double deg_per_canunit = 0.015625f;
- int deg_3B = ((int) (angleDeg / deg_per_canunit));
- int32_t paramValue;
- paramValue = (long) deg_3B;
- paramValue <<= 8;
- paramValue |= (uint8_t) tareType;
- return ConfigSetParameter(paramEnum, (double)paramValue);
+ const double deg_per_canunit = 0.015625f;
+ int deg_3B = ((int) (angleDeg / deg_per_canunit));
+ int32_t paramValue;
+ paramValue = (long) deg_3B;
+ paramValue <<= 8;
+ paramValue |= (uint8_t) tareType;
+ return ConfigSetParameter(paramEnum, (double)paramValue);
}
/**
* Change the periodMs of a TALON's status frame. See kStatusFrame_* enums for
* what's available.
*/
void PigeonImu::SetStatusFrameRateMs(StatusFrameRate statusFrameRate, int periodMs) {
- /* bounds check the period */
- if (periodMs < 1)
- periodMs = 1;
- else if (periodMs > 255)
- periodMs = 255;
- /* bounds frame */
- if((unsigned int)statusFrameRate > 255)
- return;
- /* save the unsigned pieces */
- uint8_t period = (uint8_t)periodMs;
- uint8_t idx = statusFrameRate;
- /* assemble */
- int32_t paramValue = period;
- paramValue <<= 8;
- paramValue |= idx;
- /* send the set request */
- ConfigSetParameter(ParamEnum::ParamEnum_StatusFrameRate, paramValue);
+ /* bounds check the period */
+ if (periodMs < 1)
+ periodMs = 1;
+ else if (periodMs > 255)
+ periodMs = 255;
+ /* bounds frame */
+ if((unsigned int)statusFrameRate > 255)
+ return;
+ /* save the unsigned pieces */
+ uint8_t period = (uint8_t)periodMs;
+ uint8_t idx = statusFrameRate;
+ /* assemble */
+ int32_t paramValue = period;
+ paramValue <<= 8;
+ paramValue |= idx;
+ /* send the set request */
+ ConfigSetParameter(ParamEnum::ParamEnum_StatusFrameRate, paramValue);
}
int PigeonImu::SetYaw(double angleDeg)
{
- int errCode = ConfigSetParameter(ParamEnum::ParamEnum_YawOffset, TareType::SetValue, angleDeg);
- return HandleError(errCode);
+ int errCode = ConfigSetParameter(ParamEnum::ParamEnum_YawOffset, TareType::SetValue, angleDeg);
+ return HandleError(errCode);
}
/**
* Atomically add to the Yaw register.
*/
int PigeonImu::AddYaw(double angleDeg)
{
- int errCode = ConfigSetParameter(ParamEnum::ParamEnum_YawOffset, TareType::AddOffset, angleDeg);
- return HandleError(errCode);
+ int errCode = ConfigSetParameter(ParamEnum::ParamEnum_YawOffset, TareType::AddOffset, angleDeg);
+ return HandleError(errCode);
}
int PigeonImu::SetYawToCompass()
{
- int errCode = ConfigSetParameter(ParamEnum::ParamEnum_YawOffset, TareType::MatchCompass, 0);
- return HandleError(errCode);
+ int errCode = ConfigSetParameter(ParamEnum::ParamEnum_YawOffset, TareType::MatchCompass, 0);
+ return HandleError(errCode);
}
int PigeonImu::SetFusedHeading(double angleDeg)
{
- int errCode = ConfigSetParameter(ParamEnum::ParamEnum_FusedHeadingOffset, TareType::SetValue, angleDeg);
- return HandleError(errCode);
+ int errCode = ConfigSetParameter(ParamEnum::ParamEnum_FusedHeadingOffset, TareType::SetValue, angleDeg);
+ return HandleError(errCode);
}
int PigeonImu::SetAccumZAngle(double angleDeg)
{
- int errCode = ConfigSetParameter(ParamEnum::ParamEnum_AccumZ, TareType::SetValue, angleDeg);
- return HandleError(errCode);
+ int errCode = ConfigSetParameter(ParamEnum::ParamEnum_AccumZ, TareType::SetValue, angleDeg);
+ return HandleError(errCode);
}
/**
* Enable/Disable Temp compensation. Pigeon defaults with this on at boot.
@@ -129,21 +129,21 @@ int PigeonImu::SetAccumZAngle(double angleDeg)
*/
int PigeonImu::EnableTemperatureCompensation(bool bTempCompEnable)
{
- int errCode = ConfigSetParameter(ParamEnum::ParamEnum_TempCompDisable, bTempCompEnable ? 0 : 1);
- return HandleError(errCode);
+ int errCode = ConfigSetParameter(ParamEnum::ParamEnum_TempCompDisable, bTempCompEnable ? 0 : 1);
+ return HandleError(errCode);
}
/**
* Atomically add to the Fused Heading register.
*/
int PigeonImu::AddFusedHeading(double angleDeg)
{
- int errCode = ConfigSetParameter(ParamEnum::ParamEnum_FusedHeadingOffset, TareType::AddOffset, angleDeg);
- return HandleError(errCode);
+ int errCode = ConfigSetParameter(ParamEnum::ParamEnum_FusedHeadingOffset, TareType::AddOffset, angleDeg);
+ return HandleError(errCode);
}
int PigeonImu::SetFusedHeadingToCompass()
{
- int errCode = ConfigSetParameter(ParamEnum::ParamEnum_FusedHeadingOffset, TareType::MatchCompass, 0);
- return HandleError(errCode);
+ int errCode = ConfigSetParameter(ParamEnum::ParamEnum_FusedHeadingOffset, TareType::MatchCompass, 0);
+ return HandleError(errCode);
}
/**
* Set the declination for compass.
@@ -151,8 +151,8 @@ int PigeonImu::SetFusedHeadingToCompass()
*/
int PigeonImu::SetCompassDeclination(double angleDegOffset)
{
- int errCode = ConfigSetParameter(ParamEnum::ParamEnum_CompassOffset, TareType::SetOffset, 0);
- return HandleError(errCode);
+ int errCode = ConfigSetParameter(ParamEnum::ParamEnum_CompassOffset, TareType::SetOffset, 0);
+ return HandleError(errCode);
}
/**
* Sets the compass angle.
@@ -161,18 +161,18 @@ int PigeonImu::SetCompassDeclination(double angleDegOffset)
*/
int PigeonImu::SetCompassAngle(double angleDeg)
{
- int errCode = ConfigSetParameter(ParamEnum::ParamEnum_CompassOffset, TareType::SetValue, 0);
- return HandleError(errCode);
+ int errCode = ConfigSetParameter(ParamEnum::ParamEnum_CompassOffset, TareType::SetValue, 0);
+ return HandleError(errCode);
}
//----------------------- Calibration routines -----------------------//
int PigeonImu::EnterCalibrationMode(CalibrationMode calMode)
{
- long frame;
- frame = (uint32_t) calMode;
- frame <<= 8;
- frame |= (uint8_t) ParamEnum::ParamEnum_EnterCalibration;
- int status = SendCAN(PARAM_SET | _deviceId, frame, 5, 0);
- return status;
+ long frame;
+ frame = (uint32_t) calMode;
+ frame <<= 8;
+ frame |= (uint8_t) ParamEnum::ParamEnum_EnterCalibration;
+ int status = SendCAN(PARAM_SET | _deviceId, frame, 5, 0);
+ return status;
}
/**
* Get the status of the current (or previousley complete) calibration.
@@ -180,111 +180,111 @@ int PigeonImu::EnterCalibrationMode(CalibrationMode calMode)
*/
int PigeonImu::GetGeneralStatus(PigeonImu::GeneralStatus & statusToFill)
{
- int errCode = ReceiveCAN(COND_STATUS_1);
-
- uint8_t b3 = (uint8_t)(_cache >> 0x18);
- uint8_t b5 = (uint8_t)(_cache >> 0x28);
-
- uint8_t iCurrMode = (b5 >> 4) & 0xF;
- PigeonImu::CalibrationMode currentMode = (PigeonImu::CalibrationMode)(iCurrMode);
-
- /* shift up bottom nibble, and back down with sign-extension */
- int32_t calibrationErr = b5 & 0xF;
- calibrationErr <<= (32 - 4);
- calibrationErr >>= (32 - 4);
-
- int32_t noMotionBiasCount = (uint8_t)(_cache >> 0x24) & 0xF;
- int32_t tempCompensationCount = (uint8_t)(_cache >> 0x20) & 0xF;
- int32_t upTimSec = (uint8_t)(_cache >> 0x38);
-
- statusToFill.currentMode = currentMode;
- statusToFill.calibrationError = calibrationErr;
- statusToFill.bCalIsBooting = ((b3 & 1) == 1);
- statusToFill.state = GetState(errCode, _cache);
- statusToFill.tempC = GetTemp(_cache);
- statusToFill.noMotionBiasCount = noMotionBiasCount;
- statusToFill.tempCompensationCount = tempCompensationCount;
- statusToFill.upTimeSec = upTimSec;
- statusToFill.lastError = errCode;
-
- /* build description string */
- if (errCode != 0) { // same as NoComm
- statusToFill.description = "Status frame was not received, check wired connections and web-based config.";
- } else if(statusToFill.bCalIsBooting) {
- statusToFill.description = "Pigeon is boot-caling to properly bias accel and gyro. Do not move Pigeon. When finished biasing, calibration mode will start.";
- } else if(statusToFill.state == UserCalibration) {
- /* mode specific descriptions */
- switch(currentMode) {
- case BootTareGyroAccel:
- statusToFill.description = "Boot-Calibration: Gyro and Accelerometer are being biased.";
- break;
- case Temperature:
- statusToFill.description = "Temperature-Calibration: Pigeon is collecting temp data and will finish when temp range is reached. "
- "Do not moved Pigeon.";
- break;
- case Magnetometer12Pt:
- statusToFill.description = "Magnetometer Level 1 calibration: Orient the Pigeon PCB in the 12 positions documented in the User's Manual.";
- break;
- case Magnetometer360:
- statusToFill.description = "Magnetometer Level 2 calibration: Spin robot slowly in 360' fashion. ";
- break;
- case Accelerometer:
- statusToFill.description = "Accelerometer Calibration: Pigeon PCB must be placed on a level source. Follow User's Guide for how to level surfacee. ";
- break;
- }
- } else if (statusToFill.state == Ready){
- /* definitely not doing anything cal-related. So just instrument the motion driver state */
- statusToFill.description = "Pigeon is running normally. Last CAL error code was ";
- statusToFill.description += std::to_string(calibrationErr);
- statusToFill.description += ".";
- } else if (statusToFill.state == Initializing){
- /* definitely not doing anything cal-related. So just instrument the motion driver state */
- statusToFill.description = "Pigeon is boot-caling to properly bias accel and gyro. Do not move Pigeon.";
- } else {
- statusToFill.description = "Not enough data to determine status.";
- }
-
- return HandleError(errCode);
+ int errCode = ReceiveCAN(COND_STATUS_1);
+
+ uint8_t b3 = (uint8_t)(_cache >> 0x18);
+ uint8_t b5 = (uint8_t)(_cache >> 0x28);
+
+ uint8_t iCurrMode = (b5 >> 4) & 0xF;
+ PigeonImu::CalibrationMode currentMode = (PigeonImu::CalibrationMode)(iCurrMode);
+
+ /* shift up bottom nibble, and back down with sign-extension */
+ int32_t calibrationErr = b5 & 0xF;
+ calibrationErr <<= (32 - 4);
+ calibrationErr >>= (32 - 4);
+
+ int32_t noMotionBiasCount = (uint8_t)(_cache >> 0x24) & 0xF;
+ int32_t tempCompensationCount = (uint8_t)(_cache >> 0x20) & 0xF;
+ int32_t upTimSec = (uint8_t)(_cache >> 0x38);
+
+ statusToFill.currentMode = currentMode;
+ statusToFill.calibrationError = calibrationErr;
+ statusToFill.bCalIsBooting = ((b3 & 1) == 1);
+ statusToFill.state = GetState(errCode, _cache);
+ statusToFill.tempC = GetTemp(_cache);
+ statusToFill.noMotionBiasCount = noMotionBiasCount;
+ statusToFill.tempCompensationCount = tempCompensationCount;
+ statusToFill.upTimeSec = upTimSec;
+ statusToFill.lastError = errCode;
+
+ /* build description string */
+ if (errCode != 0) { // same as NoComm
+ statusToFill.description = "Status frame was not received, check wired connections and web-based config.";
+ } else if(statusToFill.bCalIsBooting) {
+ statusToFill.description = "Pigeon is boot-caling to properly bias accel and gyro. Do not move Pigeon. When finished biasing, calibration mode will start.";
+ } else if(statusToFill.state == UserCalibration) {
+ /* mode specific descriptions */
+ switch(currentMode) {
+ case BootTareGyroAccel:
+ statusToFill.description = "Boot-Calibration: Gyro and Accelerometer are being biased.";
+ break;
+ case Temperature:
+ statusToFill.description = "Temperature-Calibration: Pigeon is collecting temp data and will finish when temp range is reached. "
+ "Do not moved Pigeon.";
+ break;
+ case Magnetometer12Pt:
+ statusToFill.description = "Magnetometer Level 1 calibration: Orient the Pigeon PCB in the 12 positions documented in the User's Manual.";
+ break;
+ case Magnetometer360:
+ statusToFill.description = "Magnetometer Level 2 calibration: Spin robot slowly in 360' fashion. ";
+ break;
+ case Accelerometer:
+ statusToFill.description = "Accelerometer Calibration: Pigeon PCB must be placed on a level source. Follow User's Guide for how to level surfacee. ";
+ break;
+ }
+ } else if (statusToFill.state == Ready){
+ /* definitely not doing anything cal-related. So just instrument the motion driver state */
+ statusToFill.description = "Pigeon is running normally. Last CAL error code was ";
+ statusToFill.description += std::to_string(calibrationErr);
+ statusToFill.description += ".";
+ } else if (statusToFill.state == Initializing){
+ /* definitely not doing anything cal-related. So just instrument the motion driver state */
+ statusToFill.description = "Pigeon is boot-caling to properly bias accel and gyro. Do not move Pigeon.";
+ } else {
+ statusToFill.description = "Not enough data to determine status.";
+ }
+
+ return HandleError(errCode);
}
//----------------------- General Error status -----------------------//
int PigeonImu::GetLastError()
{
- return _lastError;
+ return _lastError;
}
int PigeonImu::HandleError(int errorCode)
{
- /* error handler */
- if (errorCode != 0) {
- /* what should we do here? */
- wpi_setErrorWithContext(errorCode, HAL_GetErrorMessage(errorCode));
- }
- /* mirror last status */
- _lastError = errorCode;
- return _lastError;
+ /* error handler */
+ if (errorCode != 0) {
+ /* what should we do here? */
+ wpi_setErrorWithContext(errorCode, HAL_GetErrorMessage(errorCode));
+ }
+ /* mirror last status */
+ _lastError = errorCode;
+ return _lastError;
}
//----------------------- General Signal decoders -----------------------//
int PigeonImu::ReceiveCAN(int arbId)
{
- return ReceiveCAN(arbId, true);
+ return ReceiveCAN(arbId, true);
}
int PigeonImu::ReceiveCAN(int arbId, bool allowStale)
{
- _len = 0;
- _cache = 0;
- return this->GetRx(arbId | _deviceId, (uint8_t *)&_cache, EXPECTED_RESPONSE_TIMEOUT_MS, allowStale);
+ _len = 0;
+ _cache = 0;
+ return this->GetRx(arbId | _deviceId, (uint8_t *)&_cache, EXPECTED_RESPONSE_TIMEOUT_MS, allowStale);
}
int PigeonImu::SendCAN(int arbId, const uint64_t & data, int dataSize, int periodMs)
{
- int32_t status = 0;
- FRC_NetworkCommunication_CANSessionMux_sendMessage( arbId,
- (const uint8_t*)&data,
- dataSize,
- periodMs,
- &status);
- return status;
+ int32_t status = 0;
+ FRC_NetworkCommunication_CANSessionMux_sendMessage( arbId,
+ (const uint8_t*)&data,
+ dataSize,
+ periodMs,
+ &status);
+ return status;
}
/**
@@ -292,186 +292,186 @@ int PigeonImu::SendCAN(int arbId, const uint64_t & data, int dataSize, int perio
*/
int PigeonImu::GetTwoParam16(int arbId, int16_t words[2])
{
- int errCode = ReceiveCAN(arbId);
- /* always give caller the latest */
- words[0] = (short)((uint8_t)(_cache));
- words[0] <<= 8;
- words[0] |= (short)((uint8_t)(_cache >> 0x08));
+ int errCode = ReceiveCAN(arbId);
+ /* always give caller the latest */
+ words[0] = (short)((uint8_t)(_cache));
+ words[0] <<= 8;
+ words[0] |= (short)((uint8_t)(_cache >> 0x08));
- words[1] = (short)((uint8_t)(_cache >> 0x10));
- words[1] <<= 8;
- words[1] |= (short)((uint8_t)(_cache >> 0x18));
+ words[1] = (short)((uint8_t)(_cache >> 0x10));
+ words[1] <<= 8;
+ words[1] |= (short)((uint8_t)(_cache >> 0x18));
- return errCode;
+ return errCode;
}
int PigeonImu::GetThreeParam16(int arbId, short words[2])
{
- int errCode = ReceiveCAN(arbId);
+ int errCode = ReceiveCAN(arbId);
- words[0] = (short)((uint8_t)(_cache));
- words[0] <<= 8;
- words[0] |= (short)((uint8_t)(_cache >> 0x08));
+ words[0] = (short)((uint8_t)(_cache));
+ words[0] <<= 8;
+ words[0] |= (short)((uint8_t)(_cache >> 0x08));
- words[1] = (short)((uint8_t)(_cache >> 0x10));
- words[1] <<= 8;
- words[1] |= (short)((uint8_t)(_cache >> 0x18));
+ words[1] = (short)((uint8_t)(_cache >> 0x10));
+ words[1] <<= 8;
+ words[1] |= (short)((uint8_t)(_cache >> 0x18));
- words[2] = (short)((uint8_t)(_cache >> 0x20));
- words[2] <<= 8;
- words[2] |= (short)((uint8_t)(_cache >> 0x28));
- return errCode;
+ words[2] = (short)((uint8_t)(_cache >> 0x20));
+ words[2] <<= 8;
+ words[2] |= (short)((uint8_t)(_cache >> 0x28));
+ return errCode;
}
int PigeonImu::GetThreeParam16(int arbId, double signals[3], double scalar)
{
- short word_p1;
- short word_p2;
- short word_p3;
- int errCode = ReceiveCAN(arbId);
+ short word_p1;
+ short word_p2;
+ short word_p3;
+ int errCode = ReceiveCAN(arbId);
- word_p1 = (short)((uint8_t)(_cache));
- word_p1 <<= 8;
- word_p1 |= (short)((uint8_t)(_cache >> 0x08));
+ word_p1 = (short)((uint8_t)(_cache));
+ word_p1 <<= 8;
+ word_p1 |= (short)((uint8_t)(_cache >> 0x08));
- word_p2 = (short)((uint8_t)(_cache >> 0x10));
- word_p2 <<= 8;
- word_p2|= (short)((uint8_t)(_cache >> 0x18));
+ word_p2 = (short)((uint8_t)(_cache >> 0x10));
+ word_p2 <<= 8;
+ word_p2|= (short)((uint8_t)(_cache >> 0x18));
- word_p3 = (short)((uint8_t)(_cache >> 0x20));
- word_p3 <<= 8;
- word_p3 |= (short)((uint8_t)(_cache >> 0x28));
+ word_p3 = (short)((uint8_t)(_cache >> 0x20));
+ word_p3 <<= 8;
+ word_p3 |= (short)((uint8_t)(_cache >> 0x28));
- signals[0] = word_p1 * scalar;
- signals[1] = word_p2 * scalar;
- signals[2] = word_p3 * scalar;
+ signals[0] = word_p1 * scalar;
+ signals[1] = word_p2 * scalar;
+ signals[2] = word_p3 * scalar;
- return errCode;
+ return errCode;
}
int PigeonImu::GetThreeBoundedAngles(int arbId, double boundedAngles[3])
{
- return GetThreeParam16(arbId, boundedAngles, 360. / 32768.);
+ return GetThreeParam16(arbId, boundedAngles, 360. / 32768.);
}
int PigeonImu::GetFourParam16(int arbId, double params[4], double scalar)
{
- short p0,p1,p2,p3;
- int errCode = ReceiveCAN(arbId);
+ short p0,p1,p2,p3;
+ int errCode = ReceiveCAN(arbId);
- p0 = (short)((uint8_t)(_cache));
- p0 <<= 8;
- p0 |= (short)((uint8_t)(_cache >> 0x08));
+ p0 = (short)((uint8_t)(_cache));
+ p0 <<= 8;
+ p0 |= (short)((uint8_t)(_cache >> 0x08));
- p1 = (short)((uint8_t)(_cache >> 0x10));
- p1 <<= 8;
- p1 |= (short)((uint8_t)(_cache >> 0x18));
+ p1 = (short)((uint8_t)(_cache >> 0x10));
+ p1 <<= 8;
+ p1 |= (short)((uint8_t)(_cache >> 0x18));
- p2 = (short)((uint8_t)(_cache >> 0x20));
- p2 <<= 8;
- p2 |= (short)((uint8_t)(_cache >> 0x28));
+ p2 = (short)((uint8_t)(_cache >> 0x20));
+ p2 <<= 8;
+ p2 |= (short)((uint8_t)(_cache >> 0x28));
- p3 = (short)((uint8_t)(_cache >> 0x30));
- p3 <<= 8;
- p3 |= (short)((uint8_t)(_cache >> 0x38));
+ p3 = (short)((uint8_t)(_cache >> 0x30));
+ p3 <<= 8;
+ p3 |= (short)((uint8_t)(_cache >> 0x38));
- /* always give caller the latest */
- params[0] = p0 * scalar;
- params[1] = p1 * scalar;
- params[2] = p2 * scalar;
- params[3] = p3 * scalar;
+ /* always give caller the latest */
+ params[0] = p0 * scalar;
+ params[1] = p1 * scalar;
+ params[2] = p2 * scalar;
+ params[3] = p3 * scalar;
- return errCode;
+ return errCode;
}
int PigeonImu::GetThreeParam20(int arbId, double params[3], double scalar)
{
- int p1, p2, p3;
+ int p1, p2, p3;
- int errCode = ReceiveCAN(arbId);
+ int errCode = ReceiveCAN(arbId);
- uint8_t p1_h8 = (uint8_t)_cache;
- uint8_t p1_m8 = (uint8_t)(_cache >> 8);
- uint8_t p1_l4 = (uint8_t)(_cache >> 20);
+ uint8_t p1_h8 = (uint8_t)_cache;
+ uint8_t p1_m8 = (uint8_t)(_cache >> 8);
+ uint8_t p1_l4 = (uint8_t)(_cache >> 20);
- uint8_t p2_h4 = (uint8_t)(_cache >> 16);
- uint8_t p2_m8 = (uint8_t)(_cache >> 24);
- uint8_t p2_l8 = (uint8_t)(_cache >> 32);
+ uint8_t p2_h4 = (uint8_t)(_cache >> 16);
+ uint8_t p2_m8 = (uint8_t)(_cache >> 24);
+ uint8_t p2_l8 = (uint8_t)(_cache >> 32);
- uint8_t p3_h8 = (uint8_t)(_cache >> 40);
- uint8_t p3_m8 = (uint8_t)(_cache >> 48);
- uint8_t p3_l4 = (uint8_t)(_cache >> 60);
+ uint8_t p3_h8 = (uint8_t)(_cache >> 40);
+ uint8_t p3_m8 = (uint8_t)(_cache >> 48);
+ uint8_t p3_l4 = (uint8_t)(_cache >> 60);
- p1_l4 &= 0xF;
- p2_h4 &= 0xF;
- p3_l4 &= 0xF;
+ p1_l4 &= 0xF;
+ p2_h4 &= 0xF;
+ p3_l4 &= 0xF;
- p1 = p1_h8;
- p1 <<= 8;
- p1 |= p1_m8;
- p1 <<= 4;
- p1 |= p1_l4;
- p1 <<= (32 - 20);
- p1 >>= (32 - 20);
+ p1 = p1_h8;
+ p1 <<= 8;
+ p1 |= p1_m8;
+ p1 <<= 4;
+ p1 |= p1_l4;
+ p1 <<= (32 - 20);
+ p1 >>= (32 - 20);
- p2 = p2_h4;
- p2 <<= 8;
- p2 |= p2_m8;
- p2 <<= 8;
- p2 |= p2_l8;
- p2 <<= (32 - 20);
- p2 >>= (32 - 20);
+ p2 = p2_h4;
+ p2 <<= 8;
+ p2 |= p2_m8;
+ p2 <<= 8;
+ p2 |= p2_l8;
+ p2 <<= (32 - 20);
+ p2 >>= (32 - 20);
- p3 = p3_h8;
- p3 <<= 8;
- p3 |= p3_m8;
- p3 <<= 4;
- p3 |= p3_l4;
- p3 <<= (32 - 20);
- p3 >>= (32 - 20);
+ p3 = p3_h8;
+ p3 <<= 8;
+ p3 |= p3_m8;
+ p3 <<= 4;
+ p3 |= p3_l4;
+ p3 <<= (32 - 20);
+ p3 >>= (32 - 20);
- params[0] = p1 * scalar;
- params[1] = p2 * scalar;
- params[2] = p3 * scalar;
+ params[0] = p1 * scalar;
+ params[1] = p2 * scalar;
+ params[2] = p3 * scalar;
- return errCode;
+ return errCode;
}
//----------------------- Strongly typed Signal decoders -----------------------//
int PigeonImu::Get6dQuaternion(double wxyz[4])
{
- int errCode = GetFourParam16(COND_STATUS_10, wxyz, 1.0 / 16384.);
- return HandleError(errCode);
+ int errCode = GetFourParam16(COND_STATUS_10, wxyz, 1.0 / 16384.);
+ return HandleError(errCode);
}
int PigeonImu::GetYawPitchRoll(double ypr[3])
{
- int errCode = GetThreeParam20(COND_STATUS_9, ypr, (360. / 8192.));
- return HandleError(errCode);
+ int errCode = GetThreeParam20(COND_STATUS_9, ypr, (360. / 8192.));
+ return HandleError(errCode);
}
int PigeonImu::GetAccumGyro(double xyz_deg[3])
{
- int errCode = GetThreeParam20(COND_STATUS_11, xyz_deg, (360. / 8192.));
- return HandleError(errCode);
+ int errCode = GetThreeParam20(COND_STATUS_11, xyz_deg, (360. / 8192.));
+ return HandleError(errCode);
}
/**
* @return compass heading [0,360) degrees.
*/
double PigeonImu::GetAbsoluteCompassHeading()
{
- int32_t raw;
- double retval;
- int errCode = ReceiveCAN(COND_STATUS_2);
+ int32_t raw;
+ double retval;
+ int errCode = ReceiveCAN(COND_STATUS_2);
- uint8_t m8 = (_cache >> 0x30) & 0xFF;
- uint8_t l8 = (_cache >> 0x38) & 0xFF;
+ uint8_t m8 = (_cache >> 0x30) & 0xFF;
+ uint8_t l8 = (_cache >> 0x38) & 0xFF;
- raw = m8;
- raw <<= 8;
- raw |= l8;
- raw &= 0x1FFF;
+ raw = m8;
+ raw <<= 8;
+ raw |= l8;
+ raw &= 0x1FFF;
- retval = raw * (360. / 8192.);
+ retval = raw * (360. / 8192.);
- HandleError(errCode);
- return retval;
+ HandleError(errCode);
+ return retval;
}
/**
* @return continuous compass heading [-23040, 23040) degrees.
@@ -479,106 +479,106 @@ double PigeonImu::GetAbsoluteCompassHeading()
*/
double PigeonImu::GetCompassHeading()
{
- int32_t raw;
- double retval;
- int errCode = ReceiveCAN(COND_STATUS_2);
- uint8_t h4 = (_cache >> 0x28) & 0xF;
- uint8_t m8 = (_cache >> 0x30) & 0xFF;
- uint8_t l8 = (_cache >> 0x38) & 0xFF;
+ int32_t raw;
+ double retval;
+ int errCode = ReceiveCAN(COND_STATUS_2);
+ uint8_t h4 = (_cache >> 0x28) & 0xF;
+ uint8_t m8 = (_cache >> 0x30) & 0xFF;
+ uint8_t l8 = (_cache >> 0x38) & 0xFF;
- raw = h4;
- raw <<= 8;
- raw |= m8;
- raw <<= 8;
- raw |= l8;
- raw <<= (32 - 20);
- raw >>= (32 - 20);
+ raw = h4;
+ raw <<= 8;
+ raw |= m8;
+ raw <<= 8;
+ raw |= l8;
+ raw <<= (32 - 20);
+ raw >>= (32 - 20);
- retval = raw * (360. / 8192.);
+ retval = raw * (360. / 8192.);
- HandleError(errCode);
- return retval;
+ HandleError(errCode);
+ return retval;
}
/**
* @return field strength in Microteslas (uT).
*/
double PigeonImu::GetCompassFieldStrength()
{
- double magnitudeMicroTeslas;
- int16_t words[2];
- int errCode = GetTwoParam16(COND_STATUS_2, words);
- magnitudeMicroTeslas = words[1] * (0.15f);
- HandleError(errCode);
- return magnitudeMicroTeslas;
+ double magnitudeMicroTeslas;
+ int16_t words[2];
+ int errCode = GetTwoParam16(COND_STATUS_2, words);
+ magnitudeMicroTeslas = words[1] * (0.15f);
+ HandleError(errCode);
+ return magnitudeMicroTeslas;
}
double PigeonImu::GetTemp(const uint64_t & statusFrame)
{
- uint8_t H = (uint8_t)(statusFrame >> 0);
- uint8_t L = (uint8_t)(statusFrame >> 8);
- int raw = 0;
- raw |= H;
- raw <<= 8;
- raw |= L;
- double tempC = raw * (1.0f / 256.0f);
- return tempC;
+ uint8_t H = (uint8_t)(statusFrame >> 0);
+ uint8_t L = (uint8_t)(statusFrame >> 8);
+ int raw = 0;
+ raw |= H;
+ raw <<= 8;
+ raw |= L;
+ double tempC = raw * (1.0f / 256.0f);
+ return tempC;
}
double PigeonImu::GetTemp()
{
- int errCode = ReceiveCAN(COND_STATUS_1);
- double tempC = GetTemp(_cache);
- HandleError(errCode);
- return tempC;
+ int errCode = ReceiveCAN(COND_STATUS_1);
+ double tempC = GetTemp(_cache);
+ HandleError(errCode);
+ return tempC;
}
PigeonImu::PigeonState PigeonImu::GetState(int errCode, const uint64_t & statusFrame)
{
- PigeonState retval = PigeonState::NoComm;
-
- if(errCode != 0){
- /* bad frame */
- } else {
- /* good frame */
- uint8_t b2 = (uint8_t)(statusFrame >> 0x10);
-
- MotionDriverState mds = (MotionDriverState)(b2 & 0x1f);
- switch (mds) {
- case Error:
- case Init0:
- case WaitForPowerOff:
- case ConfigAg:
- case SelfTestAg:
- case StartDMP:
- case ConfigCompass_0:
- case ConfigCompass_1:
- case ConfigCompass_2:
- case ConfigCompass_3:
- case ConfigCompass_4:
- case ConfigCompass_5:
- case SelfTestCompass:
- case WaitForGyroStable:
- case AdditionalAccelAdjust:
- retval = PigeonState::Initializing;
- break;
- case Idle:
- retval = PigeonState::Ready;
- break;
- case Calibration:
- case LedInstrum:
- retval = PigeonState::UserCalibration;
- break;
- default:
- retval = PigeonState::Initializing;
- break;
- }
- }
- return retval;
+ PigeonState retval = PigeonState::NoComm;
+
+ if(errCode != 0){
+ /* bad frame */
+ } else {
+ /* good frame */
+ uint8_t b2 = (uint8_t)(statusFrame >> 0x10);
+
+ MotionDriverState mds = (MotionDriverState)(b2 & 0x1f);
+ switch (mds) {
+ case Error:
+ case Init0:
+ case WaitForPowerOff:
+ case ConfigAg:
+ case SelfTestAg:
+ case StartDMP:
+ case ConfigCompass_0:
+ case ConfigCompass_1:
+ case ConfigCompass_2:
+ case ConfigCompass_3:
+ case ConfigCompass_4:
+ case ConfigCompass_5:
+ case SelfTestCompass:
+ case WaitForGyroStable:
+ case AdditionalAccelAdjust:
+ retval = PigeonState::Initializing;
+ break;
+ case Idle:
+ retval = PigeonState::Ready;
+ break;
+ case Calibration:
+ case LedInstrum:
+ retval = PigeonState::UserCalibration;
+ break;
+ default:
+ retval = PigeonState::Initializing;
+ break;
+ }
+ }
+ return retval;
}
PigeonImu::PigeonState PigeonImu::GetState()
{
- int errCode = ReceiveCAN(COND_STATUS_1);
- PigeonState retval = PigeonImu::GetState(errCode, _cache);
- HandleError(errCode);
- return retval;
+ int errCode = ReceiveCAN(COND_STATUS_1);
+ PigeonState retval = PigeonImu::GetState(errCode, _cache);
+ HandleError(errCode);
+ return retval;
}
///
/// How long has Pigeon been running
@@ -587,97 +587,97 @@ PigeonImu::PigeonState PigeonImu::GetState()
///
uint32_t PigeonImu::GetUpTime()
{
- /* repoll status frame */
- int errCode = ReceiveCAN(COND_STATUS_1);
- uint32_t timeSec = (uint8_t)(_cache >> 56);
- HandleError(errCode);
- return timeSec;
+ /* repoll status frame */
+ int errCode = ReceiveCAN(COND_STATUS_1);
+ uint32_t timeSec = (uint8_t)(_cache >> 56);
+ HandleError(errCode);
+ return timeSec;
}
int PigeonImu::GetRawMagnetometer(int16_t rm_xyz[3])
{
- int errCode = GetThreeParam16(RAW_STATUS_4, rm_xyz);
- return HandleError(errCode);
+ int errCode = GetThreeParam16(RAW_STATUS_4, rm_xyz);
+ return HandleError(errCode);
}
int PigeonImu::GetBiasedMagnetometer(int16_t bm_xyz[3])
{
- int errCode = GetThreeParam16(BIASED_STATUS_4, bm_xyz);
- return HandleError(errCode);
+ int errCode = GetThreeParam16(BIASED_STATUS_4, bm_xyz);
+ return HandleError(errCode);
}
int PigeonImu::GetBiasedAccelerometer(int16_t ba_xyz[3])
{
- int errCode = GetThreeParam16(BIASED_STATUS_6, ba_xyz);
- return HandleError(errCode);
+ int errCode = GetThreeParam16(BIASED_STATUS_6, ba_xyz);
+ return HandleError(errCode);
}
int PigeonImu::GetRawGyro(double xyz_dps[3])
{
- int errCode = GetThreeParam16(BIASED_STATUS_2, xyz_dps, 1.0f / 16.4f);
- return HandleError(errCode);
+ int errCode = GetThreeParam16(BIASED_STATUS_2, xyz_dps, 1.0f / 16.4f);
+ return HandleError(errCode);
}
int PigeonImu::GetAccelerometerAngles(double tiltAngles[3])
{
- int errCode = GetThreeBoundedAngles(COND_STATUS_3, tiltAngles);
- return HandleError(errCode);
+ int errCode = GetThreeBoundedAngles(COND_STATUS_3, tiltAngles);
+ return HandleError(errCode);
}
/**
- * @param status object reference to fill with fusion status flags.
- * Caller may omit this parameter if flags are not needed.
+ * @param status object reference to fill with fusion status flags.
+ * Caller may omit this parameter if flags are not needed.
* @return fused heading in degrees.
*/
double PigeonImu::GetFusedHeading(FusionStatus & status)
{
- bool bIsFusing, bIsValid;
- double temp[3];
- double fusedHeading;
-
- int errCode = GetThreeParam20(COND_STATUS_6, temp, 360. / 8192.);
- fusedHeading = temp[0];
- uint8_t b2 = (uint8_t)(_cache >> 16);
-
- std::string description;
-
- if (errCode != 0) {
- bIsFusing = false;
- bIsValid = false;
- description = "Could not receive status frame. Check wiring and web-config.";
- } else {
- int flags = (b2) & 7;
- if (flags == 7) {
- bIsFusing = true;
- } else {
- bIsFusing = false;
- }
-
- if ((b2 & 0x8) == 0) {
- bIsValid = false;
- } else {
- bIsValid = true;
- }
-
- if(bIsValid == false) {
- description = "Fused Heading is not valid.";
- }else if(bIsFusing == false){
- description = "Fused Heading is valid.";
- } else {
- description = "Fused Heading is valid and is fusing compass.";
- }
- }
-
- /* fill caller's struct */
- status.heading = fusedHeading;
- status.bIsFusing = bIsFusing;
- status.bIsValid = bIsValid;
- status.description = description;
- status.lastError = errCode;
-
- HandleError(errCode);
- return fusedHeading;
+ bool bIsFusing, bIsValid;
+ double temp[3];
+ double fusedHeading;
+
+ int errCode = GetThreeParam20(COND_STATUS_6, temp, 360. / 8192.);
+ fusedHeading = temp[0];
+ uint8_t b2 = (uint8_t)(_cache >> 16);
+
+ std::string description;
+
+ if (errCode != 0) {
+ bIsFusing = false;
+ bIsValid = false;
+ description = "Could not receive status frame. Check wiring and web-config.";
+ } else {
+ int flags = (b2) & 7;
+ if (flags == 7) {
+ bIsFusing = true;
+ } else {
+ bIsFusing = false;
+ }
+
+ if ((b2 & 0x8) == 0) {
+ bIsValid = false;
+ } else {
+ bIsValid = true;
+ }
+
+ if(bIsValid == false) {
+ description = "Fused Heading is not valid.";
+ }else if(bIsFusing == false){
+ description = "Fused Heading is valid.";
+ } else {
+ description = "Fused Heading is valid and is fusing compass.";
+ }
+ }
+
+ /* fill caller's struct */
+ status.heading = fusedHeading;
+ status.bIsFusing = bIsFusing;
+ status.bIsValid = bIsValid;
+ status.description = description;
+ status.lastError = errCode;
+
+ HandleError(errCode);
+ return fusedHeading;
}
double PigeonImu::GetFusedHeading()
{
- FusionStatus temp;
- return GetFusedHeading(temp);
+ FusionStatus temp;
+ return GetFusedHeading(temp);
}
//----------------------- Startup/Reset status -----------------------//
/**
@@ -686,101 +686,101 @@ double PigeonImu::GetFusedHeading()
*/
int PigeonImu::GetStartupStatus()
{
- int errCode = ReceiveCAN(COND_STATUS_5, false);
- if (errCode == 0) {
- uint8_t H, L;
- int raw;
- /* frame has been received, therefore motor contorller has reset at least once */
- _resetStats.hasReset = true;
- /* reset count */
- H = (uint8_t)(_cache >> 0);
- L = (uint8_t)(_cache >> 8);
- raw = H << 8 | L;
- _resetStats.resetCount = (int) raw;
- /* reset flags */
- H = (uint8_t)(_cache >> 16);
- L = (uint8_t)(_cache >> 24);
- raw = H << 8 | L;
- _resetStats.resetFlags = (int) raw;
- /* firmVers */
- H = (uint8_t)(_cache >> 32);
- L = (uint8_t)(_cache >> 40);
- raw = H << 8 | L;
- _resetStats.firmVers = (int) raw;
- }
- return errCode;
+ int errCode = ReceiveCAN(COND_STATUS_5, false);
+ if (errCode == 0) {
+ uint8_t H, L;
+ int raw;
+ /* frame has been received, therefore motor contorller has reset at least once */
+ _resetStats.hasReset = true;
+ /* reset count */
+ H = (uint8_t)(_cache >> 0);
+ L = (uint8_t)(_cache >> 8);
+ raw = H << 8 | L;
+ _resetStats.resetCount = (int) raw;
+ /* reset flags */
+ H = (uint8_t)(_cache >> 16);
+ L = (uint8_t)(_cache >> 24);
+ raw = H << 8 | L;
+ _resetStats.resetFlags = (int) raw;
+ /* firmVers */
+ H = (uint8_t)(_cache >> 32);
+ L = (uint8_t)(_cache >> 40);
+ raw = H << 8 | L;
+ _resetStats.firmVers = (int) raw;
+ }
+ return errCode;
}
uint32_t PigeonImu::GetResetCount()
{
- /* repoll status frame */
- int errCode = GetStartupStatus();
- uint32_t retval = _resetStats.resetCount;
- HandleError(errCode);
- return retval;
+ /* repoll status frame */
+ int errCode = GetStartupStatus();
+ uint32_t retval = _resetStats.resetCount;
+ HandleError(errCode);
+ return retval;
}
uint32_t PigeonImu::GetResetFlags()
{
- /* repoll status frame */
- int errCode = GetStartupStatus();
- uint32_t retval = _resetStats.resetFlags;
- HandleError(errCode);
- return retval;
+ /* repoll status frame */
+ int errCode = GetStartupStatus();
+ uint32_t retval = _resetStats.resetFlags;
+ HandleError(errCode);
+ return retval;
}
/**
* @param param holds the version of the Talon. Talon must be powered cycled at least once.
*/
uint32_t PigeonImu::GetFirmVers()
{
- /* repoll status frame */
- int errCode = GetStartupStatus();
- uint32_t retval = _resetStats.firmVers;
- HandleError(errCode);
- return retval;
+ /* repoll status frame */
+ int errCode = GetStartupStatus();
+ uint32_t retval = _resetStats.firmVers;
+ HandleError(errCode);
+ return retval;
}
/**
* @return true iff a reset has occured since last call.
*/
bool PigeonImu::HasResetOccured()
{
- /* repoll status frame, ignore return since hasReset is explicitly tracked */
- GetStartupStatus();
- /* get-then-clear reset flag */
- bool retval = _resetStats.hasReset;
- _resetStats.hasReset = false;
- return retval;
+ /* repoll status frame, ignore return since hasReset is explicitly tracked */
+ GetStartupStatus();
+ /* get-then-clear reset flag */
+ bool retval = _resetStats.hasReset;
+ _resetStats.hasReset = false;
+ return retval;
}
/* static */ std::string PigeonImu::ToString(PigeonState state)
{
- std::string retval = "Unknown";
- switch (state) {
- case Initializing:
- return "Initializing";
- case Ready:
- return "Ready";
- case UserCalibration:
- return "UserCalibration";
- case NoComm:
- return "NoComm";
- }
- return retval;
+ std::string retval = "Unknown";
+ switch (state) {
+ case Initializing:
+ return "Initializing";
+ case Ready:
+ return "Ready";
+ case UserCalibration:
+ return "UserCalibration";
+ case NoComm:
+ return "NoComm";
+ }
+ return retval;
}
/* static */ std::string PigeonImu::ToString(CalibrationMode cm)
{
- std::string retval = "Unknown";
- switch (cm) {
- case BootTareGyroAccel:
- return "BootTareGyroAccel";
- case Temperature:
- return "Temperature";
- case Magnetometer12Pt:
- return "Magnetometer12Pt";
- case Magnetometer360:
- return "Magnetometer360";
- case Accelerometer:
- return "Accelerometer";
- }
- return retval;
+ std::string retval = "Unknown";
+ switch (cm) {
+ case BootTareGyroAccel:
+ return "BootTareGyroAccel";
+ case Temperature:
+ return "Temperature";
+ case Magnetometer12Pt:
+ return "Magnetometer12Pt";
+ case Magnetometer360:
+ return "Magnetometer360";
+ case Accelerometer:
+ return "Accelerometer";
+ }
+ return retval;
}
#endif // CTR_EXCLUDE_WPILIB_CLASSES
diff --git a/Season2016/CPP_Pigeon_StraightServo_Example/src/Robot.cpp b/Season2016/CPP_Pigeon_StraightServo_Example/src/Robot.cpp
index f2a14a1..93f5c97 100644
--- a/Season2016/CPP_Pigeon_StraightServo_Example/src/Robot.cpp
+++ b/Season2016/CPP_Pigeon_StraightServo_Example/src/Robot.cpp
@@ -13,208 +13,208 @@
#include "WPILib.h"
#include "PigeonImu.h"
class Robot: public IterativeRobot {
- /* robot peripherals */
- CANTalon * _leftFront;
- CANTalon * _rightFront;
- CANTalon * _leftRear;
- CANTalon * _rightRear;
- CANTalon * _spareTalon; /* spare talon, remove if not necessary, Pigeon can be placed on CANbus or plugged into a Talon. */
- PigeonImu * _pidgey;
- Joystick *_driveStick; /* Joystick object on USB port 1 */
- /** state for tracking whats controlling the drivetrain */
- enum {
- GoStraightOff, GoStraightWithPidgeon, GoStraightSameThrottle
- } _goStraight = GoStraightOff;
+ /* robot peripherals */
+ CANTalon * _leftFront;
+ CANTalon * _rightFront;
+ CANTalon * _leftRear;
+ CANTalon * _rightRear;
+ CANTalon * _spareTalon; /* spare talon, remove if not necessary, Pigeon can be placed on CANbus or plugged into a Talon. */
+ PigeonImu * _pidgey;
+ Joystick *_driveStick; /* Joystick object on USB port 1 */
+ /** state for tracking whats controlling the drivetrain */
+ enum {
+ GoStraightOff, GoStraightWithPidgeon, GoStraightSameThrottle
+ } _goStraight = GoStraightOff;
- /* Some gains for heading servo,
- * these were tweaked by using the web-based config (CAN Talon) and
- * pressing gamepad button 6 to load them.
- */
- double kPgain = 0.04; /* percent throttle per degree of error */
- double kDgain = 0.0004; /* percent throttle per angular velocity dps */
- double kMaxCorrectionRatio = 0.30; /* cap corrective turning throttle to 30 percent of forward throttle */
- /** holds the current angle to servo to */
- double _targetAngle = 0;
- /** count loops to print every second or so */
- int _printLoops = 0;
+ /* Some gains for heading servo,
+ * these were tweaked by using the web-based config (CAN Talon) and
+ * pressing gamepad button 6 to load them.
+ */
+ double kPgain = 0.04; /* percent throttle per degree of error */
+ double kDgain = 0.0004; /* percent throttle per angular velocity dps */
+ double kMaxCorrectionRatio = 0.30; /* cap corrective turning throttle to 30 percent of forward throttle */
+ /** holds the current angle to servo to */
+ double _targetAngle = 0;
+ /** count loops to print every second or so */
+ int _printLoops = 0;
public:
- /**
- * Constructor for this class.
- */
- Robot() {
- _leftFront = new CANTalon(6);
- _rightFront = new CANTalon(3);
- _leftRear = new CANTalon(4);
- _rightRear = new CANTalon(1);
- _spareTalon = new CANTalon(2);
+ /**
+ * Constructor for this class.
+ */
+ Robot() {
+ _leftFront = new CANTalon(6);
+ _rightFront = new CANTalon(3);
+ _leftRear = new CANTalon(4);
+ _rightRear = new CANTalon(1);
+ _spareTalon = new CANTalon(2);
- /* choose which cabling method for Pigeon */
- //_pidgey = new PigeonImu(0); /* Pigeon is on CANBus (powered from ~12V, and has a device ID of zero */
- _pidgey = new PigeonImu(_spareTalon); /* Pigeon is ribbon cabled to the specified CANTalon. */
+ /* choose which cabling method for Pigeon */
+ //_pidgey = new PigeonImu(0); /* Pigeon is on CANBus (powered from ~12V, and has a device ID of zero */
+ _pidgey = new PigeonImu(_spareTalon); /* Pigeon is ribbon cabled to the specified CANTalon. */
- /* Define joystick being used at USB port #0 on the Drivers Station */
- _driveStick = new Joystick(0);
- }
+ /* Define joystick being used at USB port #0 on the Drivers Station */
+ _driveStick = new Joystick(0);
+ }
- void TeleopInit() {
- _pidgey->SetFusedHeading(0.0); /* reset heading, angle measurement wraps at plus/minus 23,040 degrees (64 rotations) */
- _goStraight = GoStraightOff;
- }
+ void TeleopInit() {
+ _pidgey->SetFusedHeading(0.0); /* reset heading, angle measurement wraps at plus/minus 23,040 degrees (64 rotations) */
+ _goStraight = GoStraightOff;
+ }
- /**
- * Gets called once for each new packet from the DS.
- */
- void TeleopPeriodic() {
- /* some temps for Pigeon API */
- PigeonImu::GeneralStatus genStatus;
- double xyz_dps[3];
- /* grab some input data from Pigeon and gamepad*/
- _pidgey->GetGeneralStatus(genStatus);
- _pidgey->GetRawGyro(xyz_dps);
- double currentAngle = _pidgey->GetFusedHeading();
- bool angleIsGood = (_pidgey->GetState() == PigeonImu::Ready) ? true : false;
- double currentAngularRate = xyz_dps[2];
- /* get input from gamepad */
- bool userWantsGoStraight = _driveStick->GetRawButton(5); /* top left shoulder button */
- double forwardThrottle = _driveStick->GetAxis(Joystick::kYAxis) * -1.0; /* sign so that positive is forward */
- double turnThrottle = _driveStick->GetAxis(Joystick::kTwistAxis) * -1.0; /* sign so that positive means turn left */
- /* deadbands so centering joysticks always results in zero output */
- forwardThrottle = Db(forwardThrottle);
- turnThrottle = Db(turnThrottle);
- /* simple state machine to update our goStraight selection */
- switch (_goStraight) {
+ /**
+ * Gets called once for each new packet from the DS.
+ */
+ void TeleopPeriodic() {
+ /* some temps for Pigeon API */
+ PigeonImu::GeneralStatus genStatus;
+ double xyz_dps[3];
+ /* grab some input data from Pigeon and gamepad*/
+ _pidgey->GetGeneralStatus(genStatus);
+ _pidgey->GetRawGyro(xyz_dps);
+ double currentAngle = _pidgey->GetFusedHeading();
+ bool angleIsGood = (_pidgey->GetState() == PigeonImu::Ready) ? true : false;
+ double currentAngularRate = xyz_dps[2];
+ /* get input from gamepad */
+ bool userWantsGoStraight = _driveStick->GetRawButton(5); /* top left shoulder button */
+ double forwardThrottle = _driveStick->GetAxis(Joystick::kYAxis) * -1.0; /* sign so that positive is forward */
+ double turnThrottle = _driveStick->GetAxis(Joystick::kTwistAxis) * -1.0; /* sign so that positive means turn left */
+ /* deadbands so centering joysticks always results in zero output */
+ forwardThrottle = Db(forwardThrottle);
+ turnThrottle = Db(turnThrottle);
+ /* simple state machine to update our goStraight selection */
+ switch (_goStraight) {
- /* go straight is off, better check gamepad to see if we should enable the feature */
- case GoStraightOff:
- if (userWantsGoStraight == false) {
- /* nothing to do */
- } else if (angleIsGood == false) {
- /* user wants to servo but Pigeon isn't connected? */
- _goStraight = GoStraightSameThrottle; /* just apply same throttle to both sides */
- } else {
- /* user wants to servo, save the current heading so we know where to servo to. */
- _goStraight = GoStraightWithPidgeon;
- _targetAngle = currentAngle;
- }
- break;
+ /* go straight is off, better check gamepad to see if we should enable the feature */
+ case GoStraightOff:
+ if (userWantsGoStraight == false) {
+ /* nothing to do */
+ } else if (angleIsGood == false) {
+ /* user wants to servo but Pigeon isn't connected? */
+ _goStraight = GoStraightSameThrottle; /* just apply same throttle to both sides */
+ } else {
+ /* user wants to servo, save the current heading so we know where to servo to. */
+ _goStraight = GoStraightWithPidgeon;
+ _targetAngle = currentAngle;
+ }
+ break;
- /* we are servo-ing heading with Pigeon */
- case GoStraightWithPidgeon:
- if (userWantsGoStraight == false) {
- _goStraight = GoStraightOff; /* user let go, turn off the feature */
- } else if (angleIsGood == false) {
- _goStraight = GoStraightSameThrottle; /* we were servoing with pidgy, but we lost connection? Check wiring and deviceID setup */
- } else {
- /* user still wants to drive straight, keep doing it */
- }
- break;
+ /* we are servo-ing heading with Pigeon */
+ case GoStraightWithPidgeon:
+ if (userWantsGoStraight == false) {
+ _goStraight = GoStraightOff; /* user let go, turn off the feature */
+ } else if (angleIsGood == false) {
+ _goStraight = GoStraightSameThrottle; /* we were servoing with pidgy, but we lost connection? Check wiring and deviceID setup */
+ } else {
+ /* user still wants to drive straight, keep doing it */
+ }
+ break;
- /* we are simply applying the same throttle to both sides, apparently Pigeon is not connected */
- case GoStraightSameThrottle:
- if (userWantsGoStraight == false) {
- _goStraight = GoStraightOff; /* user let go, turn off the feature */
- } else {
- /* user still wants to drive straight, keep doing it */
- }
- break;
- }
+ /* we are simply applying the same throttle to both sides, apparently Pigeon is not connected */
+ case GoStraightSameThrottle:
+ if (userWantsGoStraight == false) {
+ _goStraight = GoStraightOff; /* user let go, turn off the feature */
+ } else {
+ /* user still wants to drive straight, keep doing it */
+ }
+ break;
+ }
- /* if we can servo with IMU, do the math here */
- if (_goStraight == GoStraightWithPidgeon) {
- /* very simple Proportional and Derivative (PD) loop with a cap,
- * replace with favorite close loop strategy or leverage future Talon <=> Pigeon features. */
- turnThrottle = (_targetAngle - currentAngle) * kPgain - (currentAngularRate) * kDgain;
- /* the max correction is the forward throttle times a scalar,
- * This can be done a number of ways but basically only apply small turning correction when we are moving slow
- * and larger correction the faster we move. Otherwise you may need stiffer pgain at higher velocities. */
- double maxThrot = MaxCorrection(forwardThrottle, kMaxCorrectionRatio);
- turnThrottle = Cap(turnThrottle, maxThrot);
- } else if (_goStraight == GoStraightSameThrottle) {
- /* clear the turn throttle, just apply same throttle to both sides */
- turnThrottle = 0;
- } else {
- /* do nothing */
- }
+ /* if we can servo with IMU, do the math here */
+ if (_goStraight == GoStraightWithPidgeon) {
+ /* very simple Proportional and Derivative (PD) loop with a cap,
+ * replace with favorite close loop strategy or leverage future Talon <=> Pigeon features. */
+ turnThrottle = (_targetAngle - currentAngle) * kPgain - (currentAngularRate) * kDgain;
+ /* the max correction is the forward throttle times a scalar,
+ * This can be done a number of ways but basically only apply small turning correction when we are moving slow
+ * and larger correction the faster we move. Otherwise you may need stiffer pgain at higher velocities. */
+ double maxThrot = MaxCorrection(forwardThrottle, kMaxCorrectionRatio);
+ turnThrottle = Cap(turnThrottle, maxThrot);
+ } else if (_goStraight == GoStraightSameThrottle) {
+ /* clear the turn throttle, just apply same throttle to both sides */
+ turnThrottle = 0;
+ } else {
+ /* do nothing */
+ }
- /* positive turnThrottle means turn to the left, this can be replaced with ArcadeDrive object, or teams drivetrain object */
- float left = forwardThrottle - turnThrottle;
- float right = forwardThrottle + turnThrottle;
- left = Cap(left, 1.0);
- right = Cap(right, 1.0);
+ /* positive turnThrottle means turn to the left, this can be replaced with ArcadeDrive object, or teams drivetrain object */
+ float left = forwardThrottle - turnThrottle;
+ float right = forwardThrottle + turnThrottle;
+ left = Cap(left, 1.0);
+ right = Cap(right, 1.0);
- /* my right side motors need to drive negative to move robot forward */
- _leftFront->Set(left);
- _leftRear->Set(left);
- _rightFront->Set(-1. * right);
- _rightRear->Set(-1. * right);
+ /* my right side motors need to drive negative to move robot forward */
+ _leftFront->Set(left);
+ _leftRear->Set(left);
+ _rightFront->Set(-1. * right);
+ _rightRear->Set(-1. * right);
- /* some printing for easy debugging */
- if (++_printLoops > 50){
- _printLoops = 0;
- printf("------------------------------------------\n");
- printf("error: %f\n", _targetAngle - currentAngle);
- printf("angle: %f\n", currentAngle);
- printf("rate: %f\n", currentAngularRate);
- printf("noMotionBiasCount: %i\n", genStatus.noMotionBiasCount);
- printf("tempCompensationCount: %i\n", genStatus.tempCompensationCount);
- printf("%s\n", angleIsGood ? "Angle is good" : "Angle is NOT GOOD");
- printf("------------------------------------------\n");
- }
+ /* some printing for easy debugging */
+ if (++_printLoops > 50){
+ _printLoops = 0;
+ printf("------------------------------------------\n");
+ printf("error: %f\n", _targetAngle - currentAngle);
+ printf("angle: %f\n", currentAngle);
+ printf("rate: %f\n", currentAngularRate);
+ printf("noMotionBiasCount: %i\n", genStatus.noMotionBiasCount);
+ printf("tempCompensationCount: %i\n", genStatus.tempCompensationCount);
+ printf("%s\n", angleIsGood ? "Angle is good" : "Angle is NOT GOOD");
+ printf("------------------------------------------\n");
+ }
- /* press btn 6, top right shoulder, to apply gains from webdash. This can
- * be replaced with your favorite means of changing gains. */
- if (_driveStick->GetRawButton(6)) {
- UpdatGains();
- }
- }
+ /* press btn 6, top right shoulder, to apply gains from webdash. This can
+ * be replaced with your favorite means of changing gains. */
+ if (_driveStick->GetRawButton(6)) {
+ UpdatGains();
+ }
+ }
- /** @return 10% deadband */
- double Db(double axisVal) {
- if (axisVal < -0.10)
- return axisVal;
- if (axisVal > +0.10)
- return axisVal;
- return 0;
- }
- /** @param value to cap.
- * @param peak positive double representing the maximum (peak) value.
- * @return a capped value.
- */
- double Cap(double value, double peak) {
- if (value < -peak)
- return -peak;
- if (value > +peak)
- return +peak;
- return value;
- }
- /**
- * As a simple trick, lets take the spare talon and use the web-based
- * config to easily change the gains we use for the Pigeon servo.
- * The talon isn't being used for closed-loop, just use it as a convenient
- * storage for gains.
- */
- void UpdatGains() {
- kPgain = _spareTalon->GetP();
- kDgain = _spareTalon->GetD();
- kMaxCorrectionRatio = _spareTalon->GetF();
- }
- /**
- * Given the robot forward throttle and ratio, return the max
- * corrective turning throttle to adjust for heading. This is
- * a simple method of avoiding using different gains for
- * low speed, high speed, and no-speed (zero turns).
- */
- double MaxCorrection(double forwardThrot, double scalor) {
- /* make it positive */
- if(forwardThrot < 0) {forwardThrot = -forwardThrot;}
- /* max correction is the current forward throttle scaled down */
- forwardThrot *= scalor;
- /* ensure caller is allowed at least 10% throttle,
- * regardless of forward throttle */
- if(forwardThrot < 0.10)
- return 0.10;
- return forwardThrot;
- }
+ /** @return 10% deadband */
+ double Db(double axisVal) {
+ if (axisVal < -0.10)
+ return axisVal;
+ if (axisVal > +0.10)
+ return axisVal;
+ return 0;
+ }
+ /** @param value to cap.
+ * @param peak positive double representing the maximum (peak) value.
+ * @return a capped value.
+ */
+ double Cap(double value, double peak) {
+ if (value < -peak)
+ return -peak;
+ if (value > +peak)
+ return +peak;
+ return value;
+ }
+ /**
+ * As a simple trick, lets take the spare talon and use the web-based
+ * config to easily change the gains we use for the Pigeon servo.
+ * The talon isn't being used for closed-loop, just use it as a convenient
+ * storage for gains.
+ */
+ void UpdatGains() {
+ kPgain = _spareTalon->GetP();
+ kDgain = _spareTalon->GetD();
+ kMaxCorrectionRatio = _spareTalon->GetF();
+ }
+ /**
+ * Given the robot forward throttle and ratio, return the max
+ * corrective turning throttle to adjust for heading. This is
+ * a simple method of avoiding using different gains for
+ * low speed, high speed, and no-speed (zero turns).
+ */
+ double MaxCorrection(double forwardThrot, double scalor) {
+ /* make it positive */
+ if(forwardThrot < 0) {forwardThrot = -forwardThrot;}
+ /* max correction is the current forward throttle scaled down */
+ forwardThrot *= scalor;
+ /* ensure caller is allowed at least 10% throttle,
+ * regardless of forward throttle */
+ if(forwardThrot < 0.10)
+ return 0.10;
+ return forwardThrot;
+ }
};
START_ROBOT_CLASS(Robot)
diff --git a/Season2016/JAVA_Pigeon_StraightServo_Example/.classpath b/Season2016/JAVA_Pigeon_StraightServo_Example/.classpath
index 7f8567a..19345cb 100644
--- a/Season2016/JAVA_Pigeon_StraightServo_Example/.classpath
+++ b/Season2016/JAVA_Pigeon_StraightServo_Example/.classpath
@@ -1,9 +1,9 @@
-
-
-
-
-
-
+
+
+
+
+
+
diff --git a/Season2016/JAVA_Pigeon_StraightServo_Example/.project b/Season2016/JAVA_Pigeon_StraightServo_Example/.project
index bd88159..344d3e0 100644
--- a/Season2016/JAVA_Pigeon_StraightServo_Example/.project
+++ b/Season2016/JAVA_Pigeon_StraightServo_Example/.project
@@ -1,18 +1,18 @@
- JAVA_Pigeon_StraightServo_Example
-
-
-
-
-
- org.eclipse.jdt.core.javabuilder
-
-
-
-
-
- org.eclipse.jdt.core.javanature
- edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
-
+ JAVA_Pigeon_StraightServo_Example
+
+
+
+
+
+ org.eclipse.jdt.core.javabuilder
+
+
+
+
+
+ org.eclipse.jdt.core.javanature
+ edu.wpi.first.wpilib.plugins.core.nature.FRCProjectNature
+
diff --git a/Season2016/JAVA_Pigeon_StraightServo_Example/src/com/ctre/CTR_Code.java b/Season2016/JAVA_Pigeon_StraightServo_Example/src/com/ctre/CTR_Code.java
index 6f60c8b..cadd716 100644
--- a/Season2016/JAVA_Pigeon_StraightServo_Example/src/com/ctre/CTR_Code.java
+++ b/Season2016/JAVA_Pigeon_StraightServo_Example/src/com/ctre/CTR_Code.java
@@ -1,26 +1,26 @@
-package com.ctre;
+package com.c re;
public enum CTR_Code
{
- CTR_OKAY(0), //!< No Error - Function executed as expected
- CTR_RxTimeout(1), //!< CAN frame has not been received within specified period of time.
- CTR_TxTimeout(2), //!< Not used.
- CTR_InvalidParamValue(3), //!< Caller passed an invalid param
- CTR_UnexpectedArbId(4), //!< Specified CAN Id is invalid.
- CTR_TxFailed(5), //!< Could not transmit the CAN frame.
- CTR_SigNotUpdated(6), //!< Have not received an value response for signal.
- CTR_BufferFull(7), //!< Caller attempted to insert data into a buffer that is full.
- CTR_UnknownError(8); //!< Error code not supported
+ CTR_OKAY(0), //!< No Error - Func ion execu ed as expec ed
+ CTR_RxTimeou (1), //!< CAN frame has no been received wi hin specified period of ime.
+ CTR_TxTimeou (2), //!< No used.
+ CTR_InvalidParamValue(3), //!< Caller passed an invalid param
+ CTR_Unexpec edArbId(4), //!< Specified CAN Id is invalid.
+ CTR_TxFailed(5), //!< Could no ransmi he CAN frame.
+ CTR_SigNo Upda ed(6), //!< Have no received an value response for signal.
+ CTR_BufferFull(7), //!< Caller a emp ed o inser da a in o a buffer ha is full.
+ CTR_UnknownError(8); //!< Error code no suppor ed
- private int value; private CTR_Code(int value) { this.value = value; }
- public static CTR_Code getEnum(int value) {
- for (CTR_Code e : CTR_Code.values()) {
- if (e.value == value) {
- return e;
- }
- }
- return CTR_UnknownError;
- }
- public int IntValue() { return value;}
+ priva e in value; priva e CTR_Code(in value) { his.value = value; }
+ public s a ic CTR_Code ge Enum(in value) {
+ for (CTR_Code e : CTR_Code.values()) {
+ if (e.value == value) {
+ re urn e;
+ }
+ }
+ re urn CTR_UnknownError;
+ }
+ public in In Value() { re urn value;}
}
diff --git a/Season2016/JAVA_Pigeon_StraightServo_Example/src/com/ctre/CtreCanMap.java b/Season2016/JAVA_Pigeon_StraightServo_Example/src/com/ctre/CtreCanMap.java
index 8c8cbdf..700f78e 100644
--- a/Season2016/JAVA_Pigeon_StraightServo_Example/src/com/ctre/CtreCanMap.java
+++ b/Season2016/JAVA_Pigeon_StraightServo_Example/src/com/ctre/CtreCanMap.java
@@ -1,130 +1,130 @@
-package com.ctre;
+package com.c re;
-import java.nio.ByteBuffer;
-import java.nio.ByteOrder;
-import java.util.HashMap;
-import java.util.Map;
+impor java.nio.By eBuffer;
+impor java.nio.By eOrder;
+impor java.u il.HashMap;
+impor java.u il.Map;
-import edu.wpi.first.wpilibj.can.CANJNI;
+impor edu.wpi.firs .wpilibj.can.CANJNI;
-public class CtreCanMap {
+public class C reCanMap {
- public class RxEvent {
- public long _data = 0;
- public long _time = 0;
- public int _len = 0;
+ public class RxEven {
+ public long _da a = 0;
+ public long _ ime = 0;
+ public in _len = 0;
- public RxEvent() {
- }
+ public RxEven () {
+ }
- public RxEvent(long data, long time, int len) {
- _data = data;
- _time = time;
- _len = len;
- }
+ public RxEven (long da a, long ime, in len) {
+ _da a = da a;
+ _ ime = ime;
+ _len = len;
+ }
- public RxEvent clone() {
- return new RxEvent(_data, _time, _len);
- }
-
- public void Copy(RxEvent src)
- {
- _data = src._data;
- _time = src._time;
- _len = src._len;
- }
- };
+ public RxEven clone() {
+ re urn new RxEven (_da a, _ ime, _len);
+ }
+
+ public void Copy(RxEven src)
+ {
+ _da a = src._da a;
+ _ ime = src._ ime;
+ _len = src._len;
+ }
+ };
- Map _map = new HashMap();
+ Map _map = new HashMap();
- protected int GetRx(int arbId, int timeoutMs, RxEvent toFill, boolean allowStale) {
- CTR_Code retval = CTR_Code.CTR_RxTimeout;
- /* cap timeout at 999ms */
- if(timeoutMs > 999)
- timeoutMs = 999;
- if(timeoutMs < 100)
- timeoutMs = 100;
+ pro ec ed in Ge Rx(in arbId, in imeou Ms, RxEven oFill, boolean allowS ale) {
+ CTR_Code re val = CTR_Code.CTR_RxTimeou ;
+ /* cap imeou a 999ms */
+ if( imeou Ms > 999)
+ imeou Ms = 999;
+ if( imeou Ms < 100)
+ imeou Ms = 100;
- /* call into JNI to get message */
- try {
-
- ByteBuffer targetedMessageID = ByteBuffer.allocateDirect(4);
- targetedMessageID.order(ByteOrder.LITTLE_ENDIAN);
-
- targetedMessageID.asIntBuffer().put(0, arbId);
-
- ByteBuffer timeStamp = ByteBuffer.allocateDirect(4);
-
- // Get the data.
- ByteBuffer dataBuffer =
- CANJNI.FRCNetCommCANSessionMuxReceiveMessage(targetedMessageID.asIntBuffer(),
- 0xFFFFFFFF, timeStamp);
+ /* call in o JNI o ge message */
+ ry {
+
+ By eBuffer arge edMessageID = By eBuffer.alloca eDirec (4);
+ arge edMessageID.order(By eOrder.LITTLE_ENDIAN);
+
+ arge edMessageID.asIn Buffer().pu (0, arbId);
+
+ By eBuffer imeS amp = By eBuffer.alloca eDirec (4);
+
+ // Ge he da a.
+ By eBuffer da aBuffer =
+ CANJNI.FRCNe CommCANSessionMuxReceiveMessage( arge edMessageID.asIn Buffer(),
+ 0xFFFFFFFF, imeS amp);
- if(( dataBuffer != null) && (timeStamp != null)) {
- /* fresh message */
- toFill._len = dataBuffer.capacity();
- toFill._data = 0;
- if(toFill._len > 0){
- int lenMinusOne = toFill._len - 1;
- for (int i = 0; i < toFill._len; i++) {
- /* grab byte without sign extensions */
- long aByte = dataBuffer.get(lenMinusOne-i);
- aByte &= 0xFF;
- /* stuff little endian */
- toFill._data <<= 8;
- toFill._data |= aByte;
- }
- }
- toFill._time = System.currentTimeMillis();
+ if(( da aBuffer != null) && ( imeS amp != null)) {
+ /* fresh message */
+ oFill._len = da aBuffer.capaci y();
+ oFill._da a = 0;
+ if( oFill._len > 0){
+ in lenMinusOne = oFill._len - 1;
+ for (in i = 0; i < oFill._len; i++) {
+ /* grab by e wi hou sign ex ensions */
+ long aBy e = da aBuffer.ge (lenMinusOne-i);
+ aBy e &= 0xFF;
+ /* s uff li le endian */
+ oFill._da a <<= 8;
+ oFill._da a |= aBy e;
+ }
+ }
+ oFill._ ime = Sys em.curren TimeMillis();
- /* store it */
- _map.put(arbId, toFill.clone());
- retval = CTR_Code.CTR_OKAY;
- }
- else
- {
- /* no message */
- retval = CTR_Code.CTR_RxTimeout;
- }
+ /* s ore i */
+ _map.pu (arbId, oFill.clone());
+ re val = CTR_Code.CTR_OKAY;
+ }
+ else
+ {
+ /* no message */
+ re val = CTR_Code.CTR_RxTimeou ;
+ }
- } catch (Exception e) {
- /* no message, check the cache*/
- retval = CTR_Code.CTR_RxTimeout;
- }
+ } ca ch (Excep ion e) {
+ /* no message, check he cache*/
+ re val = CTR_Code.CTR_RxTimeou ;
+ }
- if (retval != CTR_Code.CTR_OKAY) {
- if(allowStale == false) {
- /* caller does not want old data */
- } else {
- /* lookup object first */
- RxEvent lookup = (RxEvent)_map.get(arbId);
- /* was a message received before */
- if (lookup == null)
- {
- /* leave retval nonzero */
- }
- else
- {
- /* check how old the object is */
- long now = System.currentTimeMillis();
- long timeSince = now - lookup._time;
-
- if(timeSince > timeoutMs)
- {
- /* at least copy the last received despite being old */
- toFill.Copy(lookup);
-
- /* too old, leave retval nonzero */
- }
- else
- {
- /* copy to caller's object */
- toFill.Copy(lookup);
- retval = CTR_Code.CTR_OKAY;
- }
- }
- }
- }
- return retval.IntValue();
- }
+ if (re val != CTR_Code.CTR_OKAY) {
+ if(allowS ale == false) {
+ /* caller does no wan old da a */
+ } else {
+ /* lookup objec firs */
+ RxEven lookup = (RxEven )_map.ge (arbId);
+ /* was a message received before */
+ if (lookup == null)
+ {
+ /* leave re val nonzero */
+ }
+ else
+ {
+ /* check how old he objec is */
+ long now = Sys em.curren TimeMillis();
+ long imeSince = now - lookup._ ime;
+
+ if( imeSince > imeou Ms)
+ {
+ /* a leas copy he las received despi e being old */
+ oFill.Copy(lookup);
+
+ /* oo old, leave re val nonzero */
+ }
+ else
+ {
+ /* copy o caller's objec */
+ oFill.Copy(lookup);
+ re val = CTR_Code.CTR_OKAY;
+ }
+ }
+ }
+ }
+ re urn re val.In Value();
+ }
}
diff --git a/Season2016/JAVA_Pigeon_StraightServo_Example/src/com/ctre/PigeonImu.java b/Season2016/JAVA_Pigeon_StraightServo_Example/src/com/ctre/PigeonImu.java
index 01c171f..73f0396 100644
--- a/Season2016/JAVA_Pigeon_StraightServo_Example/src/com/ctre/PigeonImu.java
+++ b/Season2016/JAVA_Pigeon_StraightServo_Example/src/com/ctre/PigeonImu.java
@@ -35,1028 +35,1028 @@
*/
public class PigeonImu extends CtreCanMap
{
- /** Data object for holding fusion information. */
- public static class FusionStatus {
- public double heading;
- public boolean bIsValid;
- public boolean bIsFusing;
- public String description;
- /**
- * Same as GetLastError()
- */
- public int lastError;
- }
- /** Various calibration modes supported by Pigeon. */
- public enum CalibrationMode {
- BootTareGyroAccel(0),
- Temperature(1),
- Magnetometer12Pt(2),
- Magnetometer360(3),
- Accelerometer(5),
- Unknown(-1);
- private int value; private CalibrationMode(int value) { this.value = value; }
-
- public static CalibrationMode getEnum(int value) {
- for (CalibrationMode e : CalibrationMode.values()) {
- if (e.value == value) {
- return e;
- }
- }
- return Unknown;
- }
- };
- /** Overall state of the Pigeon. */
- public enum PigeonState {
- NoComm,
- Initializing,
- Ready,
- UserCalibration,
- };
- /**
- * Data object for status on current calibration and general status.
- *
- * Pigeon has many calibration modes supported for a variety of uses.
- * The modes generally collects and saves persistently information that makes
- * the Pigeon signals more accurate. This includes collecting temperature, gyro, accelerometer,
- * and compass information.
- *
- * For FRC use-cases, typically compass and temperature calibration is not required.
- *
- * Additionally when motion driver software in the Pigeon boots, it will perform a fast boot calibration
- * to initially bias gyro and setup accelerometer.
- *
- * These modes can be enabled with the EnterCalibration mode.
- *
- * When a calibration mode is entered, caller can expect...
- *
- * - PigeonState to reset to Initializing and bCalIsBooting is set to true. Pigeon LEDs will blink the boot pattern.
- * This is similar to the normal boot cal, however it can an additional ~30 seconds since calibration generally
- * requires more information.
- * currentMode will reflect the user's selected calibration mode.
- *
- * - PigeonState will eventually settle to UserCalibration and Pigeon LEDs will show cal specific blink patterns.
- * bCalIsBooting is now false.
- *
- * - Follow the instructions in the Pigeon User Manual to meet the calibration specific requirements.
- * When finished calibrationError will update with the result.
- * Pigeon will solid-fill LEDs with red (for failure) or green (for success) for ~5 seconds.
- * Pigeon then perform boot-cal to cleanly apply the newly saved calibration data.
- */
- public static class GeneralStatus {
- /**
- * The current state of the motion driver. This reflects if the sensor signals are accurate.
- * Most calibration modes will force Pigeon to reinit the motion driver.
- */
- public PigeonState state;
- /**
- * The currently applied calibration mode if state is in UserCalibration or if bCalIsBooting is true.
- * Otherwise it holds the last selected calibration mode (when calibrationError was updated).
- */
- public CalibrationMode currentMode;
- /**
- * The error code for the last calibration mode.
- * Zero represents a successful cal (with solid green LEDs at end of cal)
- * and nonzero is a failed calibration (with solid red LEDs at end of cal).
- * Different calibration
- */
- public int calibrationError;
- /**
- * After caller requests a calibration mode, pigeon will perform a boot-cal before
- * entering the requested mode. During this period, this flag is set to true.
- */
- public boolean bCalIsBooting;
- /**
- * general string description of current status
- */
- public String description;
- /**
- * Temperature in Celsius
- */
- public double tempC;
- /**
- * Number of seconds Pigeon has been up (since boot).
- * This register is reset on power boot or processor reset.
- * Register is capped at 255 seconds with no wrap around.
- */
- public int upTimeSec;
- /**
- * Number of times the Pigeon has automatically rebiased the gyro.
- * This counter overflows from 15 -> 0 with no cap.
- */
- public int noMotionBiasCount;
- /**
- * Number of times the Pigeon has temperature compensated the various signals.
- * This counter overflows from 15 -> 0 with no cap.
- */
- public int tempCompensationCount;
- /**
- * Same as GetLastError()
- */
- public int lastError;
- };
- /** General Parameter Enums */
- public enum ParamEnum {
- YawOffset(160),
- CompassOffset(161),
- BetaGain(162),
- Reserved163(163),
- GyroNoMotionCal(164),
- EnterCalibration(165),
- FusedHeadingOffset(166),
- StatusFrameRate(169),
- AccumZ(170),
- TempCompDisable(171);
- private int value; private ParamEnum(int value) { this.value = value; }
- };
- /**
- * Enumerated types for frame rate ms.
- */
- public enum StatusFrameRate {
- CondStatus_1_General (2),
- CondStatus_9_SixDeg_YPR (3),
- CondStatus_6_SensorFusion (4),
- CondStatus_11_GyroAccum (5),
- CondStatus_2_GeneralCompass (11),
- CondStatus_3_GeneralAccel (12),
- CondStatus_10_SixDeg_Quat (14),
- RawStatus_4_Mag (6),
- BiasedStatus_2_Gyro (8),
- BiasedStatus_4_Mag (9),
- BiasedStatus_6_Accel (10);
-
- public int value;
-
- public static StatusFrameRate valueOf(int value) {
- for (StatusFrameRate mode : values()) {
- if (mode.value == value) {
- return mode;
- }
- }
- return null;
- }
-
- StatusFrameRate(int value) {
- this.value = value;
- }
- }
- /** firmware state reported over CAN */
- private enum MotionDriverState
- {
- Init0 (0),
- WaitForPowerOff (1),
- ConfigAg (2),
- SelfTestAg (3),
- StartDMP (4),
- ConfigCompass_0 (5),
- ConfigCompass_1 (6),
- ConfigCompass_2 (7),
- ConfigCompass_3 (8),
- ConfigCompass_4 (9),
- ConfigCompass_5 (10),
- SelfTestCompass (11),
- WaitForGyroStable (12),
- AdditionalAccelAdjust (13),
- Idle (14),
- Calibration (15),
- LedInstrum (16),
- Error (31);
- private int value; private MotionDriverState(int value) { this.value = value; }
-
- public static MotionDriverState getEnum(int value) {
- for (MotionDriverState e : MotionDriverState.values()) {
- if (e.value == value) {
- return e;
- }
- }
- return Error;
- }
- };
- /** sub command for the various Set param enums */
- private enum TareType {
- SetValue (0x00),
- AddOffset (0x01),
- MatchCompass (0x02),
- SetOffset (0xFF);
- private int value; private TareType(int value) { this.value = value; }
- };
- /** data storage for reset signals */
- private class ResetStats {
- public int resetCount;
- public int resetFlags;
- public int firmVers;
- public boolean hasReset;
- };
- ResetStats _resetStats = new ResetStats();
-
- /** Portion of the arbID for all status and control frames. */
- private int _deviceId;
- private int _lastError = 0;
- private long _cache;
- //private int _len;
- private short [] _cache_words = new short[4];
- private double [] _cache_prec = new double[4];
- private RxEvent _rxe = new RxEvent();
-
- /** overall threshold for when frame data is too old */
- private final int EXPECTED_RESPONSE_TIMEOUT_MS = (200);
-
- /** CAN frame defines */
- //private static final int RAW_STATUS_2 = 0x00040C40;
- private static final int RAW_STATUS_4 = 0x00040CC0;
- //private static final int RAW_STATUS_6 = 0x00040D40;
-
- private static final int BIASED_STATUS_2 = 0x00041C40;
- private static final int BIASED_STATUS_4 = 0x00041CC0;
- private static final int BIASED_STATUS_6 = 0x00041D40;
-
- private static final int COND_STATUS_1 = 0x00042000;
- private static final int COND_STATUS_2 = 0x00042040;
- private static final int COND_STATUS_3 = 0x00042080;
- //private static final int COND_STATUS_4 = 0x000420c0;
- private static final int COND_STATUS_5 = 0x00042100;
- private static final int COND_STATUS_6 = 0x00042140;
- //private static final int COND_STATUS_7 = 0x00042180;
- //private static final int COND_STATUS_8 = 0x000421c0;
- private static final int COND_STATUS_9 = 0x00042200;
- private static final int COND_STATUS_10 = 0x00042240;
- private static final int COND_STATUS_11 = 0x00042280;
-
-
- private static final int CONTROL_1 = 0x00042800;
-
- //private static final int PARAM_REQUEST = 0x00042C00;
- //private static final int PARAM_RESPONSE = 0x00042C40;
- private static final int PARAM_SET = 0x00042C80;
-
- //private static final int kParamArbIdValue = PARAM_RESPONSE;
- //private static final int kParamArbIdMask = 0xFFFFFFFF;
-
-
- /**
- * Create a Pigeon object that communicates with Pigeon on CAN Bus.
- * @param deviceNumber CAN Device Id of Pigeon [0,62]
- */
- public PigeonImu(int deviceNumber)
- {
- _deviceId = 0x15000000 | (int)deviceNumber;
-
- SendCAN(CONTROL_1 | _deviceId, 0x00000000, 0, 100);
- }
-
- /**
- * Create a Pigeon object that communciates with Pigeon through the Gadgeteer ribbon
- * @param talonSrx cable connected to a Talon on CAN Bus.
- */
- public PigeonImu(CANTalon talonSrx)
- {
- _deviceId = (int)0x02000000 | talonSrx.getDeviceID();
-
- SendCAN(CONTROL_1 | _deviceId, 0x00000000, 0, 100);
- }
-
- //----------------------- Control Param routines -----------------------//
- /**
- * General setter to allow for the use of future features, without having to update API.
- * @param paramEnum Parameter to set
- * @param paramValue Parameter value
- * @return nonzero error code if set fails.
- */
- public int ConfigSetParameter(ParamEnum paramEnum, double paramValue)
- {
- int frame;
- /* param specific encoders can be placed here */
- frame = (int) paramValue;
- frame <<= 8;
- frame |= (paramEnum.value) & 0xFF;
- int status = SendCAN(PARAM_SET | _deviceId, frame, 5, 0);
- return status;
- }
- private int ConfigSetParameter(ParamEnum paramEnum, TareType tareType, double angleDeg)
- {
- final double deg_per_canunit = 0.015625f;
- int deg_3B = ((int)(angleDeg / deg_per_canunit));
- long paramValue;
- paramValue = (long)deg_3B & 0xFFFFFF;
- paramValue <<= 8;
- paramValue |= (tareType.value) & 0xFF;
- return ConfigSetParameter(paramEnum, (double)paramValue);
- }
- public void SetStatusFrameRateMs(StatusFrameRate stateFrameRate, int periodMs) {
- /* bounds check the period */
- if (periodMs < 1)
- periodMs = 1;
- else if (periodMs > 255)
- periodMs = 255;
- /* bounds frame */
- if(stateFrameRate.value > 255)
- return;
- /* save the unsigned pieces */
- int period = (int)periodMs;
- int idx = (stateFrameRate.value & 0xFF);
- /* assemble */
- int paramValue = period;
- paramValue <<= 8;
- paramValue |= idx;
- /* send the set request */
- ConfigSetParameter(ParamEnum.StatusFrameRate, paramValue);
- }
- public int SetYaw(double angleDeg)
- {
- int errCode = ConfigSetParameter(ParamEnum.YawOffset, TareType.SetValue, angleDeg);
- return HandleError(errCode);
- }
- /**
- * Atomically add to the Yaw register.
- */
- public int AddYaw(double angleDeg)
- {
- int errCode = ConfigSetParameter(ParamEnum.YawOffset, TareType.AddOffset, angleDeg);
- return HandleError(errCode);
- }
- public int SetYawToCompass()
- {
- int errCode = ConfigSetParameter(ParamEnum.YawOffset, TareType.MatchCompass, 0);
- return HandleError(errCode);
- }
- public int SetFusedHeading(double angleDeg)
- {
- int errCode = ConfigSetParameter(ParamEnum.FusedHeadingOffset, TareType.SetValue, angleDeg);
- return HandleError(errCode);
- }
- /**
- * Atomically add to the Fused Heading register.
- */
- public int AddFusedHeading(double angleDeg)
- {
- int errCode = ConfigSetParameter(ParamEnum.FusedHeadingOffset, TareType.AddOffset, angleDeg);
- return HandleError(errCode);
- }
- public int SetFusedHeadingToCompass()
- {
- int errCode = ConfigSetParameter(ParamEnum.FusedHeadingOffset, TareType.MatchCompass, 0);
- return HandleError(errCode);
- }
- public int SetAccumZAngle(double angleDeg)
- {
- int errCode = ConfigSetParameter(ParamEnum.AccumZ, TareType.SetValue, angleDeg);
- return HandleError(errCode);
- }
- /**
- * Enable/Disable Temp compensation. Pigeon defaults with this on at boot.
- * @param tempCompEnable
- * @return nonzero for error, zero for success.
- */
- public int EnableTemperatureCompensation(boolean bTempCompEnable)
- {
- int errCode = ConfigSetParameter(ParamEnum.TempCompDisable, bTempCompEnable ? 0 : 1);
- return HandleError(errCode);
- }
- /**
- * Set the declination for compass.
- * Declination is the difference between Earth Magnetic north, and the geographic "True North".
- */
- int SetCompassDeclination(double angleDegOffset)
- {
- int errCode = ConfigSetParameter(ParamEnum.CompassOffset, TareType.SetOffset, 0);
- return HandleError(errCode);
- }
- /**
- * Sets the compass angle.
- * Although compass is absolute [0,360) degrees, the continuous compass
- * register holds the wrap-arounds.
- */
- int SetCompassAngle(double angleDeg)
- {
- int errCode = ConfigSetParameter(ParamEnum.CompassOffset, TareType.SetValue, 0);
- return HandleError(errCode);
- }
- //----------------------- Calibration routines -----------------------//
- public int EnterCalibrationMode(CalibrationMode calMode)
- {
- long frame;
- frame = calMode.value & 0xFF;
- frame <<= 8;
- frame |= ((int)ParamEnum.EnterCalibration.value) & 0xFF;
- int status = SendCAN(PARAM_SET | _deviceId, frame, 5, 0);
- return status;
- }
- /**
- * Get the status of the current (or previousley complete) calibration.
- * @param statusToFill
- */
- public int GetGeneralStatus(GeneralStatus statusToFill)
- {
- int errCode= ReceiveCAN(COND_STATUS_1);
-
- int b3 = (int)(_cache >> 0x18) & 0xFF;
- int b5 = (int)(_cache >> 0x28) & 0xFF;
-
- int iCurrMode = (b5 >> 4) & 0xF;
- CalibrationMode currentMode = CalibrationMode.getEnum(iCurrMode);
-
- /* shift up bottom nibble, and back down with sign-extension */
- int calibrationErr = (int)b5 & 0xF;
- calibrationErr <<= (32 - 4);
- calibrationErr >>= (32 - 4);
-
- int noMotionBiasCount = (int) (_cache >> 0x24) & 0xF;
- int tempCompensationCount = (int) (_cache >> 0x20) & 0xF;
- int upTimSec = (int) (_cache >> 0x38) & 0xFF;
-
- if (statusToFill != null) {
- statusToFill.currentMode = currentMode;
- statusToFill.calibrationError = calibrationErr;
- statusToFill.bCalIsBooting = ((b3 & 1) == 1);
- statusToFill.state = GetState(errCode, _cache);
- statusToFill.tempC = GetTemp(_cache);
- statusToFill.noMotionBiasCount = noMotionBiasCount;
- statusToFill.tempCompensationCount = tempCompensationCount;
- statusToFill.upTimeSec = upTimSec;
- statusToFill.lastError = errCode;
-
- /* build description string */
- if (errCode != 0) { // same as NoComm
- statusToFill.description = "Status frame was not received, check wired connections and web-based config.";
- } else if(statusToFill.bCalIsBooting) {
- statusToFill.description = "Pigeon is boot-caling to properly bias accel and gyro. Do not move Pigeon. When finished biasing, calibration mode will start.";
- } else if(statusToFill.state == PigeonState.UserCalibration) {
- /* mode specific descriptions */
- switch(currentMode) {
- case BootTareGyroAccel:
- statusToFill.description = "Boot-Calibration: Gyro and Accelerometer are being biased.";
- break;
- case Temperature:
- statusToFill.description = "Temperature-Calibration: Pigeon is collecting temp data and will finish when temp range is reached. " +
- "Do not moved Pigeon.";
- break;
- case Magnetometer12Pt:
- statusToFill.description = "Magnetometer Level 1 calibration: Orient the Pigeon PCB in the 12 positions documented in the User's Manual.";
- break;
- case Magnetometer360:
- statusToFill.description = "Magnetometer Level 2 calibration: Spin robot slowly in 360' fashion. ";
- break;
- case Accelerometer:
- statusToFill.description = "Accelerometer Calibration: Pigeon PCB must be placed on a level source. Follow User's Guide for how to level surfacee. ";
- break;
- case Unknown:
- statusToFill.description = "Unknown Calibration mode: " + iCurrMode;
- break;
- }
- } else if (statusToFill.state == PigeonState.Ready){
- /* definitely not doing anything cal-related. So just instrument the motion driver state */
- statusToFill.description = "Pigeon is running normally. Last CAL error code was ";
- statusToFill.description += calibrationErr;
- statusToFill.description += ".";
- } else if (statusToFill.state == PigeonState.Initializing){
- /* definitely not doing anything cal-related. So just instrument the motion driver state */
- statusToFill.description = "Pigeon is boot-caling to properly bias accel and gyro. Do not move Pigeon.";
- } else {
- statusToFill.description = "Not enough data to determine status.";
- }
- }
- return HandleError(errCode);
- }
- //----------------------- General Error status -----------------------//
- public int GetLastError()
- {
- return _lastError;
- }
- private String GetErrorMessage(int ctrCode)
- {
- CTR_Code code = CTR_Code.getEnum(ctrCode);
- switch(code) {
- case CTR_OKAY:return "CTRE CAN Receive Timeout";
- case CTR_RxTimeout: return "CTRE CAN Receive Timeout";
- case CTR_TxTimeout: return "CTRE CAN Transmit Timeout";
- case CTR_InvalidParamValue: return "CTRE CAN Invalid Parameter";
- case CTR_UnexpectedArbId: return "CTRE Unexpected Arbitration ID (CAN Node ID)";
- case CTR_TxFailed: return "CTRE CAN Transmit Error";
- case CTR_SigNotUpdated:return "CTRE CAN Signal Not Updated";
- case CTR_BufferFull:return "CTRE CAN Buffer Full";
- default:
- case CTR_UnknownError:return "CTRE CAN Unknown Error Value:" + ctrCode;
- }
- }
- private int HandleError(int errorCode)
- {
- /* error handler */
- if (errorCode != 0) {
- /* what should we do here? */
- DriverStation.reportError(GetErrorMessage(errorCode),true);
- }
- /* mirror last status */
- _lastError = errorCode;
- return _lastError;
- }
-
- //----------------------- General Signal decoders -----------------------//
- private int ReceiveCAN(int arbId)
- {
- return ReceiveCAN(arbId, true);
- }
- private int ReceiveCAN(int arbId, boolean allowStale)
- {
- int retval = super.GetRx(arbId | _deviceId, EXPECTED_RESPONSE_TIMEOUT_MS, _rxe, allowStale);
- /* always pass up the data */
- _cache = _rxe._data;
- //_len = _rxe._len;
- return retval;
- }
- int SendCAN(int arbId, long data, int dataSize, int periodMs)
- {
- int retval = 0; /* no means of getting error info for now */
-
+ /** Data object for holding fusion information. */
+ public static class FusionStatus {
+ public double heading;
+ public boolean bIsValid;
+ public boolean bIsFusing;
+ public String description;
+ /**
+ * Same as GetLastError()
+ */
+ public int lastError;
+ }
+ /** Various calibration modes supported by Pigeon. */
+ public enum CalibrationMode {
+ BootTareGyroAccel(0),
+ Temperature(1),
+ Magnetometer12Pt(2),
+ Magnetometer360(3),
+ Accelerometer(5),
+ Unknown(-1);
+ private int value; private CalibrationMode(int value) { this.value = value; }
+
+ public static CalibrationMode getEnum(int value) {
+ for (CalibrationMode e : CalibrationMode.values()) {
+ if (e.value == value) {
+ return e;
+ }
+ }
+ return Unknown;
+ }
+ };
+ /** Overall state of the Pigeon. */
+ public enum PigeonState {
+ NoComm,
+ Initializing,
+ Ready,
+ UserCalibration,
+ };
+ /**
+ * Data object for status on current calibration and general status.
+ *
+ * Pigeon has many calibration modes supported for a variety of uses.
+ * The modes generally collects and saves persistently information that makes
+ * the Pigeon signals more accurate. This includes collecting temperature, gyro, accelerometer,
+ * and compass information.
+ *
+ * For FRC use-cases, typically compass and temperature calibration is not required.
+ *
+ * Additionally when motion driver software in the Pigeon boots, it will perform a fast boot calibration
+ * to initially bias gyro and setup accelerometer.
+ *
+ * These modes can be enabled with the EnterCalibration mode.
+ *
+ * When a calibration mode is entered, caller can expect...
+ *
+ * - PigeonState to reset to Initializing and bCalIsBooting is set to true. Pigeon LEDs will blink the boot pattern.
+ * This is similar to the normal boot cal, however it can an additional ~30 seconds since calibration generally
+ * requires more information.
+ * currentMode will reflect the user's selected calibration mode.
+ *
+ * - PigeonState will eventually settle to UserCalibration and Pigeon LEDs will show cal specific blink patterns.
+ * bCalIsBooting is now false.
+ *
+ * - Follow the instructions in the Pigeon User Manual to meet the calibration specific requirements.
+ * When finished calibrationError will update with the result.
+ * Pigeon will solid-fill LEDs with red (for failure) or green (for success) for ~5 seconds.
+ * Pigeon then perform boot-cal to cleanly apply the newly saved calibration data.
+ */
+ public static class GeneralStatus {
+ /**
+ * The current state of the motion driver. This reflects if the sensor signals are accurate.
+ * Most calibration modes will force Pigeon to reinit the motion driver.
+ */
+ public PigeonState state;
+ /**
+ * The currently applied calibration mode if state is in UserCalibration or if bCalIsBooting is true.
+ * Otherwise it holds the last selected calibration mode (when calibrationError was updated).
+ */
+ public CalibrationMode currentMode;
+ /**
+ * The error code for the last calibration mode.
+ * Zero represents a successful cal (with solid green LEDs at end of cal)
+ * and nonzero is a failed calibration (with solid red LEDs at end of cal).
+ * Different calibration
+ */
+ public int calibrationError;
+ /**
+ * After caller requests a calibration mode, pigeon will perform a boot-cal before
+ * entering the requested mode. During this period, this flag is set to true.
+ */
+ public boolean bCalIsBooting;
+ /**
+ * general string description of current status
+ */
+ public String description;
+ /**
+ * Temperature in Celsius
+ */
+ public double tempC;
+ /**
+ * Number of seconds Pigeon has been up (since boot).
+ * This register is reset on power boot or processor reset.
+ * Register is capped at 255 seconds with no wrap around.
+ */
+ public int upTimeSec;
+ /**
+ * Number of times the Pigeon has automatically rebiased the gyro.
+ * This counter overflows from 15 -> 0 with no cap.
+ */
+ public int noMotionBiasCount;
+ /**
+ * Number of times the Pigeon has temperature compensated the various signals.
+ * This counter overflows from 15 -> 0 with no cap.
+ */
+ public int tempCompensationCount;
+ /**
+ * Same as GetLastError()
+ */
+ public int lastError;
+ };
+ /** General Parameter Enums */
+ public enum ParamEnum {
+ YawOffset(160),
+ CompassOffset(161),
+ BetaGain(162),
+ Reserved163(163),
+ GyroNoMotionCal(164),
+ EnterCalibration(165),
+ FusedHeadingOffset(166),
+ StatusFrameRate(169),
+ AccumZ(170),
+ TempCompDisable(171);
+ private int value; private ParamEnum(int value) { this.value = value; }
+ };
+ /**
+ * Enumerated types for frame rate ms.
+ */
+ public enum StatusFrameRate {
+ CondStatus_1_General (2),
+ CondStatus_9_SixDeg_YPR (3),
+ CondStatus_6_SensorFusion (4),
+ CondStatus_11_GyroAccum (5),
+ CondStatus_2_GeneralCompass (11),
+ CondStatus_3_GeneralAccel (12),
+ CondStatus_10_SixDeg_Quat (14),
+ RawStatus_4_Mag (6),
+ BiasedStatus_2_Gyro (8),
+ BiasedStatus_4_Mag (9),
+ BiasedStatus_6_Accel (10);
+
+ public int value;
+
+ public static StatusFrameRate valueOf(int value) {
+ for (StatusFrameRate mode : values()) {
+ if (mode.value == value) {
+ return mode;
+ }
+ }
+ return null;
+ }
+
+ StatusFrameRate(int value) {
+ this.value = value;
+ }
+ }
+ /** firmware state reported over CAN */
+ private enum MotionDriverState
+ {
+ Init0 (0),
+ WaitForPowerOff (1),
+ ConfigAg (2),
+ SelfTestAg (3),
+ StartDMP (4),
+ ConfigCompass_0 (5),
+ ConfigCompass_1 (6),
+ ConfigCompass_2 (7),
+ ConfigCompass_3 (8),
+ ConfigCompass_4 (9),
+ ConfigCompass_5 (10),
+ SelfTestCompass (11),
+ WaitForGyroStable (12),
+ AdditionalAccelAdjust (13),
+ Idle (14),
+ Calibration (15),
+ LedInstrum (16),
+ Error (31);
+ private int value; private MotionDriverState(int value) { this.value = value; }
+
+ public static MotionDriverState getEnum(int value) {
+ for (MotionDriverState e : MotionDriverState.values()) {
+ if (e.value == value) {
+ return e;
+ }
+ }
+ return Error;
+ }
+ };
+ /** sub command for the various Set param enums */
+ private enum TareType {
+ SetValue (0x00),
+ AddOffset (0x01),
+ MatchCompass (0x02),
+ SetOffset (0xFF);
+ private int value; private TareType(int value) { this.value = value; }
+ };
+ /** data storage for reset signals */
+ private class ResetStats {
+ public int resetCount;
+ public int resetFlags;
+ public int firmVers;
+ public boolean hasReset;
+ };
+ ResetStats _resetStats = new ResetStats();
+
+ /** Portion of the arbID for all status and control frames. */
+ private int _deviceId;
+ private int _lastError = 0;
+ private long _cache;
+ //private int _len;
+ private short [] _cache_words = new short[4];
+ private double [] _cache_prec = new double[4];
+ private RxEvent _rxe = new RxEvent();
+
+ /** overall threshold for when frame data is too old */
+ private final int EXPECTED_RESPONSE_TIMEOUT_MS = (200);
+
+ /** CAN frame defines */
+ //private static final int RAW_STATUS_2 = 0x00040C40;
+ private static final int RAW_STATUS_4 = 0x00040CC0;
+ //private static final int RAW_STATUS_6 = 0x00040D40;
+
+ private static final int BIASED_STATUS_2 = 0x00041C40;
+ private static final int BIASED_STATUS_4 = 0x00041CC0;
+ private static final int BIASED_STATUS_6 = 0x00041D40;
+
+ private static final int COND_STATUS_1 = 0x00042000;
+ private static final int COND_STATUS_2 = 0x00042040;
+ private static final int COND_STATUS_3 = 0x00042080;
+ //private static final int COND_STATUS_4 = 0x000420c0;
+ private static final int COND_STATUS_5 = 0x00042100;
+ private static final int COND_STATUS_6 = 0x00042140;
+ //private static final int COND_STATUS_7 = 0x00042180;
+ //private static final int COND_STATUS_8 = 0x000421c0;
+ private static final int COND_STATUS_9 = 0x00042200;
+ private static final int COND_STATUS_10 = 0x00042240;
+ private static final int COND_STATUS_11 = 0x00042280;
+
+
+ private static final int CONTROL_1 = 0x00042800;
+
+ //private static final int PARAM_REQUEST = 0x00042C00;
+ //private static final int PARAM_RESPONSE = 0x00042C40;
+ private static final int PARAM_SET = 0x00042C80;
+
+ //private static final int kParamArbIdValue = PARAM_RESPONSE;
+ //private static final int kParamArbIdMask = 0xFFFFFFFF;
+
+
+ /**
+ * Create a Pigeon object that communicates with Pigeon on CAN Bus.
+ * @param deviceNumber CAN Device Id of Pigeon [0,62]
+ */
+ public PigeonImu(int deviceNumber)
+ {
+ _deviceId = 0x15000000 | (int)deviceNumber;
+
+ SendCAN(CONTROL_1 | _deviceId, 0x00000000, 0, 100);
+ }
+
+ /**
+ * Create a Pigeon object that communciates with Pigeon through the Gadgeteer ribbon
+ * @param talonSrx cable connected to a Talon on CAN Bus.
+ */
+ public PigeonImu(CANTalon talonSrx)
+ {
+ _deviceId = (int)0x02000000 | talonSrx.getDeviceID();
+
+ SendCAN(CONTROL_1 | _deviceId, 0x00000000, 0, 100);
+ }
+
+ //----------------------- Control Param routines -----------------------//
+ /**
+ * General setter to allow for the use of future features, without having to update API.
+ * @param paramEnum Parameter to set
+ * @param paramValue Parameter value
+ * @return nonzero error code if set fails.
+ */
+ public int ConfigSetParameter(ParamEnum paramEnum, double paramValue)
+ {
+ int frame;
+ /* param specific encoders can be placed here */
+ frame = (int) paramValue;
+ frame <<= 8;
+ frame |= (paramEnum.value) & 0xFF;
+ int status = SendCAN(PARAM_SET | _deviceId, frame, 5, 0);
+ return status;
+ }
+ private int ConfigSetParameter(ParamEnum paramEnum, TareType tareType, double angleDeg)
+ {
+ final double deg_per_canunit = 0.015625f;
+ int deg_3B = ((int)(angleDeg / deg_per_canunit));
+ long paramValue;
+ paramValue = (long)deg_3B & 0xFFFFFF;
+ paramValue <<= 8;
+ paramValue |= (tareType.value) & 0xFF;
+ return ConfigSetParameter(paramEnum, (double)paramValue);
+ }
+ public void SetStatusFrameRateMs(StatusFrameRate stateFrameRate, int periodMs) {
+ /* bounds check the period */
+ if (periodMs < 1)
+ periodMs = 1;
+ else if (periodMs > 255)
+ periodMs = 255;
+ /* bounds frame */
+ if(stateFrameRate.value > 255)
+ return;
+ /* save the unsigned pieces */
+ int period = (int)periodMs;
+ int idx = (stateFrameRate.value & 0xFF);
+ /* assemble */
+ int paramValue = period;
+ paramValue <<= 8;
+ paramValue |= idx;
+ /* send the set request */
+ ConfigSetParameter(ParamEnum.StatusFrameRate, paramValue);
+ }
+ public int SetYaw(double angleDeg)
+ {
+ int errCode = ConfigSetParameter(ParamEnum.YawOffset, TareType.SetValue, angleDeg);
+ return HandleError(errCode);
+ }
+ /**
+ * Atomically add to the Yaw register.
+ */
+ public int AddYaw(double angleDeg)
+ {
+ int errCode = ConfigSetParameter(ParamEnum.YawOffset, TareType.AddOffset, angleDeg);
+ return HandleError(errCode);
+ }
+ public int SetYawToCompass()
+ {
+ int errCode = ConfigSetParameter(ParamEnum.YawOffset, TareType.MatchCompass, 0);
+ return HandleError(errCode);
+ }
+ public int SetFusedHeading(double angleDeg)
+ {
+ int errCode = ConfigSetParameter(ParamEnum.FusedHeadingOffset, TareType.SetValue, angleDeg);
+ return HandleError(errCode);
+ }
+ /**
+ * Atomically add to the Fused Heading register.
+ */
+ public int AddFusedHeading(double angleDeg)
+ {
+ int errCode = ConfigSetParameter(ParamEnum.FusedHeadingOffset, TareType.AddOffset, angleDeg);
+ return HandleError(errCode);
+ }
+ public int SetFusedHeadingToCompass()
+ {
+ int errCode = ConfigSetParameter(ParamEnum.FusedHeadingOffset, TareType.MatchCompass, 0);
+ return HandleError(errCode);
+ }
+ public int SetAccumZAngle(double angleDeg)
+ {
+ int errCode = ConfigSetParameter(ParamEnum.AccumZ, TareType.SetValue, angleDeg);
+ return HandleError(errCode);
+ }
+ /**
+ * Enable/Disable Temp compensation. Pigeon defaults with this on at boot.
+ * @param tempCompEnable
+ * @return nonzero for error, zero for success.
+ */
+ public int EnableTemperatureCompensation(boolean bTempCompEnable)
+ {
+ int errCode = ConfigSetParameter(ParamEnum.TempCompDisable, bTempCompEnable ? 0 : 1);
+ return HandleError(errCode);
+ }
+ /**
+ * Set the declination for compass.
+ * Declination is the difference between Earth Magnetic north, and the geographic "True North".
+ */
+ int SetCompassDeclination(double angleDegOffset)
+ {
+ int errCode = ConfigSetParameter(ParamEnum.CompassOffset, TareType.SetOffset, 0);
+ return HandleError(errCode);
+ }
+ /**
+ * Sets the compass angle.
+ * Although compass is absolute [0,360) degrees, the continuous compass
+ * register holds the wrap-arounds.
+ */
+ int SetCompassAngle(double angleDeg)
+ {
+ int errCode = ConfigSetParameter(ParamEnum.CompassOffset, TareType.SetValue, 0);
+ return HandleError(errCode);
+ }
+ //----------------------- Calibration routines -----------------------//
+ public int EnterCalibrationMode(CalibrationMode calMode)
+ {
+ long frame;
+ frame = calMode.value & 0xFF;
+ frame <<= 8;
+ frame |= ((int)ParamEnum.EnterCalibration.value) & 0xFF;
+ int status = SendCAN(PARAM_SET | _deviceId, frame, 5, 0);
+ return status;
+ }
+ /**
+ * Get the status of the current (or previousley complete) calibration.
+ * @param statusToFill
+ */
+ public int GetGeneralStatus(GeneralStatus statusToFill)
+ {
+ int errCode= ReceiveCAN(COND_STATUS_1);
+
+ int b3 = (int)(_cache >> 0x18) & 0xFF;
+ int b5 = (int)(_cache >> 0x28) & 0xFF;
+
+ int iCurrMode = (b5 >> 4) & 0xF;
+ CalibrationMode currentMode = CalibrationMode.getEnum(iCurrMode);
+
+ /* shift up bottom nibble, and back down with sign-extension */
+ int calibrationErr = (int)b5 & 0xF;
+ calibrationErr <<= (32 - 4);
+ calibrationErr >>= (32 - 4);
+
+ int noMotionBiasCount = (int) (_cache >> 0x24) & 0xF;
+ int tempCompensationCount = (int) (_cache >> 0x20) & 0xF;
+ int upTimSec = (int) (_cache >> 0x38) & 0xFF;
+
+ if (statusToFill != null) {
+ statusToFill.currentMode = currentMode;
+ statusToFill.calibrationError = calibrationErr;
+ statusToFill.bCalIsBooting = ((b3 & 1) == 1);
+ statusToFill.state = GetState(errCode, _cache);
+ statusToFill.tempC = GetTemp(_cache);
+ statusToFill.noMotionBiasCount = noMotionBiasCount;
+ statusToFill.tempCompensationCount = tempCompensationCount;
+ statusToFill.upTimeSec = upTimSec;
+ statusToFill.lastError = errCode;
+
+ /* build description string */
+ if (errCode != 0) { // same as NoComm
+ statusToFill.description = "Status frame was not received, check wired connections and web-based config.";
+ } else if(statusToFill.bCalIsBooting) {
+ statusToFill.description = "Pigeon is boot-caling to properly bias accel and gyro. Do not move Pigeon. When finished biasing, calibration mode will start.";
+ } else if(statusToFill.state == PigeonState.UserCalibration) {
+ /* mode specific descriptions */
+ switch(currentMode) {
+ case BootTareGyroAccel:
+ statusToFill.description = "Boot-Calibration: Gyro and Accelerometer are being biased.";
+ break;
+ case Temperature:
+ statusToFill.description = "Temperature-Calibration: Pigeon is collecting temp data and will finish when temp range is reached. " +
+ "Do not moved Pigeon.";
+ break;
+ case Magnetometer12Pt:
+ statusToFill.description = "Magnetometer Level 1 calibration: Orient the Pigeon PCB in the 12 positions documented in the User's Manual.";
+ break;
+ case Magnetometer360:
+ statusToFill.description = "Magnetometer Level 2 calibration: Spin robot slowly in 360' fashion. ";
+ break;
+ case Accelerometer:
+ statusToFill.description = "Accelerometer Calibration: Pigeon PCB must be placed on a level source. Follow User's Guide for how to level surfacee. ";
+ break;
+ case Unknown:
+ statusToFill.description = "Unknown Calibration mode: " + iCurrMode;
+ break;
+ }
+ } else if (statusToFill.state == PigeonState.Ready){
+ /* definitely not doing anything cal-related. So just instrument the motion driver state */
+ statusToFill.description = "Pigeon is running normally. Last CAL error code was ";
+ statusToFill.description += calibrationErr;
+ statusToFill.description += ".";
+ } else if (statusToFill.state == PigeonState.Initializing){
+ /* definitely not doing anything cal-related. So just instrument the motion driver state */
+ statusToFill.description = "Pigeon is boot-caling to properly bias accel and gyro. Do not move Pigeon.";
+ } else {
+ statusToFill.description = "Not enough data to determine status.";
+ }
+ }
+ return HandleError(errCode);
+ }
+ //----------------------- General Error status -----------------------//
+ public int GetLastError()
+ {
+ return _lastError;
+ }
+ private String GetErrorMessage(int ctrCode)
+ {
+ CTR_Code code = CTR_Code.getEnum(ctrCode);
+ switch(code) {
+ case CTR_OKAY:return "CTRE CAN Receive Timeout";
+ case CTR_RxTimeout: return "CTRE CAN Receive Timeout";
+ case CTR_TxTimeout: return "CTRE CAN Transmit Timeout";
+ case CTR_InvalidParamValue: return "CTRE CAN Invalid Parameter";
+ case CTR_UnexpectedArbId: return "CTRE Unexpected Arbitration ID (CAN Node ID)";
+ case CTR_TxFailed: return "CTRE CAN Transmit Error";
+ case CTR_SigNotUpdated:return "CTRE CAN Signal Not Updated";
+ case CTR_BufferFull:return "CTRE CAN Buffer Full";
+ default:
+ case CTR_UnknownError:return "CTRE CAN Unknown Error Value:" + ctrCode;
+ }
+ }
+ private int HandleError(int errorCode)
+ {
+ /* error handler */
+ if (errorCode != 0) {
+ /* what should we do here? */
+ DriverStation.reportError(GetErrorMessage(errorCode),true);
+ }
+ /* mirror last status */
+ _lastError = errorCode;
+ return _lastError;
+ }
+
+ //----------------------- General Signal decoders -----------------------//
+ private int ReceiveCAN(int arbId)
+ {
+ return ReceiveCAN(arbId, true);
+ }
+ private int ReceiveCAN(int arbId, boolean allowStale)
+ {
+ int retval = super.GetRx(arbId | _deviceId, EXPECTED_RESPONSE_TIMEOUT_MS, _rxe, allowStale);
+ /* always pass up the data */
+ _cache = _rxe._data;
+ //_len = _rxe._len;
+ return retval;
+ }
+ int SendCAN(int arbId, long data, int dataSize, int periodMs)
+ {
+ int retval = 0; /* no means of getting error info for now */
+
ByteBuffer trustedBuffer = ByteBuffer.allocateDirect(dataSize);
- switch (dataSize) {
- default:
- case 8: trustedBuffer.put(7, (byte) (data >> 0x38)); /* fall through */
- case 7: trustedBuffer.put(6, (byte) (data >> 0x30)); /* fall through */
- case 6: trustedBuffer.put(5, (byte) (data >> 0x28)); /* fall through */
- case 5: trustedBuffer.put(4, (byte) (data >> 0x20)); /* fall through */
- case 4: trustedBuffer.put(3, (byte) (data >> 0x18)); /* fall through */
- case 3: trustedBuffer.put(2, (byte) (data >> 0x10)); /* fall through */
- case 2: trustedBuffer.put(1, (byte) (data >> 0x08)); /* fall through */
- case 1: trustedBuffer.put(0, (byte) (data >> 0x00)); break;
- case 0: /* nothing to do */ break;
- }
+ switch (dataSize) {
+ default:
+ case 8: trustedBuffer.put(7, (byte) (data >> 0x38)); /* fall through */
+ case 7: trustedBuffer.put(6, (byte) (data >> 0x30)); /* fall through */
+ case 6: trustedBuffer.put(5, (byte) (data >> 0x28)); /* fall through */
+ case 5: trustedBuffer.put(4, (byte) (data >> 0x20)); /* fall through */
+ case 4: trustedBuffer.put(3, (byte) (data >> 0x18)); /* fall through */
+ case 3: trustedBuffer.put(2, (byte) (data >> 0x10)); /* fall through */
+ case 2: trustedBuffer.put(1, (byte) (data >> 0x08)); /* fall through */
+ case 1: trustedBuffer.put(0, (byte) (data >> 0x00)); break;
+ case 0: /* nothing to do */ break;
+ }
CANJNI.FRCNetCommCANSessionMuxSendMessage(arbId, trustedBuffer, periodMs);
return retval;
}
- /**
- * Decode two 16bit params.
- */
- private int GetTwoParam16(int arbId, short [] words)
- {
- int errCode = ReceiveCAN(arbId);
- /* always give caller the latest */
- if (words.length >= 2) {
- words[0] = (short) ((_cache) & 0xFF);
- words[0] <<= 8;
- words[0] |= ((_cache >> 0x08) & 0xFF);
-
- words[1] = (short) ((_cache >> 0x10) & 0xFF);
- words[1] <<= 8;
- words[1] |= ((_cache >> 0x18) & 0xFF);
- }
- return errCode;
- }
- private int GetThreeParam16(int arbId, short [] words)
- {
- int errCode = ReceiveCAN(arbId);
-
- if (words.length >= 3) {
- words[0] = (short)(_cache & 0xFF);
- words[0] <<= 8;
- words[0] |= (short)((_cache >> 0x08) & 0xFF);
-
- words[1] = (short)((_cache >> 0x10) & 0xFF);
- words[1] <<= 8;
- words[1] |= (short)((_cache >> 0x18) & 0xFF);
-
- words[2] = (short)((_cache >> 0x20) & 0xFF);
- words[2] <<= 8;
- words[2] |= (short)((_cache >> 0x28) & 0xFF);
- }
-
- return errCode;
- }
-
- private int GetThreeParam16(int arbId, double [] signals, double scalar)
- {
- short word_p1;
- short word_p2;
- short word_p3;
- int errCode = ReceiveCAN(arbId);
-
- word_p1 = (short) (_cache & 0xFF);
- word_p1 <<= 8;
- word_p1 |= (short) ((_cache >> 0x08) & 0xFF);
-
- word_p2 = (short) ((_cache >> 0x10) & 0xFF);
- word_p2 <<= 8;
- word_p2 |= (short) ((_cache >> 0x18) & 0xFF);
-
- word_p3 = (short) ((_cache >> 0x20) & 0xFF);
- word_p3 <<= 8;
- word_p3 |= (short) ((_cache >> 0x28) & 0xFF);
-
- if (signals.length >= 3) {
- signals[0] = word_p1 * scalar;
- signals[1] = word_p2 * scalar;
- signals[2] = word_p3 * scalar;
- }
-
- return errCode;
- }
-
- private int GetThreeBoundedAngles(int arbId, double [] boundedAngles)
- {
- return GetThreeParam16(arbId, boundedAngles, 360f / 32768f);
- }
- private int GetFourParam16(int arbId, double [] params, double scalar)
- {
- short p0,p1,p2,p3;
- int errCode = ReceiveCAN(arbId);
-
- p0 = (short) (_cache & 0xFF);
- p0 <<= 8;
- p0 |= (short) ((_cache >> 0x08) & 0xFF);
-
- p1 = (short) ((_cache >> 0x10) & 0xFF);
- p1 <<= 8;
- p1 |= (short) ((_cache >> 0x18) & 0xFF);
-
- p2 = (short) ((_cache >> 0x20) & 0xFF);
- p2 <<= 8;
- p2 |= (short) ((_cache >> 0x28) & 0xFF);
-
- p3 = (short) ((_cache >> 0x30) & 0xFF);
- p3 <<= 8;
- p3 |= (short) ((_cache >> 0x38) & 0xFF);
-
- /* always give caller the latest */
- if (params.length >= 4) {
- params[0] = p0 * scalar;
- params[1] = p1 * scalar;
- params[2] = p2 * scalar;
- params[3] = p3 * scalar;
- }
-
- return errCode;
- }
-
- private int GetThreeParam20(int arbId, double [] params, double scalar)
- {
- int p1, p2, p3;
-
- int errCode = ReceiveCAN(arbId);
-
- int p1_h8 = (int)_cache;
- int p1_m8 = (int)(_cache >> 8);
- int p1_l4 = (int)(_cache >> 20);
-
- int p2_h4 = (int)(_cache >> 16);
- int p2_m8 = (int)(_cache >> 24);
- int p2_l8 = (int)(_cache >> 32);
-
- int p3_h8 = (int)(_cache >> 40);
- int p3_m8 = (int)(_cache >> 48);
- int p3_l4 = (int)(_cache >> 60);
-
- p1_l4 &= 0xF;
- p2_h4 &= 0xF;
- p3_l4 &= 0xF;
-
- p1_h8 &= 0xFF;
- p1_m8 &= 0xFF;
- p2_m8 &= 0xFF;
- p2_l8 &= 0xFF;
- p3_h8 &= 0xFF;
- p3_m8 &= 0xFF;
-
- p1 = p1_h8;
- p1 <<= 8;
- p1 |= p1_m8;
- p1 <<= 4;
- p1 |= p1_l4;
- p1 <<= (32 - 20);
- p1 >>= (32 - 20);
-
- p2 = p2_h4;
- p2 <<= 8;
- p2 |= p2_m8;
- p2 <<= 8;
- p2 |= p2_l8;
- p2 <<= (32 - 20);
- p2 >>= (32 - 20);
-
- p3 = p3_h8;
- p3 <<= 8;
- p3 |= p3_m8;
- p3 <<= 4;
- p3 |= p3_l4;
- p3 <<= (32 - 20);
- p3 >>= (32 - 20);
-
- if(params.length >= 3) {
- params[0] = p1 * scalar;
- params[1] = p2 * scalar;
- params[2] = p3 * scalar;
- }
- return errCode;
- }
- //----------------------- Strongly typed Signal decoders -----------------------//
- public int Get6dQuaternion(double [] wxyz)
- {
- int errCode = GetFourParam16(COND_STATUS_10, wxyz, 1.0 / 16384);
- return HandleError(errCode);
- }
- public int GetYawPitchRoll(double [] ypr)
- {
- int errCode = GetThreeParam20(COND_STATUS_9, ypr, (360. / 8192.));
- return HandleError(errCode);
- }
- public int GetAccumGyro(double xyz_deg[])
- {
- int errCode = GetThreeParam20(COND_STATUS_11, xyz_deg, (360. / 8192.));
- return HandleError(errCode);
- }
- /**
- * @return compass heading [0,360) degrees.
- */
- public double GetAbsoluteCompassHeading()
- {
- int raw;
- double retval;
- int errCode = ReceiveCAN(COND_STATUS_2);
-
- raw = (int) ((_cache >> 0x30) & 0xFF);
- raw <<= 8;
- raw |= ((_cache >> 0x38) & 0xFF);
-
- /* throw out the rotation count */
- raw &= 0x1FFF;
-
- retval = raw * (360. / 8192.);
-
- HandleError(errCode);
- return retval;
- }
- /**
- * @return continuous compass heading [-23040, 23040) degrees.
- * Use SetCompassHeading to modify the wrap-around portion.
- */
- public double GetCompassHeading()
- {
- int raw;
- double retval;
- int errCode = ReceiveCAN(COND_STATUS_2);
- int h4 = (int) ((_cache >> 0x28) & 0xF);
- int m8 = (int) ((_cache >> 0x30) & 0xFF);
- int l8 = (int) ((_cache >> 0x38) & 0xFF);
-
- raw = h4;
- raw <<= 8;
- raw |= m8;
- raw <<= 8;
- raw |= l8;
-
- /* sign extend */
- raw <<= (32 - 20);
- raw >>= (32 - 20);
-
- retval = raw * (360. / 8192.);
-
- HandleError(errCode);
- return retval;
- }
- /**
- * @return field strength in Microteslas (uT).
- */
- public double GetCompassFieldStrength()
- {
- double magnitudeMicroTeslas;
-
- int errCode = GetTwoParam16(COND_STATUS_2, _cache_words);
- magnitudeMicroTeslas = _cache_words[1] * (0.15);
- HandleError(errCode);
- return magnitudeMicroTeslas;
- }
-
- private double GetTemp(long statusFrame)
- {
- int H = (int) ((statusFrame >> 0) & 0xFF);
- int L = (int) ((statusFrame >> 8) & 0xFF);
- int raw = 0;
- raw |= H;
- raw <<= 8;
- raw |= L;
- double tempC = raw * (1.0f / 256.0f);
- return tempC;
- }
- public double GetTemp()
- {
- int errCode = ReceiveCAN(COND_STATUS_1);
- double tempC = GetTemp(_cache);
- HandleError(errCode);
- return tempC;
- }
- private PigeonState GetState(int errCode, long statusFrame)
- {
- PigeonState retval = PigeonState.NoComm;
-
- if(errCode != 0){
- /* bad frame */
- } else {
- /* good frame */
- byte b2 = (byte)(statusFrame >> 0x10);
-
- MotionDriverState mds = MotionDriverState.getEnum(b2 & 0x1f);
- switch (mds) {
- case Error:
- case Init0:
- case WaitForPowerOff:
- case ConfigAg:
- case SelfTestAg:
- case StartDMP:
- case ConfigCompass_0:
- case ConfigCompass_1:
- case ConfigCompass_2:
- case ConfigCompass_3:
- case ConfigCompass_4:
- case ConfigCompass_5:
- case SelfTestCompass:
- case WaitForGyroStable:
- case AdditionalAccelAdjust:
- retval = PigeonState.Initializing;
- break;
- case Idle:
- retval = PigeonState.Ready;
- break;
- case Calibration:
- case LedInstrum:
- retval = PigeonState.UserCalibration;
- break;
- default:
- retval = PigeonState.Initializing;
- break;
- }
- }
- return retval;
- }
- public PigeonState GetState()
- {
- int errCode = ReceiveCAN(COND_STATUS_1);
- PigeonState retval = GetState(errCode, _cache);
- HandleError(errCode);
- return retval;
- }
- ///
- /// How long has Pigeon been running
- ///
- ///
- ///
- public int GetUpTime()
- {
- /* repoll status frame */
- int errCode = ReceiveCAN(COND_STATUS_1);
- int timeSec = (int) ((_cache >> 56) & 0xFF);
- HandleError(errCode);
- return timeSec;
- }
-
- public int GetRawMagnetometer(short [] rm_xyz)
- {
- int errCode = GetThreeParam16(RAW_STATUS_4, rm_xyz);
- return HandleError(errCode);
- }
- public int GetBiasedMagnetometer(short [] bm_xyz)
- {
- int errCode = GetThreeParam16(BIASED_STATUS_4, bm_xyz);
- return HandleError(errCode);
- }
- public int GetBiasedAccelerometer(short [] ba_xyz)
- {
- int errCode = GetThreeParam16(BIASED_STATUS_6, ba_xyz);
- return HandleError(errCode);
- }
- public int GetRawGyro(double [] xyz_dps)
- {
- int errCode = GetThreeParam16(BIASED_STATUS_2, xyz_dps, 1.0f / 16.4f);
- return HandleError(errCode);
- }
-
- public int GetAccelerometerAngles(double [] tiltAngles)
- {
- int errCode = GetThreeBoundedAngles(COND_STATUS_3, tiltAngles);
- return HandleError(errCode);
- }
- /**
- * @param status object reference to fill with fusion status flags.
- * Caller may pass null if flags are not needed.
- * @return fused heading in degrees.
- */
- public double GetFusedHeading(FusionStatus status)
- {
- boolean bIsFusing, bIsValid;
- double fusedHeading;
-
- int errCode = GetThreeParam20(COND_STATUS_6, _cache_prec, 360. / 8192.);
- fusedHeading = _cache_prec[0];
- byte b2 = (byte)(_cache >> 16);
-
- String description;
-
- if (errCode != 0) {
- bIsFusing = false;
- bIsValid = false;
- description = "Could not receive status frame. Check wiring and web-config.";
- } else {
- int flags = (b2) & 7;
- if (flags == 7) {
- bIsFusing = true;
- } else {
- bIsFusing = false;
- }
-
- if ((b2 & 0x8) == 0) {
- bIsValid = false;
- } else {
- bIsValid = true;
- }
-
- if(bIsValid == false) {
- description = "Fused Heading is not valid.";
- }else if(bIsFusing == false){
- description = "Fused Heading is valid.";
- } else {
- description = "Fused Heading is valid and is fusing compass.";
- }
- }
-
- if (status != null) {
- /* fill caller's struct */
- status.heading = fusedHeading;
- status.bIsFusing = bIsFusing;
- status.bIsValid = bIsValid;
- status.description = description;
- status.lastError = errCode;
- }
-
- HandleError(errCode);
- return fusedHeading;
- }
- //----------------------- Startup/Reset status -----------------------//
- /**
- * Polls status5 frame, which is only transmitted on motor controller boot.
- * @return error code.
- */
- private int GetStartupStatus()
- {
- int errCode = ReceiveCAN(COND_STATUS_5, false);
- if (errCode == 0) {
- int H,L;
- int raw;
- /* frame has been received, therefore motor contorller has reset at least once */
- _resetStats.hasReset = true;
- /* reset count */
- H = (int) ((_cache) & 0xFF);
- L = (int) ((_cache >> 0x08) & 0xFF);
- raw = H<<8 | L;
- _resetStats.resetCount = (int)raw;
- /* reset flags */
- H = (int) ((_cache >> 0x10) & 0xFF);
- L = (int) ((_cache >> 0x18) & 0xFF);
- raw = H << 8 | L;
- _resetStats.resetFlags = (int)raw;
- /* firmVers */
- H = (int) ((_cache >> 0x20) & 0xFF);
- L = (int) ((_cache >> 0x28) & 0xFF);
- raw = H << 8 | L;
- _resetStats.firmVers = (int)raw;
- }
- return errCode;
- }
- public int GetResetCount()
- {
- /* repoll status frame */
- int errCode = GetStartupStatus();
- int retval = _resetStats.resetCount;
- HandleError(errCode);
- return retval;
- }
- public int GetResetFlags()
- {
- /* repoll status frame */
- int errCode = GetStartupStatus();
- int retval = _resetStats.resetFlags;
- HandleError(errCode);
- return retval;
- }
- /**
- * @return param holds the version of the Talon. Talon must be powered cycled at least once.
- */
- public int GetFirmVers()
- {
- /* repoll status frame */
- int errCode = GetStartupStatus();
- int retval = _resetStats.firmVers;
- HandleError(errCode);
- return retval;
- }
- /**
- * @return true iff a reset has occured since last call.
- */
- public boolean HasResetOccured()
- {
- /* repoll status frame, ignore return since hasReset is explicitly tracked */
- GetStartupStatus();
- /* get-then-clear reset flag */
- boolean retval = _resetStats.hasReset;
- _resetStats.hasReset = false;
- return retval;
- }
+ /**
+ * Decode two 16bit params.
+ */
+ private int GetTwoParam16(int arbId, short [] words)
+ {
+ int errCode = ReceiveCAN(arbId);
+ /* always give caller the latest */
+ if (words.length >= 2) {
+ words[0] = (short) ((_cache) & 0xFF);
+ words[0] <<= 8;
+ words[0] |= ((_cache >> 0x08) & 0xFF);
+
+ words[1] = (short) ((_cache >> 0x10) & 0xFF);
+ words[1] <<= 8;
+ words[1] |= ((_cache >> 0x18) & 0xFF);
+ }
+ return errCode;
+ }
+ private int GetThreeParam16(int arbId, short [] words)
+ {
+ int errCode = ReceiveCAN(arbId);
+
+ if (words.length >= 3) {
+ words[0] = (short)(_cache & 0xFF);
+ words[0] <<= 8;
+ words[0] |= (short)((_cache >> 0x08) & 0xFF);
+
+ words[1] = (short)((_cache >> 0x10) & 0xFF);
+ words[1] <<= 8;
+ words[1] |= (short)((_cache >> 0x18) & 0xFF);
+
+ words[2] = (short)((_cache >> 0x20) & 0xFF);
+ words[2] <<= 8;
+ words[2] |= (short)((_cache >> 0x28) & 0xFF);
+ }
+
+ return errCode;
+ }
+
+ private int GetThreeParam16(int arbId, double [] signals, double scalar)
+ {
+ short word_p1;
+ short word_p2;
+ short word_p3;
+ int errCode = ReceiveCAN(arbId);
+
+ word_p1 = (short) (_cache & 0xFF);
+ word_p1 <<= 8;
+ word_p1 |= (short) ((_cache >> 0x08) & 0xFF);
+
+ word_p2 = (short) ((_cache >> 0x10) & 0xFF);
+ word_p2 <<= 8;
+ word_p2 |= (short) ((_cache >> 0x18) & 0xFF);
+
+ word_p3 = (short) ((_cache >> 0x20) & 0xFF);
+ word_p3 <<= 8;
+ word_p3 |= (short) ((_cache >> 0x28) & 0xFF);
+
+ if (signals.length >= 3) {
+ signals[0] = word_p1 * scalar;
+ signals[1] = word_p2 * scalar;
+ signals[2] = word_p3 * scalar;
+ }
+
+ return errCode;
+ }
+
+ private int GetThreeBoundedAngles(int arbId, double [] boundedAngles)
+ {
+ return GetThreeParam16(arbId, boundedAngles, 360f / 32768f);
+ }
+ private int GetFourParam16(int arbId, double [] params, double scalar)
+ {
+ short p0,p1,p2,p3;
+ int errCode = ReceiveCAN(arbId);
+
+ p0 = (short) (_cache & 0xFF);
+ p0 <<= 8;
+ p0 |= (short) ((_cache >> 0x08) & 0xFF);
+
+ p1 = (short) ((_cache >> 0x10) & 0xFF);
+ p1 <<= 8;
+ p1 |= (short) ((_cache >> 0x18) & 0xFF);
+
+ p2 = (short) ((_cache >> 0x20) & 0xFF);
+ p2 <<= 8;
+ p2 |= (short) ((_cache >> 0x28) & 0xFF);
+
+ p3 = (short) ((_cache >> 0x30) & 0xFF);
+ p3 <<= 8;
+ p3 |= (short) ((_cache >> 0x38) & 0xFF);
+
+ /* always give caller the latest */
+ if (params.length >= 4) {
+ params[0] = p0 * scalar;
+ params[1] = p1 * scalar;
+ params[2] = p2 * scalar;
+ params[3] = p3 * scalar;
+ }
+
+ return errCode;
+ }
+
+ private int GetThreeParam20(int arbId, double [] params, double scalar)
+ {
+ int p1, p2, p3;
+
+ int errCode = ReceiveCAN(arbId);
+
+ int p1_h8 = (int)_cache;
+ int p1_m8 = (int)(_cache >> 8);
+ int p1_l4 = (int)(_cache >> 20);
+
+ int p2_h4 = (int)(_cache >> 16);
+ int p2_m8 = (int)(_cache >> 24);
+ int p2_l8 = (int)(_cache >> 32);
+
+ int p3_h8 = (int)(_cache >> 40);
+ int p3_m8 = (int)(_cache >> 48);
+ int p3_l4 = (int)(_cache >> 60);
+
+ p1_l4 &= 0xF;
+ p2_h4 &= 0xF;
+ p3_l4 &= 0xF;
+
+ p1_h8 &= 0xFF;
+ p1_m8 &= 0xFF;
+ p2_m8 &= 0xFF;
+ p2_l8 &= 0xFF;
+ p3_h8 &= 0xFF;
+ p3_m8 &= 0xFF;
+
+ p1 = p1_h8;
+ p1 <<= 8;
+ p1 |= p1_m8;
+ p1 <<= 4;
+ p1 |= p1_l4;
+ p1 <<= (32 - 20);
+ p1 >>= (32 - 20);
+
+ p2 = p2_h4;
+ p2 <<= 8;
+ p2 |= p2_m8;
+ p2 <<= 8;
+ p2 |= p2_l8;
+ p2 <<= (32 - 20);
+ p2 >>= (32 - 20);
+
+ p3 = p3_h8;
+ p3 <<= 8;
+ p3 |= p3_m8;
+ p3 <<= 4;
+ p3 |= p3_l4;
+ p3 <<= (32 - 20);
+ p3 >>= (32 - 20);
+
+ if(params.length >= 3) {
+ params[0] = p1 * scalar;
+ params[1] = p2 * scalar;
+ params[2] = p3 * scalar;
+ }
+ return errCode;
+ }
+ //----------------------- Strongly typed Signal decoders -----------------------//
+ public int Get6dQuaternion(double [] wxyz)
+ {
+ int errCode = GetFourParam16(COND_STATUS_10, wxyz, 1.0 / 16384);
+ return HandleError(errCode);
+ }
+ public int GetYawPitchRoll(double [] ypr)
+ {
+ int errCode = GetThreeParam20(COND_STATUS_9, ypr, (360. / 8192.));
+ return HandleError(errCode);
+ }
+ public int GetAccumGyro(double xyz_deg[])
+ {
+ int errCode = GetThreeParam20(COND_STATUS_11, xyz_deg, (360. / 8192.));
+ return HandleError(errCode);
+ }
+ /**
+ * @return compass heading [0,360) degrees.
+ */
+ public double GetAbsoluteCompassHeading()
+ {
+ int raw;
+ double retval;
+ int errCode = ReceiveCAN(COND_STATUS_2);
+
+ raw = (int) ((_cache >> 0x30) & 0xFF);
+ raw <<= 8;
+ raw |= ((_cache >> 0x38) & 0xFF);
+
+ /* throw out the rotation count */
+ raw &= 0x1FFF;
+
+ retval = raw * (360. / 8192.);
+
+ HandleError(errCode);
+ return retval;
+ }
+ /**
+ * @return continuous compass heading [-23040, 23040) degrees.
+ * Use SetCompassHeading to modify the wrap-around portion.
+ */
+ public double GetCompassHeading()
+ {
+ int raw;
+ double retval;
+ int errCode = ReceiveCAN(COND_STATUS_2);
+ int h4 = (int) ((_cache >> 0x28) & 0xF);
+ int m8 = (int) ((_cache >> 0x30) & 0xFF);
+ int l8 = (int) ((_cache >> 0x38) & 0xFF);
+
+ raw = h4;
+ raw <<= 8;
+ raw |= m8;
+ raw <<= 8;
+ raw |= l8;
+
+ /* sign extend */
+ raw <<= (32 - 20);
+ raw >>= (32 - 20);
+
+ retval = raw * (360. / 8192.);
+
+ HandleError(errCode);
+ return retval;
+ }
+ /**
+ * @return field strength in Microteslas (uT).
+ */
+ public double GetCompassFieldStrength()
+ {
+ double magnitudeMicroTeslas;
+
+ int errCode = GetTwoParam16(COND_STATUS_2, _cache_words);
+ magnitudeMicroTeslas = _cache_words[1] * (0.15);
+ HandleError(errCode);
+ return magnitudeMicroTeslas;
+ }
+
+ private double GetTemp(long statusFrame)
+ {
+ int H = (int) ((statusFrame >> 0) & 0xFF);
+ int L = (int) ((statusFrame >> 8) & 0xFF);
+ int raw = 0;
+ raw |= H;
+ raw <<= 8;
+ raw |= L;
+ double tempC = raw * (1.0f / 256.0f);
+ return tempC;
+ }
+ public double GetTemp()
+ {
+ int errCode = ReceiveCAN(COND_STATUS_1);
+ double tempC = GetTemp(_cache);
+ HandleError(errCode);
+ return tempC;
+ }
+ private PigeonState GetState(int errCode, long statusFrame)
+ {
+ PigeonState retval = PigeonState.NoComm;
+
+ if(errCode != 0){
+ /* bad frame */
+ } else {
+ /* good frame */
+ byte b2 = (byte)(statusFrame >> 0x10);
+
+ MotionDriverState mds = MotionDriverState.getEnum(b2 & 0x1f);
+ switch (mds) {
+ case Error:
+ case Init0:
+ case WaitForPowerOff:
+ case ConfigAg:
+ case SelfTestAg:
+ case StartDMP:
+ case ConfigCompass_0:
+ case ConfigCompass_1:
+ case ConfigCompass_2:
+ case ConfigCompass_3:
+ case ConfigCompass_4:
+ case ConfigCompass_5:
+ case SelfTestCompass:
+ case WaitForGyroStable:
+ case AdditionalAccelAdjust:
+ retval = PigeonState.Initializing;
+ break;
+ case Idle:
+ retval = PigeonState.Ready;
+ break;
+ case Calibration:
+ case LedInstrum:
+ retval = PigeonState.UserCalibration;
+ break;
+ default:
+ retval = PigeonState.Initializing;
+ break;
+ }
+ }
+ return retval;
+ }
+ public PigeonState GetState()
+ {
+ int errCode = ReceiveCAN(COND_STATUS_1);
+ PigeonState retval = GetState(errCode, _cache);
+ HandleError(errCode);
+ return retval;
+ }
+ ///
+ /// How long has Pigeon been running
+ ///
+ ///
+ ///
+ public int GetUpTime()
+ {
+ /* repoll status frame */
+ int errCode = ReceiveCAN(COND_STATUS_1);
+ int timeSec = (int) ((_cache >> 56) & 0xFF);
+ HandleError(errCode);
+ return timeSec;
+ }
+
+ public int GetRawMagnetometer(short [] rm_xyz)
+ {
+ int errCode = GetThreeParam16(RAW_STATUS_4, rm_xyz);
+ return HandleError(errCode);
+ }
+ public int GetBiasedMagnetometer(short [] bm_xyz)
+ {
+ int errCode = GetThreeParam16(BIASED_STATUS_4, bm_xyz);
+ return HandleError(errCode);
+ }
+ public int GetBiasedAccelerometer(short [] ba_xyz)
+ {
+ int errCode = GetThreeParam16(BIASED_STATUS_6, ba_xyz);
+ return HandleError(errCode);
+ }
+ public int GetRawGyro(double [] xyz_dps)
+ {
+ int errCode = GetThreeParam16(BIASED_STATUS_2, xyz_dps, 1.0f / 16.4f);
+ return HandleError(errCode);
+ }
+
+ public int GetAccelerometerAngles(double [] tiltAngles)
+ {
+ int errCode = GetThreeBoundedAngles(COND_STATUS_3, tiltAngles);
+ return HandleError(errCode);
+ }
+ /**
+ * @param status object reference to fill with fusion status flags.
+ * Caller may pass null if flags are not needed.
+ * @return fused heading in degrees.
+ */
+ public double GetFusedHeading(FusionStatus status)
+ {
+ boolean bIsFusing, bIsValid;
+ double fusedHeading;
+
+ int errCode = GetThreeParam20(COND_STATUS_6, _cache_prec, 360. / 8192.);
+ fusedHeading = _cache_prec[0];
+ byte b2 = (byte)(_cache >> 16);
+
+ String description;
+
+ if (errCode != 0) {
+ bIsFusing = false;
+ bIsValid = false;
+ description = "Could not receive status frame. Check wiring and web-config.";
+ } else {
+ int flags = (b2) & 7;
+ if (flags == 7) {
+ bIsFusing = true;
+ } else {
+ bIsFusing = false;
+ }
+
+ if ((b2 & 0x8) == 0) {
+ bIsValid = false;
+ } else {
+ bIsValid = true;
+ }
+
+ if(bIsValid == false) {
+ description = "Fused Heading is not valid.";
+ }else if(bIsFusing == false){
+ description = "Fused Heading is valid.";
+ } else {
+ description = "Fused Heading is valid and is fusing compass.";
+ }
+ }
+
+ if (status != null) {
+ /* fill caller's struct */
+ status.heading = fusedHeading;
+ status.bIsFusing = bIsFusing;
+ status.bIsValid = bIsValid;
+ status.description = description;
+ status.lastError = errCode;
+ }
+
+ HandleError(errCode);
+ return fusedHeading;
+ }
+ //----------------------- Startup/Reset status -----------------------//
+ /**
+ * Polls status5 frame, which is only transmitted on motor controller boot.
+ * @return error code.
+ */
+ private int GetStartupStatus()
+ {
+ int errCode = ReceiveCAN(COND_STATUS_5, false);
+ if (errCode == 0) {
+ int H,L;
+ int raw;
+ /* frame has been received, therefore motor contorller has reset at least once */
+ _resetStats.hasReset = true;
+ /* reset count */
+ H = (int) ((_cache) & 0xFF);
+ L = (int) ((_cache >> 0x08) & 0xFF);
+ raw = H<<8 | L;
+ _resetStats.resetCount = (int)raw;
+ /* reset flags */
+ H = (int) ((_cache >> 0x10) & 0xFF);
+ L = (int) ((_cache >> 0x18) & 0xFF);
+ raw = H << 8 | L;
+ _resetStats.resetFlags = (int)raw;
+ /* firmVers */
+ H = (int) ((_cache >> 0x20) & 0xFF);
+ L = (int) ((_cache >> 0x28) & 0xFF);
+ raw = H << 8 | L;
+ _resetStats.firmVers = (int)raw;
+ }
+ return errCode;
+ }
+ public int GetResetCount()
+ {
+ /* repoll status frame */
+ int errCode = GetStartupStatus();
+ int retval = _resetStats.resetCount;
+ HandleError(errCode);
+ return retval;
+ }
+ public int GetResetFlags()
+ {
+ /* repoll status frame */
+ int errCode = GetStartupStatus();
+ int retval = _resetStats.resetFlags;
+ HandleError(errCode);
+ return retval;
+ }
+ /**
+ * @return param holds the version of the Talon. Talon must be powered cycled at least once.
+ */
+ public int GetFirmVers()
+ {
+ /* repoll status frame */
+ int errCode = GetStartupStatus();
+ int retval = _resetStats.firmVers;
+ HandleError(errCode);
+ return retval;
+ }
+ /**
+ * @return true iff a reset has occured since last call.
+ */
+ public boolean HasResetOccured()
+ {
+ /* repoll status frame, ignore return since hasReset is explicitly tracked */
+ GetStartupStatus();
+ /* get-then-clear reset flag */
+ boolean retval = _resetStats.hasReset;
+ _resetStats.hasReset = false;
+ return retval;
+ }
}
diff --git a/Season2016/JAVA_Pigeon_StraightServo_Example/src/org/usfirst/frc/team3539/robot/Robot.java b/Season2016/JAVA_Pigeon_StraightServo_Example/src/org/usfirst/frc/team3539/robot/Robot.java
index db78f05..8f0a873 100644
--- a/Season2016/JAVA_Pigeon_StraightServo_Example/src/org/usfirst/frc/team3539/robot/Robot.java
+++ b/Season2016/JAVA_Pigeon_StraightServo_Example/src/org/usfirst/frc/team3539/robot/Robot.java
@@ -22,209 +22,209 @@
public class Robot extends IterativeRobot {
- /* robot peripherals */
- CANTalon _leftFront;
- CANTalon _rightFront;
- CANTalon _leftRear;
- CANTalon _rightRear;
- CANTalon _spareTalon; /* spare talon, remove if not necessary, Pigeon can be placed on CANbus or plugged into a Talon. */
- PigeonImu _pidgey;
- Joystick _driveStick; /* Joystick object on USB port 1 */
-
- /** state for tracking whats controlling the drivetrain */
- enum GoStraight
- {
- Off, UsePigeon, SameThrottle
- };
-
- GoStraight _goStraight = GoStraight.Off;
-
- /*
- * Some gains for heading servo, these were tweaked by using the web-based
- * config (CAN Talon) and pressing gamepad button 6 to load them.
- */
- double kPgain = 0.04; /* percent throttle per degree of error */
- double kDgain = 0.0004; /* percent throttle per angular velocity dps */
- double kMaxCorrectionRatio = 0.30; /* cap corrective turning throttle to 30 percent of forward throttle */
- /** holds the current angle to servo to */
- double _targetAngle = 0;
- /** count loops to print every second or so */
- int _printLoops = 0;
-
- public Robot() {
- _leftFront = new CANTalon(6);
- _rightFront = new CANTalon(3);
- _leftRear = new CANTalon(4);
- _rightRear = new CANTalon(1);
- _spareTalon = new CANTalon(2);
-
- /* choose which cabling method for Pigeon */
- //_pidgey = new PigeonImu(0); /* Pigeon is on CANBus (powered from ~12V, and has a device ID of zero */
- _pidgey = new PigeonImu(_spareTalon); /* Pigeon is ribbon cabled to the specified CANTalon. */
-
- /* Define joystick being used at USB port #0 on the Drivers Station */
- _driveStick = new Joystick(0);
- }
-
+ /* robot peripherals */
+ CANTalon _leftFront;
+ CANTalon _rightFront;
+ CANTalon _leftRear;
+ CANTalon _rightRear;
+ CANTalon _spareTalon; /* spare talon, remove if not necessary, Pigeon can be placed on CANbus or plugged into a Talon. */
+ PigeonImu _pidgey;
+ Joystick _driveStick; /* Joystick object on USB port 1 */
+
+ /** state for tracking whats controlling the drivetrain */
+ enum GoStraight
+ {
+ Off, UsePigeon, SameThrottle
+ };
+
+ GoStraight _goStraight = GoStraight.Off;
+
+ /*
+ * Some gains for heading servo, these were tweaked by using the web-based
+ * config (CAN Talon) and pressing gamepad button 6 to load them.
+ */
+ double kPgain = 0.04; /* percent throttle per degree of error */
+ double kDgain = 0.0004; /* percent throttle per angular velocity dps */
+ double kMaxCorrectionRatio = 0.30; /* cap corrective turning throttle to 30 percent of forward throttle */
+ /** holds the current angle to servo to */
+ double _targetAngle = 0;
+ /** count loops to print every second or so */
+ int _printLoops = 0;
+
+ public Robot() {
+ _leftFront = new CANTalon(6);
+ _rightFront = new CANTalon(3);
+ _leftRear = new CANTalon(4);
+ _rightRear = new CANTalon(1);
+ _spareTalon = new CANTalon(2);
+
+ /* choose which cabling method for Pigeon */
+ //_pidgey = new PigeonImu(0); /* Pigeon is on CANBus (powered from ~12V, and has a device ID of zero */
+ _pidgey = new PigeonImu(_spareTalon); /* Pigeon is ribbon cabled to the specified CANTalon. */
+
+ /* Define joystick being used at USB port #0 on the Drivers Station */
+ _driveStick = new Joystick(0);
+ }
+
public void teleopInit() {
- _pidgey.SetFusedHeading(0.0); /* reset heading, angle measurement wraps at plus/minus 23,040 degrees (64 rotations) */
- _goStraight = GoStraight.Off;
+ _pidgey.SetFusedHeading(0.0); /* reset heading, angle measurement wraps at plus/minus 23,040 degrees (64 rotations) */
+ _goStraight = GoStraight.Off;
}
-
+
/**
* This function is called periodically during operator control
*/
public void teleopPeriodic() {
- /* some temps for Pigeon API */
- PigeonImu.GeneralStatus genStatus = new PigeonImu.GeneralStatus();
- PigeonImu.FusionStatus fusionStatus = new PigeonImu.FusionStatus();
- double [] xyz_dps = new double [3];
- /* grab some input data from Pigeon and gamepad*/
- _pidgey.GetGeneralStatus(genStatus);
- _pidgey.GetRawGyro(xyz_dps);
- double currentAngle = _pidgey.GetFusedHeading(fusionStatus);
- boolean angleIsGood = (_pidgey.GetState() == PigeonState.Ready) ? true : false;
- double currentAngularRate = xyz_dps[2];
- /* get input from gamepad */
- boolean userWantsGoStraight = _driveStick.getRawButton(5); /* top left shoulder button */
- double forwardThrottle = _driveStick.getAxis(AxisType.kY) * -1.0; /* sign so that positive is forward */
- double turnThrottle = _driveStick.getAxis(AxisType.kTwist) * -1.0; /* sign so that positive means turn left */
- /* deadbands so centering joysticks always results in zero output */
- forwardThrottle = Db(forwardThrottle);
- turnThrottle = Db(turnThrottle);
- /* simple state machine to update our goStraight selection */
- switch (_goStraight) {
-
- /* go straight is off, better check gamepad to see if we should enable the feature */
- case Off:
- if (userWantsGoStraight == false) {
- /* nothing to do */
- } else if (angleIsGood == false) {
- /* user wants to servo but Pigeon isn't connected? */
- _goStraight = GoStraight.SameThrottle; /* just apply same throttle to both sides */
- } else {
- /* user wants to servo, save the current heading so we know where to servo to. */
- _goStraight = GoStraight.UsePigeon;
- _targetAngle = currentAngle;
- }
- break;
-
- /* we are servo-ing heading with Pigeon */
- case UsePigeon:
- if (userWantsGoStraight == false) {
- _goStraight = GoStraight.Off; /* user let go, turn off the feature */
- } else if (angleIsGood == false) {
- _goStraight = GoStraight.SameThrottle; /* we were servoing with pidgy, but we lost connection? Check wiring and deviceID setup */
- } else {
- /* user still wants to drive straight, keep doing it */
- }
- break;
-
- /* we are simply applying the same throttle to both sides, apparently Pigeon is not connected */
- case SameThrottle:
- if (userWantsGoStraight == false) {
- _goStraight = GoStraight.Off; /* user let go, turn off the feature */
- } else {
- /* user still wants to drive straight, keep doing it */
- }
- break;
- }
-
- /* if we can servo with IMU, do the math here */
- if (_goStraight == GoStraight.UsePigeon) {
- /* very simple Proportional and Derivative (PD) loop with a cap,
- * replace with favorite close loop strategy or leverage future Talon <=> Pigeon features. */
- turnThrottle = (_targetAngle - currentAngle) * kPgain - (currentAngularRate) * kDgain;
- /* the max correction is the forward throttle times a scalar,
- * This can be done a number of ways but basically only apply small turning correction when we are moving slow
- * and larger correction the faster we move. Otherwise you may need stiffer pgain at higher velocities. */
- double maxThrot = MaxCorrection(forwardThrottle, kMaxCorrectionRatio);
- turnThrottle = Cap(turnThrottle, maxThrot);
- } else if (_goStraight == GoStraight.SameThrottle) {
- /* clear the turn throttle, just apply same throttle to both sides */
- turnThrottle = 0;
- } else {
- /* do nothing */
- }
-
- /* positive turnThrottle means turn to the left, this can be replaced with ArcadeDrive object, or teams drivetrain object */
- double left = forwardThrottle - turnThrottle;
- double right = forwardThrottle + turnThrottle;
- left = Cap(left, 1.0);
- right = Cap(right, 1.0);
-
- /* my right side motors need to drive negative to move robot forward */
- _leftFront.set(left);
- _leftRear.set(left);
- _rightFront.set(-1. * right);
- _rightRear.set(-1. * right);
-
- /* some printing for easy debugging */
- if (++_printLoops > 50){
- _printLoops = 0;
-
- System.out.println("------------------------------------------");
- System.out.println("error: " + (_targetAngle - currentAngle) );
- System.out.println("angle: "+ currentAngle);
- System.out.println("rate: "+ currentAngularRate);
- System.out.println("noMotionBiasCount: "+ genStatus.noMotionBiasCount);
- System.out.println("tempCompensationCount: "+ genStatus.tempCompensationCount);
- System.out.println( angleIsGood ? "Angle is good" : "Angle is NOT GOOD");
- System.out.println("------------------------------------------");
- }
-
- /* press btn 6, top right shoulder, to apply gains from webdash. This can
- * be replaced with your favorite means of changing gains. */
- if (_driveStick.getRawButton(6)) {
- UpdatGains();
- }
+ /* some temps for Pigeon API */
+ PigeonImu.GeneralStatus genStatus = new PigeonImu.GeneralStatus();
+ PigeonImu.FusionStatus fusionStatus = new PigeonImu.FusionStatus();
+ double [] xyz_dps = new double [3];
+ /* grab some input data from Pigeon and gamepad*/
+ _pidgey.GetGeneralStatus(genStatus);
+ _pidgey.GetRawGyro(xyz_dps);
+ double currentAngle = _pidgey.GetFusedHeading(fusionStatus);
+ boolean angleIsGood = (_pidgey.GetState() == PigeonState.Ready) ? true : false;
+ double currentAngularRate = xyz_dps[2];
+ /* get input from gamepad */
+ boolean userWantsGoStraight = _driveStick.getRawButton(5); /* top left shoulder button */
+ double forwardThrottle = _driveStick.getAxis(AxisType.kY) * -1.0; /* sign so that positive is forward */
+ double turnThrottle = _driveStick.getAxis(AxisType.kTwist) * -1.0; /* sign so that positive means turn left */
+ /* deadbands so centering joysticks always results in zero output */
+ forwardThrottle = Db(forwardThrottle);
+ turnThrottle = Db(turnThrottle);
+ /* simple state machine to update our goStraight selection */
+ switch (_goStraight) {
+
+ /* go straight is off, better check gamepad to see if we should enable the feature */
+ case Off:
+ if (userWantsGoStraight == false) {
+ /* nothing to do */
+ } else if (angleIsGood == false) {
+ /* user wants to servo but Pigeon isn't connected? */
+ _goStraight = GoStraight.SameThrottle; /* just apply same throttle to both sides */
+ } else {
+ /* user wants to servo, save the current heading so we know where to servo to. */
+ _goStraight = GoStraight.UsePigeon;
+ _targetAngle = currentAngle;
+ }
+ break;
+
+ /* we are servo-ing heading with Pigeon */
+ case UsePigeon:
+ if (userWantsGoStraight == false) {
+ _goStraight = GoStraight.Off; /* user let go, turn off the feature */
+ } else if (angleIsGood == false) {
+ _goStraight = GoStraight.SameThrottle; /* we were servoing with pidgy, but we lost connection? Check wiring and deviceID setup */
+ } else {
+ /* user still wants to drive straight, keep doing it */
+ }
+ break;
+
+ /* we are simply applying the same throttle to both sides, apparently Pigeon is not connected */
+ case SameThrottle:
+ if (userWantsGoStraight == false) {
+ _goStraight = GoStraight.Off; /* user let go, turn off the feature */
+ } else {
+ /* user still wants to drive straight, keep doing it */
+ }
+ break;
+ }
+
+ /* if we can servo with IMU, do the math here */
+ if (_goStraight == GoStraight.UsePigeon) {
+ /* very simple Proportional and Derivative (PD) loop with a cap,
+ * replace with favorite close loop strategy or leverage future Talon <=> Pigeon features. */
+ turnThrottle = (_targetAngle - currentAngle) * kPgain - (currentAngularRate) * kDgain;
+ /* the max correction is the forward throttle times a scalar,
+ * This can be done a number of ways but basically only apply small turning correction when we are moving slow
+ * and larger correction the faster we move. Otherwise you may need stiffer pgain at higher velocities. */
+ double maxThrot = MaxCorrection(forwardThrottle, kMaxCorrectionRatio);
+ turnThrottle = Cap(turnThrottle, maxThrot);
+ } else if (_goStraight == GoStraight.SameThrottle) {
+ /* clear the turn throttle, just apply same throttle to both sides */
+ turnThrottle = 0;
+ } else {
+ /* do nothing */
+ }
+
+ /* positive turnThrottle means turn to the left, this can be replaced with ArcadeDrive object, or teams drivetrain object */
+ double left = forwardThrottle - turnThrottle;
+ double right = forwardThrottle + turnThrottle;
+ left = Cap(left, 1.0);
+ right = Cap(right, 1.0);
+
+ /* my right side motors need to drive negative to move robot forward */
+ _leftFront.set(left);
+ _leftRear.set(left);
+ _rightFront.set(-1. * right);
+ _rightRear.set(-1. * right);
+
+ /* some printing for easy debugging */
+ if (++_printLoops > 50){
+ _printLoops = 0;
+
+ System.out.println("------------------------------------------");
+ System.out.println("error: " + (_targetAngle - currentAngle) );
+ System.out.println("angle: "+ currentAngle);
+ System.out.println("rate: "+ currentAngularRate);
+ System.out.println("noMotionBiasCount: "+ genStatus.noMotionBiasCount);
+ System.out.println("tempCompensationCount: "+ genStatus.tempCompensationCount);
+ System.out.println( angleIsGood ? "Angle is good" : "Angle is NOT GOOD");
+ System.out.println("------------------------------------------");
+ }
+
+ /* press btn 6, top right shoulder, to apply gains from webdash. This can
+ * be replaced with your favorite means of changing gains. */
+ if (_driveStick.getRawButton(6)) {
+ UpdatGains();
+ }
}
/** @return 10% deadband */
- double Db(double axisVal) {
- if (axisVal < -0.10)
- return axisVal;
- if (axisVal > +0.10)
- return axisVal;
- return 0;
- }
- /** @param value to cap.
- * @param peak positive double representing the maximum (peak) value.
- * @return a capped value.
- */
- double Cap(double value, double peak) {
- if (value < -peak)
- return -peak;
- if (value > +peak)
- return +peak;
- return value;
- }
- /**
- * As a simple trick, lets take the spare talon and use the web-based
- * config to easily change the gains we use for the Pigeon servo.
- * The talon isn't being used for closed-loop, just use it as a convenient
- * storage for gains.
- */
- void UpdatGains() {
- kPgain = _spareTalon.getP();
- kDgain = _spareTalon.getD();
- kMaxCorrectionRatio = _spareTalon.getF();
- }
- /**
- * Given the robot forward throttle and ratio, return the max
- * corrective turning throttle to adjust for heading. This is
- * a simple method of avoiding using different gains for
- * low speed, high speed, and no-speed (zero turns).
- */
- double MaxCorrection(double forwardThrot, double scalor) {
- /* make it positive */
- if(forwardThrot < 0) {forwardThrot = -forwardThrot;}
- /* max correction is the current forward throttle scaled down */
- forwardThrot *= scalor;
- /* ensure caller is allowed at least 10% throttle,
- * regardless of forward throttle */
- if(forwardThrot < 0.10)
- return 0.10;
- return forwardThrot;
- }
+ double Db(double axisVal) {
+ if (axisVal < -0.10)
+ return axisVal;
+ if (axisVal > +0.10)
+ return axisVal;
+ return 0;
+ }
+ /** @param value to cap.
+ * @param peak positive double representing the maximum (peak) value.
+ * @return a capped value.
+ */
+ double Cap(double value, double peak) {
+ if (value < -peak)
+ return -peak;
+ if (value > +peak)
+ return +peak;
+ return value;
+ }
+ /**
+ * As a simple trick, lets take the spare talon and use the web-based
+ * config to easily change the gains we use for the Pigeon servo.
+ * The talon isn't being used for closed-loop, just use it as a convenient
+ * storage for gains.
+ */
+ void UpdatGains() {
+ kPgain = _spareTalon.getP();
+ kDgain = _spareTalon.getD();
+ kMaxCorrectionRatio = _spareTalon.getF();
+ }
+ /**
+ * Given the robot forward throttle and ratio, return the max
+ * corrective turning throttle to adjust for heading. This is
+ * a simple method of avoiding using different gains for
+ * low speed, high speed, and no-speed (zero turns).
+ */
+ double MaxCorrection(double forwardThrot, double scalor) {
+ /* make it positive */
+ if(forwardThrot < 0) {forwardThrot = -forwardThrot;}
+ /* max correction is the current forward throttle scaled down */
+ forwardThrot *= scalor;
+ /* ensure caller is allowed at least 10% throttle,
+ * regardless of forward throttle */
+ if(forwardThrot < 0.10)
+ return 0.10;
+ return forwardThrot;
+ }
}
diff --git a/Season2016/LabVIEW_Pigeon_StraightServo_Example/FRC Simulated.xml b/Season2016/LabVIEW_Pigeon_StraightServo_Example/FRC Simulated.xml
index d99a6ad..97bb019 100644
--- a/Season2016/LabVIEW_Pigeon_StraightServo_Example/FRC Simulated.xml
+++ b/Season2016/LabVIEW_Pigeon_StraightServo_Example/FRC Simulated.xml
@@ -7622,14 +7622,14 @@
Parameters
-[FMax] 20
-[Fudge Factor] 1
-[Bounce] 0
-[CFM] 0.00001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.6
-[Stop CFM] 0.00001
+[FMax] 20
+[Fudge Factor] 1
+[Bounce] 0
+[CFM] 0.00001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.6
+[Stop CFM] 0.00001
Draw Mode
@@ -7747,14 +7747,14 @@
Parameters
-[FMax] 20
-[Fudge Factor] 1
-[Bounce] 0
-[CFM] 0.00001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.6
-[Stop CFM] 0.00001
+[FMax] 20
+[Fudge Factor] 1
+[Bounce] 0
+[CFM] 0.00001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.6
+[Stop CFM] 0.00001
Draw Mode
@@ -7872,14 +7872,14 @@
Parameters
-[FMax] 20
-[Fudge Factor] 1
-[Bounce] 0
-[CFM] 0.00001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.6
-[Stop CFM] 0.00001
+[FMax] 20
+[Fudge Factor] 1
+[Bounce] 0
+[CFM] 0.00001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.6
+[Stop CFM] 0.00001
Draw Mode
@@ -7997,14 +7997,14 @@
Parameters
-[FMax] 20
-[Fudge Factor] 1
-[Bounce] 0
-[CFM] 0.00001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.6
-[Stop CFM] 0.00001
+[FMax] 20
+[Fudge Factor] 1
+[Bounce] 0
+[CFM] 0.00001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.6
+[Stop CFM] 0.00001
Draw Mode
@@ -8122,7 +8122,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8240,7 +8240,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8358,7 +8358,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8476,7 +8476,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8594,7 +8594,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8712,14 +8712,14 @@
Parameters
-[FMax] 2.5
-[Fudge Factor] 0.1
-[Bounce] 0
-[CFM] 0.001
-[Lo Stop] -Inf
-[Hi Stop] Inf
-[Stop ERP] 0.8
-[Stop CFM] 0.001
+[FMax] 2.5
+[Fudge Factor] 0.1
+[Bounce] 0
+[CFM] 0.001
+[Lo Stop] -Inf
+[Hi Stop] Inf
+[Stop ERP] 0.8
+[Stop CFM] 0.001
Draw Mode
@@ -8837,7 +8837,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -8955,7 +8955,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -9073,7 +9073,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
@@ -9191,7 +9191,7 @@
Parameters
-[CFM] 0.00001
+[CFM] 0.00001
Draw Mode
diff --git a/Season2016/LabVIEW_Pigeon_StraightServo_Example/Pigeon StraightServo Example.lvproj b/Season2016/LabVIEW_Pigeon_StraightServo_Example/Pigeon StraightServo Example.lvproj
index 2f4eee7..149917b 100644
--- a/Season2016/LabVIEW_Pigeon_StraightServo_Example/Pigeon StraightServo Example.lvproj
+++ b/Season2016/LabVIEW_Pigeon_StraightServo_Example/Pigeon StraightServo Example.lvproj
@@ -1,78 +1,78 @@
- true
-
- -
- 3
- true
- true
- false
- 0
- My Computer/VI Server
- My Computer/VI Server
- true
- true
- false
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- Target
- roboRIO-217-FRC.local
- OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
- 76F2
- ARMLinux
- true
- 5000
- 1000
- 8
- 8
- false
- true
- 300
- 80
- 60
-
- 100
- false
- 10000
- 0
- 0
- true
- true
- true
- 8001
- /home/lvuser/natinst/bin/startup.rtexe
- true
- +*
- true
- /home/lvuser/natinst/bin
- true
- true
- +*
- false
- true
- 3363
- Main Application Instance/VI Server
- Main Application Instance/VI Server
- +*
- true
- true
- Listen 8000
+ true
+
+
-
+ 3
+ true
+ true
+ false
+ 0
+ My Computer/VI Server
+ My Computer/VI Server
+ true
+ true
+ false
+
-
+
-
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ Target
+ roboRIO-217-FRC.local
+ OS,Linux;CPU,ARM;DeviceCode,76F2;TARGET_TYPE,RT;
+ 76F2
+ ARMLinux
+ true
+ 5000
+ 1000
+ 8
+ 8
+ false
+ true
+ 300
+ 80
+ 60
+
+ 100
+ false
+ 10000
+ 0
+ 0
+ true
+ true
+ true
+ 8001
+ /home/lvuser/natinst/bin/startup.rtexe
+ true
+ +*
+ true
+ /home/lvuser/natinst/bin
+ true
+ true
+ +*
+ false
+ true
+ 3363
+ Main Application Instance/VI Server
+ Main Application Instance/VI Server
+ +*
+ true
+ true
+ Listen 8000
NI.ServerName default
DocumentRoot "$LVSERVER_DOCROOT"
@@ -100,504 +100,504 @@ AddOutputFilter chunkFilter
- false
- false
- /c/ni-rt/system/www/www.log
- 80
- /c/ni-rt/system/www
- c+*
- 60
- +*
- PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
- 15
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
- -
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
- -
- true
-
-
- -
-
-
- {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
- {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
- 8002
- http://www.NI.com
- true
- {8C1C8770-D686-4931-835E-3A364C203F20}
- Build Robot Main.vi into an EXE that will run at startup on the roboRIO
- FRC Robot Boot-up Deployment
- 0
- true
- true
- /D/CTR/FRC/FRC-Examples/LabVIEW_Pigeon_StraightServo_Example/Builds
- <none>
- true
- {6782B190-04E1-4A41-93AB-3F357B35791E}
- /home/lvuser/natinst/bin
- 1
- startup.rtexe
- /home/lvuser/natinst/bin/startup.rtexe
- <none>
- App
- Support Directory
- /home/lvuser/natinst/bin/data
- <none>
- 2
- {DB01CD21-4447-4671-A00A-D774E7A6FDE1}
- Container
- 0
- /Target/Robot Main.vi
- TopLevel
- VI
- 2
- NI
- FRC Robot Boot-up Deployment
- FRC Robot Boot-up Deployment
- Copyright © 2013 NI
- FRC Robot Boot-up Deployment
- {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
- startup.rtexe
-
-
-
+ false
+ false
+ /c/ni-rt/system/www/www.log
+ 80
+ /c/ni-rt/system/www
+ c+*
+ 60
+ +*
+ PqVr/ifkAQh+lVrdPIykXlFvg12GhhQFR8H9cUhphgg=:pTe9HRlQuMfJxAG6QCGq7UvoUpJzAzWGKy5SbZ+roSU=
+ 15
+ -
+
+
+ -
+
+
+
+
+
+
+
+
+
+
+
+ -
+
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+ -
+ true
+
+
+ -
+
-
+ {7AAF6F56-ED86-4686-A01D-90E0BB9C8086}
+ {A18A8773-40AE-4BF9-9DC4-FD6E80D0C49E}
+ 8002
+ http://www.NI.com
+ true
+ {8C1C8770-D686-4931-835E-3A364C203F20}
+ Build Robot Main.vi into an EXE that will run at startup on the roboRIO
+ FRC Robot Boot-up Deployment
+ 0
+ true
+ true
+ /D/CTR/FRC/FRC-Examples/LabVIEW_Pigeon_StraightServo_Example/Builds
+ <none>
+ true
+ {6782B190-04E1-4A41-93AB-3F357B35791E}
+ /home/lvuser/natinst/bin
+ 1
+ startup.rtexe
+ /home/lvuser/natinst/bin/startup.rtexe
+ <none>
+ App
+ Support Directory
+ /home/lvuser/natinst/bin/data
+ <none>
+ 2
+ {DB01CD21-4447-4671-A00A-D774E7A6FDE1}
+ Container
+ 0
+ /Target/Robot Main.vi
+ TopLevel
+ VI
+ 2
+ NI
+ FRC Robot Boot-up Deployment
+ FRC Robot Boot-up Deployment
+ Copyright © 2013 NI
+ FRC Robot Boot-up Deployment
+ {8C9344B8-7ED9-4E5F-92AE-3A9F547EFD4A}
+ startup.rtexe
+
+
+
diff --git a/Season2016/README.md b/Season2016/README.md
index 9c7878e..9e19925 100644
--- a/Season2016/README.md
+++ b/Season2016/README.md
@@ -3,22 +3,22 @@ These are projects to enable using the CTRE Pigeon IMU with the 2016 Control Sys
There are 2 ways to update the Web-Interface from 2016 to display Pigeon information.
Option A: Replace the File used in the Update Utility
- 1. Install the CTRE Toolsuite. (Available here: http://www.ctr-electronics.com/control-system/hro.html#product_tabs_technical_resources)
- 2. Copy libfrccanfirmwareupdate.so from this repository to C:\Users\Public\Documents\Cross The Road Electronics\LifeBoat\rio-files.
- NOTE: This will overwrite the plug-in that comes with the installer. It is recommended to save a copy of the file first.
- 3. Run the roboRIO upgrade utility from the CTRE Toolsuite LifeBoat Imager.
+ 1. Install the CTRE Toolsuite. (Available here: http://www.ctr-electronics.com/control-system/hro.html#product_tabs_technical_resources)
+ 2. Copy libfrccanfirmwareupdate.so from this repository to C:\Users\Public\Documents\Cross The Road Electronics\LifeBoat\rio-files.
+ NOTE: This will overwrite the plug-in that comes with the installer. It is recommended to save a copy of the file first.
+ 3. Run the roboRIO upgrade utility from the CTRE Toolsuite LifeBoat Imager.
Option B: Manually Install the Plug-in
- 1. Establish an FTP connection to the roboRIO.
- - The roboRIO address is 172.22.11.2
- - The username is admin
- - There is no password (leave blank)
- 2. Update the plug-in file. It is located in /usr/local/frc/lib.
- - Backup the existing plug-in file (libfrccanfirmwareupdate.so) by renaming it.
- We recommend renaming the extension to .so.orig
- - Copy the new *.so file from this github repository into the ftp directory.
- 3. Restart the webservice. SSH into the roboRIO (same settings as FTP) and run:
- - /etc/init.d/systemWebServer restart
-
+ 1. Establish an FTP connection to the roboRIO.
+ - The roboRIO address is 172.22.11.2
+ - The username is admin
+ - There is no password (leave blank)
+ 2. Update the plug-in file. It is located in /usr/local/frc/lib.
+ - Backup the existing plug-in file (libfrccanfirmwareupdate.so) by renaming it.
+ We recommend renaming the extension to .so.orig
+ - Copy the new *.so file from this github repository into the ftp directory.
+ 3. Restart the webservice. SSH into the roboRIO (same settings as FTP) and run:
+ - /etc/init.d/systemWebServer restart
+
The Webdash Interface should now display Pigeons that are connected to the roboRIO via CAN.
\ No newline at end of file