2017 FRC Control SystemFRC Java Programming FRC Java ReferencesArchive - C++\Java Porting Guide - 2014 to 2015

Archive - C++\Java Porting Guide - 2014 to 2015

When C++ and Java teams look at the WPILib APIs for 2015 they should see something that looks very familiar. Where possible we have tried to keep the APIs the same as they were on the cRIO, but in some cases we chose to make changes we had been holding off for a long time to maintain compatibility while we were on the cRIO system and there are also a number of changes that were made to support the changes in the roboRIO system.

SimpleRobot Template

C++ - 2014
class Robot: public SimpleRobot
{
C++ - 2015
class Robot: public SampleRobot
{

Java - 2014
public class Robot extends SimpleRobot
{
Java - 2015
public class Robot extends SampleRobot
{

The SimpleRobot base class has been renamed to SampleRobot to encourage people to use it only for the simplest of programs. Instead we encourage the use of the Command-based and Iterative template projects available on the New Project menus in eclipse. Teams that understand how SimpleRobot works and have a reason to continue using it may still do so under the new name.

Sensor Start/Stop methods

C++ - 2014
Encoder *enc;
enc = new Encoder(1, 2, false, k4x);
enc->Start();
C++ - 2015
Encoder *enc;
enc = new Encoder(1, 2, false, k4x);


Java - 2014
Encoder enc;
enc = new Encoder(1, 2, false, EncodingType.k4x);
enc.start();
Java - 2015
Encoder enc;
enc = new Encoder(1, 2, false, EncodingType.k4x);

Gyros, Counters and Encoders have had the Start() and Stop() methods removed. These sensors now start counting on creation/instantiation. The reset methods still exist to zero the values on the specific objects to set the values before starting a measurement.

AnalogChannel ->  AnalogInput

C++ - 2014
AnalogChannel *analog;
analog = new AnalogChannel(1);
C++ - 2015
AnalogInput *analog
analog = new AnalogInput(0);


Java - 2014
AnalogChannel analog;
analog = new AnalogChannel(1);
Java - 2015
AnalogInput analog;
analog = new AnalogInput(0);

The AnalogChannel class has been renamed to AnalogInput to match DigitalInput and avoid confusion with the addition of AnalogOutput. This is just a change in the name and the functionality is unchanged.

Module Classes

C++ - 2014
AnalogModule::GetInstance(1)->SetSampleRate(50000);
float rate = AnalogModule::GetInstance(1)->GetSampleRate();
C++ - 2015
AnalogInput::SetSampleRate(50000);
float rate = AnalogInput::GetSampleRate();

Java - 2014
AnalogModule.getInstance(1).setSampleRate(50000);
double rate = AnalogModule.getInstance(1).getSampleRate();
Java - 2015
AnalogInput.setGlobalSampleRate(50000);
double rate = AnalogInput.getGlobalSampleRate();

The Analog and Digital module classes (AnalogModule and DigitalModule) have been removed. Methods that set module-wide parameters in past implementations have been moved to static (class) methods on the respective channel classes. For more information see the Java and C++ documentation.

DS IO, Enhanced IO, and Kinect

The Cypress Firsttouch board support and Kinect server support has been removed from the DS so these classes have been removed from WPILib. Teams can use the Dashboard or USB HID devices to replace the Cypress board functionality. The TI Launchpad and 16 Hertz Leonardo++ included in your Kit of Parts can both be programmed to appear as HID devices to be used for custom I/O (click the links for more info). Teams wishing to use the Kinect as an input device will need to modify the Kinect server to send data directly to the robot using Network Tables or one of the ports available on the field network.

DS User Messages / DriverStation LCD

The User messages window on the Driver Station has been removed, therefore this functionality (DriverStationLCD class) has been removed from WPILib. As a replacement, the default Dashboard contains a number of controls and indicators of different types on the "Basic" tab that teams may wish to use to display robot information or provide input. To write to these controls, use the SmartDashboard class, the key names to use are listed on the Dashboard. More information can be found in Using the LabVIEW Dashboard with C++\Java Code.

RobotDrive

C++ - 2014 Jaguars
RobotDrive drive;
drive = new RobotDrive(1,2);
C++ - 2015 Jaguars
Jaguar *jag1, *jag2;
RobotDrive *drive;
jag1 = new Jaguar(1);
jag2 = new Jaguar(2);
drive = new RobotDrive(jag1, jag2);
C++ - 2014 Talons
Talon *talon1, *talon2;
RobotDrive *drive;
talon1 = new Talon(1);
talon2 = new Talon(2);
drive = new RobotDrive(talon1, talon2);
C++ - 2015 Talons
RobotDrive drive;
drive = new RobotDrive(1,2);

Java - 2014 Jaguars
RobotDrive drive = new RobotDrive(1,2);
Java - 2015 Jaguars
Jaguar jag1 = new Jaguar(1);
Jaguar jag2 = new Jaguar(2);
RobotDrive drive = new RobotDrive(jag1, jag2);
Java - 2014 Talons
Talon talon1 = new Talon(1);
Talon talon2 = new Talon(2);
RobotDrive drive = new RobotDrive(talon1, talon2);
Java - 2015 Talons
RobotDrive drive = new RobotDrive(1,2);

The default controller for RobotDrive has changed from Jaguar to Talon. To use RobotDrive with Jaguars, users will now need to construct the speed controllers beforehand and pass them into the RobotDrive constructor.

Compressor

C++ - 2014
Compressor *comp; comp = new Compressor(1,1); comp->Start(); C++ - 2015
Solenoid *solenoid; solenoid = new Solenoid(0);

Java - 2014
Compressor comp = new Compressor(1,1);
comp.start();
Java - 2015
Solenoid solenoid = new Solenoid(0);

The Compressor class has been replaced an updated version that uses the PCM (Pneumatics Control Module). There is no need to instantiate this class when using the module if automatic closed-loop feedback is all that is required. You only need to create Solenoid objects to cause the PCM to be initialized and started. If you wish to turn off the close-loop feedback, then the Compressor object is required. The previous Solenoid class now uses the PCM exclusively.

Solenoid

C++
Solenoid *solenoid; solenoid = new Solenoid(0); bool blacklisted = solenoid->IsBlackListed();
bool voltageStickyFault = solenoid->GetPcmSolenoidVoltageStickyFault();
bool voltageFault = solenoid->GetPCMSolenoidVoltageFault();
solenoid->ClearAllPCMStickyFaults();

Java - 2015
Solenoid solenoid = new Solenoid(0); boolean blacklisted = solenoid.isBlackListed();
boolean voltageStickyFault = solenoid.getPcmSolenoidVoltageStickyFault();
boolean voltageFault = solenoid.getPCMSolenoidVoltageFault();
solenoid.clearAllPCMStickyFaults();

The existing Solenoid and Double Solenoid class APIs were not modified significantly (with the exception of the module number changing to a PCM CAN ID), however additional methods were added to expose the additional functionality of the PCM.

Channel and Module Numbers

C++ - 2014
Talon *talon1;
talon1 = new Talon(1,1);
C++ - 2015
Talon *talon0;
talon0 = new Talon(0);

Java - 2014
Talon talon1 = new Talon(1,1);
Java - 2015
Talon talon0 = new Talon(0);

The roboRIO does not have separate modules so the module number has been removed from constructors.

Channel numbers are now zero-based as shown on the plastic cases for all the components.

CANJaguar

CAN Jaguars have been completely reimplemented and now support fully non-blocking calls along with brown-out code that will reset the operating parameters should a Jaguar reboot while the RoboRIO is still running. Setting operating modes, i.e. PercentMode, VoltageMode, etc. are documented in the API docs here:

C++: http://first.wpi.edu/FRC/roborio/release/docs/cpp  
Java: http://first.wpi.edu/FRC/roborio/release/docs/java

Team Number

C++
char name[256];
gethostname(name, 256);

Java
Runtime run = Runtime.getRuntime();
Process proc;
try {
proc = run.exec("hostname");
BufferedInputStream in = new BufferedInputStream(proc.getInputStream());
byte [] b = new byte[256];
in.read(b, 0, 256);
//The next line will print out the hostname, to use it instead, store it to a string instead of using println
System.out.println(new String(b).trim());
} catch(IOException e1) {
e1.printStackTrace();
}

You can no longer get your team number.   In place of getting your team number, teams are recommended to use the roboRIO hostname. In C++ this can be retrieved by calling gethostname() from unistd.h. In Java teams can use the code snippet shown above to get the result of the "hostname" command.

DS User Data

Driver station user data APIs have been removed in favor of NetworkTables to communicate with your laptops.

User LED and Button

C++
bool buttonVal = GetUserButton();

Java
import edu.wpi.first.wpilibj.Utility;

boolean buttonVal = Utility.getUserButton();

The User LED APIs are removed (there is no User LED on the roboRIO) and you can now read the user button.

I2C and SPI

The I2C and SPI APIs have changed to accommodate the changed architecture of these buses on the roboRIO and to better align the API in the two languages, with the largest change occurring in the Java SPI API. See the API docs for documentation on the new APIs:

C++: http://first.wpi.edu/FRC/roborio/release/docs/cpp  
Java: http://first.wpi.edu/FRC/roborio/release/docs/java

One change not entirely obvious from the class documentation is the I2C bus changed from taking 8-bit addresses on the cRIO (e.g. 0x3A for the ADXL345) to 7-bit addresses on the roboRIO (e.g. 0x1D for the ADXL345).

Analog Triggers

Analog triggers are now supported.

Interrupts

Interrupts are now supported.

Accelerometers

Accelerometer is now an interface that is implemented by ADXL345_I2C, ADXL345_SPI and BuiltInAccelerometer. The AnalogAccelerometer will likely also implement that interface in the future.

Driver Station

C++
bool attached = DriverStation.GetInstance()->IsDSAttached(); //Is the DS communicating with the robot?
bool sysActive = DriverStation.GetInstance()->IsSysActive(); //Are the FPGA outputs (such as PWM) active
bool brownedOut = DriverStation.GetInstance()->IsSysBrownedOut(); //Is the roboRIO brownout protection active?
int stickAxes = DriverStation.GetInstance()->GetStickAxisCount(0);
int stickPOVs = DriverStation.GetInstance()->GetStickPOVCount(0);
int stickButtons = DriverStation.GetInstance()->GetStickButtonCount(0);

Java
boolean attached = DriverStation.getInstance().isDSAttached(); //Is the DS communicating with the robot?
boolean sysActive = DriverStation.getInstance().isSysActive(); //Are the FPGA outputs (such as PWM) active
boolean brownedOut = DriverStation.getInstance().isSysBrownedOut(); //Is the roboRIO brownout protection active?
int stickAxes = DriverStation.getInstance().getStickAxisCount(0);
int stickPOVs = DriverStation.getInstance().getStickPOVCount(0);
int stickButtons = DriverStation.getInstance().getStickButtonCount(0);

Several new methods have been added to the DriverStation class.

Command template

The Command-Based template has been tweaked to better align template and RobotBuilder projects. CommandBase has been removed in favor of instantiating the Subsystems and OI objects from the main robot class.

MXP Channel Numbers

MXP port numbers are just continuations of the digital, analog, and PWM channel numbering scheme from the connectors along the outside of the RoboRIO.

NIVision

You now have access to all the NI Vision APIs in C++ by referencing the documented functions and Java through a set of Java Native Interfaces (JNI) to the NI libraries. See the sample programs for some examples of using the libraries from either language.

File Storage

On the cRIO, user code could store files to C:\ or to subfolders created there. On the roboRIO, users should store files to /home/lvuser or subfolders created there.

C++ Synchronized and Task

The header files for the C++ Synchronized class and Task class were moved into the OSAL subfolder (OS Abstraction Layer).

Java Networking and File IO

For Java development we have switched to the full Java 8 SE Embedded compiler. In the past many of the APIs were non-standard for things like file I/O and were located in the javax package. Now you can use the same APIs as desktop Java for accessing files on the flash drive of your roboRIO or for networking.

New Classes

A number of new classes have been created to support the new capabilities of the roboRIO and the 2015 Control System

PowerDistributionPanel

There is a new PowerDistributionPanel class that supports the current sensing features of the PDP. You can instantiate this object and read the currents from each of the motor channels.

PWM Speed Controller Classes

VictorSP and TalonSRX classes have been created for using these devices connected via PWM

CAN TalonSRX

A CANTalon class has been created to support control of the TalonSRX over the CAN bus.

Built-in Accelerometer

The RoboRIO built-in accelerometer is supported through the BuiltInAccelerometer class.

ControllerPower

The ControllerPower class contains methods for querying information about the roboRIO power (input current and voltage and voltage, current, status, and fault counts for each of the user rails).

Analog Output

The analog output channels on the MXP connector are supported through the AnalogOutput class.

Analog Potentiometer

There is now an AnalogPotentiometer class that will return angles in degrees rather than voltages that need to be converted. The class uses ratiometric scaling, that is it is based on the actual bus voltages rather than using the constant 5 for the maximum voltage when computing the rotation angle.

Changes to the development tools

  1. C++ and Java are now both based on Eclipse rather than WindRiver Workbench and Netbeans. Download a current copy of Eclipse (Luna or better) and add the FRC plugins as described in the Getting Started documentation. Once installed you can create either Java or C++ projects from the "New" -> "Project..." menu.
  2. The WPILib development tools, libraries, header files, and documentation is created in the WPILib directory contained inside your user directory. The WPILib directory is created when a version of eclipse with the plugins is first run for any user account on the system.
  3. Software simulation of robot programs is available using the Gazebo robot simulator. Currently only supplied models can be used, but they can be programmed using WPILib either with C++ or Java and most methods and classes. The simulator only runs on Linux so to try it, you need to install Linux as described in the Simulation instructions and  install the Linux WPILib plugins to get all the tools and libraries required. See the FRCSim documentation on this site.
  4. There is a full set of doxygen-based library API documentation supplied on-line: C++: http://first.wpi.edu/FRC/roborio/release/docs/cpp Java: http://first.wpi.edu/FRC/roborio/release/docs/java We will try to have the documentation supplied locally in an upcoming release.
  5. Java 8 is running on the RoboRIO so features like lambdas, enums, generics, etc. are all available to robot programs. For C++ programmers, a current version of gcc is supported so that you will be able to use all the C++ 11 features.
  6. Eclipse uses mDNS to communicate with the RoboRIO. Make sure that your development system has mDNS name resolution support included. With Linux development systems you might need to explicitly turn on mDNS. With Mac and Windows development systems, the DHCP setting will fail-over to mDNS if there is no DHCP server on the robot network.

0 Report Errors

Use this form to report any errors with the documentation. For help with WPILib, please use the FIRST Forums at http://forums.usfirst.org For reporting WPILib bugs, please submit an issue on GitHub at https://github.com/wpilibsuite/allwpilib/issues/new

Ignore