Compare commits

...

20 Commits

Author SHA1 Message Date
Tyler Veness
96e9a6989c Improved Command-based examples (#906)
Robot.cpp has been split into header-source pairs and the Command-based
examples now define an example subsystem in the Robot class.
2018-03-05 22:06:40 -08:00
Thad House
14228d82f3 Adds Direct port name Serial API (#956) 2018-03-05 19:41:09 -08:00
Peter Johnson
5175829bab PWM: Use getRaw and setRaw for Sendable "Value" property. (#963)
Also change type to "PWM".  Move old PWM Sendable behavior for both value
and type to PWMSpeedController.
2018-03-03 21:36:25 -08:00
Peter Johnson
9d7293734a SendableChooser: Do not automatically add to LiveWindow. (#964)
SendableChooser::InitSendable() is written such that it saves the table
being used in an instance variable.  This doesn't work if the chooser is
added to both LiveWindow and SmartDashboard.  Normally it is not added to
LiveWindow because the name is empty, but if setName() is called this could
still happen.  Note adding the same SendableChooser to SmartDashboard with
two different names is also not currently supported, for the same reason.

The correct solution will be to remove the instance variable, but this is
too high risk to implement mid-season, so instead just remove from LiveWindow.
2018-03-03 21:34:42 -08:00
Peter Johnson
1e5ec362f7 CameraServer: catch VideoExceptions in video listener. (#949)
We don't want failures here to stop other video properties from updating.

Reported here: https://www.chiefdelphi.com/forums/showthread.php?t=162860
2018-03-03 01:58:28 -08:00
Tyler Veness
7bb3e4efc3 Made documentation for RobotDriveBase::SetDeadband() clearer (#953)
It now mentions that the deadband is applied to the drive inputs.
2018-03-03 01:57:59 -08:00
PJ Reiniger
67de595c85 ADXRS450_Gyro: Add null check around reset (#948)
Reset() is the only function without a null check around it. We call the function on startup, which means if it is unplugged the robot crashes.

Also added an accessor for checking if it is connected, as some teams (us) would like to handle the case where it was not connected on startup.
2018-03-03 01:57:45 -08:00
Thad House
82152e90fe Adds defaults to PWM config (#961) 2018-03-03 01:56:49 -08:00
Dustin Spicuzza
1e7d439899 HAL Notifier: Don't disable the notifier manager when the last handle is cleaned up (#960)
- Addresses #959, but not a good long term solution
2018-03-03 01:56:24 -08:00
Tyler Veness
979984fa6b Fix Travis CI wpiformat install (#947) 2018-02-20 23:01:57 -08:00
Thad House
57e9fb33d2 Fixes C++ SendableChooser using invalid temp variable (#945) 2018-02-15 23:00:46 -08:00
Thad House
f5a292dadd Adds TriState JNI entry point (#938)
Also adds missing sim TriState DIO HAL call, and a ToDo for later
2018-02-12 16:05:10 -08:00
Sam Carlberg
77d6c11743 Invert right side motors in MecanumDrive sendable (#933)
This aligns with the current behavior of DifferentialDrive
Fixes shuffleboard#404
2018-02-09 08:30:12 -08:00
Tyler Veness
67f9c9a5b3 Fixed TimedRobot.java hanging if an exception was thrown (#926) 2018-02-04 22:38:19 -08:00
Thad House
f720cbb121 Switches CtreCanNode to use locking and std::chrono for time (#909) 2018-02-01 21:39:06 -08:00
Tyler Veness
64a7e57fe0 Added output normalization to DifferentialDrive::CurvatureDrive() (#924)
This normalizes within -1..1 to avoid clipping and maintain the ratio between
wheel speeds, since that ratio determines the center of rotation.

Fixes #923.
2018-02-01 21:17:04 -08:00
Tyler Veness
5ca00dddbe Added TimedRobot::GetPeriod() (#915)
Fixes #914.
2018-01-27 01:01:15 -08:00
Tyler Veness
120ceb3427 Fix channel reassignments for C++ Joystick twist and throttle axes (#903) 2018-01-26 17:26:10 -08:00
Thad House
5cbafc1382 Updates to image 17 (#913)
These should be binary compatible, so safe to use with image 16.
2018-01-26 17:21:13 -08:00
Thad House
39d1650d51 Fixes double to int to double cast in encoderJNI (#918)
Fixes #916
2018-01-26 17:20:20 -08:00
54 changed files with 725 additions and 401 deletions

View File

@@ -9,7 +9,7 @@ addons:
- ubuntu-toolchain-r-test
packages:
- g++-6
- python3.5
- python3.5-dev
before_install:
- sudo sh -c 'echo "deb http://apt.llvm.org/trusty/ llvm-toolchain-trusty-5.0 main" > /etc/apt/sources.list.d/llvm.list'

View File

@@ -169,13 +169,17 @@ void HAL_CleanNotifier(HAL_NotifierHandle notifierHandle, int32_t* status) {
// the notifier can call back into our callback, so don't hold the lock
// here (the atomic fetch_sub will prevent multiple parallel entries
// into this function)
if (notifierAlarm) notifierAlarm->writeEnable(false, status);
if (notifierManager) notifierManager->disable(status);
std::lock_guard<wpi::mutex> lock(notifierMutex);
notifierAlarm = nullptr;
notifierManager = nullptr;
closestTrigger = UINT64_MAX;
// Cleaning up the manager takes up to a second to complete, so don't do
// that here. Fix it more permanently in 2019...
// if (notifierAlarm) notifierAlarm->writeEnable(false, status);
// if (notifierManager) notifierManager->disable(status);
// std::lock_guard<wpi::mutex> lock(notifierMutex);
// notifierAlarm = nullptr;
// notifierManager = nullptr;
// closestTrigger = UINT64_MAX;
}
}

View File

@@ -104,6 +104,9 @@ HAL_DigitalHandle HAL_InitializePWMPort(HAL_PortHandle portHandle,
digitalSystem->writeEnableMXPSpecialFunction(specialFunctions | bitToSet,
status);
// Defaults to allow an always valid config.
HAL_SetPWMConfig(handle, 2.0, 1.501, 1.5, 1.499, 1.0, status);
return handle;
}
void HAL_FreePWMPort(HAL_DigitalHandle pwmPortHandle, int32_t* status) {

View File

@@ -43,6 +43,13 @@ void HAL_InitializeSerialPort(HAL_SerialPort port, int32_t* status) {
if (*status > 0) *status = 0;
}
void HAL_InitializeSerialPortDirect(HAL_SerialPort port, const char* portName,
int32_t* status) {
*status = viOpen(resourceManagerHandle, const_cast<char*>(portName), VI_NULL,
VI_NULL, reinterpret_cast<ViSession*>(&portHandles[port]));
if (*status > 0) *status = 0;
}
void HAL_SetSerialBaudRate(HAL_SerialPort port, int32_t baud, int32_t* status) {
*status = viSetAttribute(portHandles[port], VI_ATTR_ASRL_BAUD, baud);
if (*status > 0) *status = 0;

View File

@@ -68,17 +68,13 @@ void CtreCanNode::UnregisterTx(uint32_t arbId)
_txJobs.erase(iter);
}
}
timespec diff(const timespec & start, const timespec & end)
{
timespec temp;
if ((end.tv_nsec-start.tv_nsec)<0) {
temp.tv_sec = end.tv_sec-start.tv_sec-1;
temp.tv_nsec = 1000000000+end.tv_nsec-start.tv_nsec;
} else {
temp.tv_sec = end.tv_sec-start.tv_sec;
temp.tv_nsec = end.tv_nsec-start.tv_nsec;
}
return temp;
static int64_t GetTimeMs() {
std::chrono::time_point < std::chrono::system_clock > now;
now = std::chrono::system_clock::now();
auto duration = now.time_since_epoch();
auto millis = std::chrono::duration_cast < std::chrono::milliseconds
> (duration).count();
return (int64_t) millis;
}
CTR_Code CtreCanNode::GetRx(uint32_t arbId,uint8_t * dataBytes, uint32_t timeoutMs)
{
@@ -90,10 +86,11 @@ CTR_Code CtreCanNode::GetRx(uint32_t arbId,uint8_t * dataBytes, uint32_t timeout
if(timeoutMs > 999)
timeoutMs = 999;
FRC_NetworkCommunication_CANSessionMux_receiveMessage(&arbId,kFullMessageIDMask,dataBytes,&len,&timeStamp,&status);
std::lock_guard<wpi::mutex> lock(_lck);
if(status == 0){
/* fresh update */
rxEvent_t & r = _rxRxEvents[arbId]; /* lookup entry or make a default new one with all zeroes */
clock_gettime(2,&r.time); /* fill in time */
r.time = GetTimeMs();
memcpy(r.bytes, dataBytes, 8); /* fill in databytes */
}else{
/* did not get the message */
@@ -107,16 +104,13 @@ CTR_Code CtreCanNode::GetRx(uint32_t arbId,uint8_t * dataBytes, uint32_t timeout
/* we've gotten this message before but not recently */
memcpy(dataBytes,i->second.bytes,8);
/* get the time now */
struct timespec temp;
clock_gettime(2,&temp); /* get now */
int64_t now = GetTimeMs(); /* get now */
/* how long has it been? */
temp = diff(i->second.time,temp); /* temp = now - last */
if(temp.tv_sec > 0){
retval = CTR_RxTimeout;
}else if(temp.tv_nsec > ((int32_t)timeoutMs*1000*1000)){
retval = CTR_RxTimeout;
}else {
/* our last update was recent enough */
int64_t temp = now - i->second.time; /* temp = now - last */
if (temp > ((int64_t) timeoutMs)) {
retval = CTR_RxTimeout;
} else {
/* our last update was recent enough */
}
}
}

View File

@@ -4,6 +4,7 @@
#include <map>
#include <string.h> // memcpy
#include <sys/time.h>
#include <support/mutex.h>
class CtreCanNode
{
public:
@@ -108,7 +109,7 @@ private:
class rxEvent_t{
public:
uint8_t bytes[8];
struct timespec time;
int64_t time;
rxEvent_t()
{
bytes[0] = 0;
@@ -127,5 +128,7 @@ private:
typedef std::map<uint32_t,rxEvent_t> rxRxEvents_t;
rxRxEvents_t _rxRxEvents;
wpi::mutex _lck;
};
#endif

View File

@@ -21,6 +21,8 @@ extern "C" {
#endif
void HAL_InitializeSerialPort(HAL_SerialPort port, int32_t* status);
void HAL_InitializeSerialPortDirect(HAL_SerialPort port, const char* portName,
int32_t* status);
void HAL_SetSerialBaudRate(HAL_SerialPort port, int32_t baud, int32_t* status);
void HAL_SetSerialDataBits(HAL_SerialPort port, int32_t bits, int32_t* status);
void HAL_SetSerialParity(HAL_SerialPort port, int32_t parity, int32_t* status);

View File

@@ -198,6 +198,23 @@ void HAL_SetDIO(HAL_DigitalHandle dioPortHandle, HAL_Bool value,
SimDIOData[port->channel].SetValue(value);
}
/**
* Set direction of a DIO channel.
*
* @param channel The Digital I/O channel
* @param input true to set input, false for output
*/
void HAL_SetDIODirection(HAL_DigitalHandle dioPortHandle, HAL_Bool input,
int32_t* status) {
auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
if (port == nullptr) {
*status = HAL_HANDLE_ERROR;
return;
}
SimDIOData[port->channel].SetIsInput(input);
}
/**
* Read a digital I/O bit from the FPGA.
* Get a single value from a digital I/O channel.

View File

@@ -57,6 +57,9 @@ HAL_DigitalHandle HAL_InitializePWMPort(HAL_PortHandle portHandle,
SimPWMData[origChannel].SetInitialized(true);
// Defaults to allow an always valid config.
HAL_SetPWMConfig(handle, 2.0, 1.501, 1.5, 1.499, 1.0, status);
return handle;
}
void HAL_FreePWMPort(HAL_DigitalHandle pwmPortHandle, int32_t* status) {

View File

@@ -16,6 +16,9 @@ void InitializeSerialPort() {}
extern "C" {
void HAL_InitializeSerialPort(HAL_SerialPort port, int32_t* status) {}
void HAL_InitializeSerialPortDirect(HAL_SerialPort port, const char* portName,
int32_t* status) {}
void HAL_SetSerialBaudRate(HAL_SerialPort port, int32_t baud, int32_t* status) {
}

View File

@@ -7,6 +7,7 @@
#include "Drive/DifferentialDrive.h"
#include <algorithm>
#include <cmath>
#include <HAL/HAL.h>
@@ -171,6 +172,14 @@ void DifferentialDrive::CurvatureDrive(double xSpeed, double zRotation,
}
}
// Normalize the wheel speeds
double maxMagnitude =
std::max(std::abs(leftMotorOutput), std::abs(rightMotorOutput));
if (maxMagnitude > 1.0) {
leftMotorOutput /= maxMagnitude;
rightMotorOutput /= maxMagnitude;
}
m_leftMotor.Set(leftMotorOutput * m_maxOutput);
m_rightMotor.Set(-rightMotorOutput * m_maxOutput);

View File

@@ -134,12 +134,12 @@ void MecanumDrive::InitSendable(SendableBuilder& builder) {
[=]() { return m_frontLeftMotor.Get(); },
[=](double value) { m_frontLeftMotor.Set(value); });
builder.AddDoubleProperty(
"Front Right Motor Speed", [=]() { return m_frontRightMotor.Get(); },
[=](double value) { m_frontRightMotor.Set(value); });
"Front Right Motor Speed", [=]() { return -m_frontRightMotor.Get(); },
[=](double value) { m_frontRightMotor.Set(-value); });
builder.AddDoubleProperty("Rear Left Motor Speed",
[=]() { return m_rearLeftMotor.Get(); },
[=](double value) { m_rearLeftMotor.Set(value); });
builder.AddDoubleProperty("Rear Right Motor Speed",
[=]() { return m_rearRightMotor.Get(); },
[=](double value) { m_rearRightMotor.Set(value); });
builder.AddDoubleProperty(
"Rear Right Motor Speed", [=]() { return -m_rearRightMotor.Get(); },
[=](double value) { m_rearRightMotor.Set(-value); });
}

View File

@@ -21,9 +21,11 @@ using namespace frc;
RobotDriveBase::RobotDriveBase() { m_safetyHelper.SetSafetyEnabled(true); }
/**
* Change the default value for deadband scaling. The default value is
* 0.02. Values smaller then the deadband are set to 0, while values
* larger then the deadband are scaled from 0.0 to 1.0. See ApplyDeadband().
* Sets the deadband applied to the drive inputs (e.g., joystick values).
*
* The default value is 0.02. Inputs smaller than the deadband are set to 0.0
* while inputs larger than the deadband are scaled from 0.0 to 1.0. See
* ApplyDeadband().
*
* @param deadband The deadband to set.
*/

View File

@@ -131,7 +131,7 @@ int Joystick::GetThrottleChannel() const { return m_axes[Axis::kThrottle]; }
* here to complete the GenericHID interface.
*/
double Joystick::GetX(JoystickHand hand) const {
return GetRawAxis(m_axes[kDefaultXAxis]);
return GetRawAxis(m_axes[Axis::kX]);
}
/**
@@ -143,7 +143,7 @@ double Joystick::GetX(JoystickHand hand) const {
* here to complete the GenericHID interface.
*/
double Joystick::GetY(JoystickHand hand) const {
return GetRawAxis(m_axes[kDefaultYAxis]);
return GetRawAxis(m_axes[Axis::kY]);
}
/**
@@ -151,16 +151,14 @@ double Joystick::GetY(JoystickHand hand) const {
*
* This depends on the mapping of the joystick connected to the current port.
*/
double Joystick::GetZ() const { return GetRawAxis(m_axes[kDefaultZAxis]); }
double Joystick::GetZ() const { return GetRawAxis(m_axes[Axis::kZ]); }
/**
* Get the twist value of the current joystick.
*
* This depends on the mapping of the joystick connected to the current port.
*/
double Joystick::GetTwist() const {
return GetRawAxis(m_axes[kDefaultTwistAxis]);
}
double Joystick::GetTwist() const { return GetRawAxis(m_axes[Axis::kTwist]); }
/**
* Get the throttle value of the current joystick.
@@ -168,7 +166,7 @@ double Joystick::GetTwist() const {
* This depends on the mapping of the joystick connected to the current port.
*/
double Joystick::GetThrottle() const {
return GetRawAxis(m_axes[kDefaultThrottleAxis]);
return GetRawAxis(m_axes[Axis::kThrottle]);
}
/**

View File

@@ -311,8 +311,8 @@ void PWM::SetZeroLatch() {
}
void PWM::InitSendable(SendableBuilder& builder) {
builder.SetSmartDashboardType("Speed Controller");
builder.SetSmartDashboardType("PWM");
builder.SetSafeState([=]() { SetDisabled(); });
builder.AddDoubleProperty("Value", [=]() { return GetSpeed(); },
[=](double value) { SetSpeed(value); });
builder.AddDoubleProperty("Value", [=]() { return GetRaw(); },
[=](double value) { SetRaw(value); });
}

View File

@@ -7,6 +7,8 @@
#include "PWMSpeedController.h"
#include "SmartDashboard/SendableBuilder.h"
using namespace frc;
/**
@@ -52,3 +54,10 @@ void PWMSpeedController::StopMotor() { SafePWM::StopMotor(); }
* @param output Write out the PWM value as was found in the PIDController
*/
void PWMSpeedController::PIDWrite(double output) { Set(output); }
void PWMSpeedController::InitSendable(SendableBuilder& builder) {
builder.SetSmartDashboardType("Speed Controller");
builder.SetSafeState([=]() { SetDisabled(); });
builder.AddDoubleProperty("Value", [=]() { return GetSpeed(); },
[=](double value) { SetSpeed(value); });
}

View File

@@ -61,6 +61,57 @@ SerialPort::SerialPort(int baudRate, Port port, int dataBits,
HAL_Report(HALUsageReporting::kResourceType_SerialPort, 0);
}
/**
* Create an instance of a Serial Port class.
*
* @param baudRate The baud rate to configure the serial port.
* @param port The physical port to use
* @param portName The direct port name to use
* @param dataBits The number of data bits per transfer. Valid values are
* between 5 and 8 bits.
* @param parity Select the type of parity checking to use.
* @param stopBits The number of stop bits to use as defined by the enum
* StopBits.
*/
SerialPort::SerialPort(int baudRate, llvm::StringRef portName, Port port,
int dataBits, SerialPort::Parity parity,
SerialPort::StopBits stopBits) {
int32_t status = 0;
m_port = port;
llvm::SmallVector<char, 64> buf;
const char* portNameC = portName.c_str(buf);
HAL_InitializeSerialPortDirect(static_cast<HAL_SerialPort>(port), portNameC,
&status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
// Don't continue if initialization failed
if (status < 0) return;
HAL_SetSerialBaudRate(static_cast<HAL_SerialPort>(port), baudRate, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
HAL_SetSerialDataBits(static_cast<HAL_SerialPort>(port), dataBits, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
HAL_SetSerialParity(static_cast<HAL_SerialPort>(port), parity, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
HAL_SetSerialStopBits(static_cast<HAL_SerialPort>(port), stopBits, &status);
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
// Set the default timeout to 5 seconds.
SetTimeout(5.0);
// Don't wait until the buffer is full to transmit.
SetWriteBufferMode(kFlushOnAccess);
EnableTermination();
// viInstallHandler(m_portHandle, VI_EVENT_IO_COMPLETION, ioCompleteHandler,
// this);
// viEnableEvent(m_portHandle, VI_EVENT_IO_COMPLETION, VI_HNDLR, VI_NULL);
HAL_Report(HALUsageReporting::kResourceType_SerialPort, 0);
}
/**
* Destructor.
*/

View File

@@ -12,3 +12,8 @@ using namespace frc;
const char* SendableChooserBase::kDefault = "default";
const char* SendableChooserBase::kOptions = "options";
const char* SendableChooserBase::kSelected = "selected";
/**
* Instantiates a SendableChooser.
*/
SendableChooserBase::SendableChooserBase() : SendableBase(false) {}

View File

@@ -43,10 +43,15 @@ void TimedRobot::SetPeriod(double period) {
m_period = period;
if (m_startLoop) {
m_loop->StartPeriodic(m_period);
m_loop->StartPeriodic(period);
}
}
/**
* Get time period between calls to Periodic() functions.
*/
double TimedRobot::GetPeriod() const { return m_period; }
TimedRobot::TimedRobot() {
m_loop = std::make_unique<Notifier>(&TimedRobot::LoopFunc, this);

View File

@@ -28,6 +28,7 @@ class PWMSpeedController : public SafePWM, public SpeedController {
protected:
explicit PWMSpeedController(int channel);
void InitSendable(SendableBuilder& builder) override;
private:
bool m_isInverted = false;

View File

@@ -10,6 +10,7 @@
#include <string>
#include <llvm/StringRef.h>
#include <support/deprecated.h>
#include "ErrorBase.h"
@@ -56,6 +57,10 @@ class SerialPort : public ErrorBase {
SerialPort(int baudRate, Port port = kOnboard, int dataBits = 8,
Parity parity = kParity_None, StopBits stopBits = kStopBits_One);
WPI_DEPRECATED("Will be removed for 2019")
SerialPort(int baudRate, llvm::StringRef portName, Port port = kOnboard,
int dataBits = 8, Parity parity = kParity_None,
StopBits stopBits = kStopBits_One);
~SerialPort();
SerialPort(const SerialPort&) = delete;

View File

@@ -62,7 +62,7 @@ void SendableChooser<T>::AddDefault(llvm::StringRef name, T object) {
template <class T>
auto SendableChooser<T>::GetSelected()
-> decltype(_unwrap_smart_ptr(m_choices[""])) {
llvm::StringRef selected = m_defaultChoice;
std::string selected = m_defaultChoice;
if (m_selectedEntry) {
selected = m_selectedEntry.GetString(m_defaultChoice);
}

View File

@@ -23,6 +23,7 @@ namespace frc {
*/
class SendableChooserBase : public SendableBase {
public:
SendableChooserBase();
~SendableChooserBase() override = default;
protected:

View File

@@ -7,6 +7,7 @@
#pragma once
#include <atomic>
#include <memory>
#include "IterativeRobotBase.h"
@@ -30,13 +31,14 @@ class TimedRobot : public IterativeRobotBase {
void StartCompetition() override;
void SetPeriod(double seconds);
double GetPeriod() const;
protected:
TimedRobot();
virtual ~TimedRobot();
private:
double m_period = kDefaultPeriod;
std::atomic<double> m_period{kDefaultPeriod};
// Prevents loop from starting if user calls SetPeriod() in RobotInit()
bool m_startLoop = false;

View File

@@ -7,9 +7,11 @@
#include "ExampleCommand.h"
#include "../Robot.h"
ExampleCommand::ExampleCommand() {
// Use Requires() here to declare subsystem dependencies
// eg. Requires(&Robot::chassis);
Requires(&Robot::m_subsystem);
}
// Called just before this Command runs the first time

View File

@@ -7,9 +7,11 @@
#include "MyAutoCommand.h"
#include "../Robot.h"
MyAutoCommand::MyAutoCommand() {
// Use Requires() here to declare subsystem dependencies
// eg. Requires(&Robot::chassis);
Requires(&Robot::m_subsystem);
}
// Called just before this Command runs the first time

View File

@@ -5,93 +5,77 @@
/* the project. */
/*----------------------------------------------------------------------------*/
#include <Commands/Command.h>
#include "Robot.h"
#include <Commands/Scheduler.h>
#include <LiveWindow/LiveWindow.h>
#include <SmartDashboard/SendableChooser.h>
#include <SmartDashboard/SmartDashboard.h>
#include <TimedRobot.h>
#include "Commands/ExampleCommand.h"
#include "Commands/MyAutoCommand.h"
ExampleSubsystem Robot::m_subsystem;
OI Robot::m_oi;
class Robot : public frc::TimedRobot {
public:
void RobotInit() override {
m_chooser.AddDefault("Default Auto", &m_defaultAuto);
m_chooser.AddObject("My Auto", &m_myAuto);
frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
void Robot::RobotInit() {
m_chooser.AddDefault("Default Auto", &m_defaultAuto);
m_chooser.AddObject("My Auto", &m_myAuto);
frc::SmartDashboard::PutData("Auto Modes", &m_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 Robot::DisabledInit() {}
void Robot::DisabledPeriodic() {
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 Robot::AutonomousInit() {
// std::string autoSelected = frc::SmartDashboard::GetString(
// "Auto Selector", "Default");
// if (autoSelected == "My Auto") {
// m_autonomousCommand = &m_myAuto;
// } else {
// m_autonomousCommand = &m_defaultAuto;
// }
m_autonomousCommand = m_chooser.GetSelected();
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Start();
}
}
/**
* 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 Robot::AutonomousPeriodic() {
frc::Scheduler::GetInstance()->Run();
}
void DisabledPeriodic() override {
frc::Scheduler::GetInstance()->Run();
void Robot::TeleopInit() {
// 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 (m_autonomousCommand != nullptr) {
m_autonomousCommand->Cancel();
m_autonomousCommand = nullptr;
}
}
/**
* 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") {
m_autonomousCommand = &m_myAuto;
} else {
m_autonomousCommand = &m_defaultAuto;
}
void Robot::TeleopPeriodic() {
frc::Scheduler::GetInstance()->Run();
}
m_autonomousCommand = m_chooser.GetSelected();
if (m_autonomousCommand != nullptr) {
m_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 (m_autonomousCommand != nullptr) {
m_autonomousCommand->Cancel();
m_autonomousCommand = nullptr;
}
}
void TeleopPeriodic() override { frc::Scheduler::GetInstance()->Run(); }
void TestPeriodic() override {}
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc::Command* m_autonomousCommand = nullptr;
ExampleCommand m_defaultAuto;
MyAutoCommand m_myAuto;
frc::SendableChooser<frc::Command*> m_chooser;
};
void Robot::TestPeriodic() {}
START_ROBOT_CLASS(Robot)

View File

@@ -0,0 +1,40 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <Commands/Command.h>
#include <SmartDashboard/SendableChooser.h>
#include <TimedRobot.h>
#include "Commands/ExampleCommand.h"
#include "Commands/MyAutoCommand.h"
#include "OI.h"
#include "Subsystems/ExampleSubsystem.h"
class Robot : public frc::TimedRobot {
public:
static ExampleSubsystem m_subsystem;
static OI m_oi;
void RobotInit() override;
void DisabledInit() override;
void DisabledPeriodic() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc::Command* m_autonomousCommand = nullptr;
ExampleCommand m_defaultAuto;
MyAutoCommand m_myAuto;
frc::SendableChooser<frc::Command*> m_chooser;
};

View File

@@ -5,69 +5,54 @@
/* the project. */
/*----------------------------------------------------------------------------*/
#include <iostream>
#include <string>
#include "Robot.h"
#include <iostream>
#include <IterativeRobot.h>
#include <LiveWindow/LiveWindow.h>
#include <SmartDashboard/SendableChooser.h>
#include <SmartDashboard/SmartDashboard.h>
class Robot : public frc::IterativeRobot {
public:
void RobotInit() {
m_chooser.AddDefault(kAutoNameDefault, kAutoNameDefault);
m_chooser.AddObject(kAutoNameCustom, kAutoNameCustom);
frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
void Robot::RobotInit() {
m_chooser.AddDefault(kAutoNameDefault, kAutoNameDefault);
m_chooser.AddObject(kAutoNameCustom, kAutoNameCustom);
frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
}
/**
* 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 Robot::AutonomousInit() {
m_autoSelected = m_chooser.GetSelected();
// m_autoSelected = SmartDashboard::GetString(
// "Auto Selector", kAutoNameDefault);
std::cout << "Auto selected: " << m_autoSelected << std::endl;
if (m_autoSelected == kAutoNameCustom) {
// Custom Auto goes here
} else {
// Default Auto goes here
}
}
/*
* This autonomous (along with the chooser code above) shows how to
* select
* between different autonomous modes using the dashboard. The sendable
* chooser code works with the Java SmartDashboard. If you prefer the
* LabVIEW Dashboard, remove all of the chooser code and uncomment the
* GetString line to get the auto name from the text box below the Gyro.
*
* You can add additional auto modes by adding additional comparisons to
* the
* if-else structure below with additional strings. If using the
* SendableChooser make sure to add them to the chooser code above as
* well.
*/
void AutonomousInit() override {
m_autoSelected = m_chooser.GetSelected();
// m_autoSelected = SmartDashboard::GetString(
// "Auto Selector", kAutoNameDefault);
std::cout << "Auto selected: " << m_autoSelected << std::endl;
if (m_autoSelected == kAutoNameCustom) {
// Custom Auto goes here
} else {
// Default Auto goes here
}
void Robot::AutonomousPeriodic() {
if (m_autoSelected == kAutoNameCustom) {
// Custom Auto goes here
} else {
// Default Auto goes here
}
}
void AutonomousPeriodic() {
if (m_autoSelected == kAutoNameCustom) {
// Custom Auto goes here
} else {
// Default Auto goes here
}
}
void Robot::TeleopInit() {}
void TeleopInit() {}
void Robot::TeleopPeriodic() {}
void TeleopPeriodic() {}
void TestPeriodic() {}
private:
frc::LiveWindow& m_lw = *LiveWindow::GetInstance();
frc::SendableChooser<std::string> m_chooser;
const std::string kAutoNameDefault = "Default";
const std::string kAutoNameCustom = "My Auto";
std::string m_autoSelected;
};
void Robot::TestPeriodic() {}
START_ROBOT_CLASS(Robot)

View File

@@ -0,0 +1,29 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <string>
#include <IterativeRobot.h>
#include <SmartDashboard/SendableChooser.h>
class Robot : public frc::IterativeRobot {
public:
void RobotInit() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
private:
frc::SendableChooser<std::string> m_chooser;
const std::string kAutoNameDefault = "Default";
const std::string kAutoNameCustom = "My Auto";
std::string m_autoSelected;
};

View File

@@ -5,121 +5,87 @@
/* the project. */
/*----------------------------------------------------------------------------*/
#include <iostream>
#include <string>
#include "Robot.h"
#include <iostream>
#include <Drive/DifferentialDrive.h>
#include <Joystick.h>
#include <SampleRobot.h>
#include <SmartDashboard/SendableChooser.h>
#include <SmartDashboard/SmartDashboard.h>
#include <Spark.h>
#include <Timer.h>
Robot::Robot() {
// Note SmartDashboard is not initialized here, wait until
// RobotInit to make SmartDashboard calls
m_robotDrive.SetExpiration(0.1);
}
void Robot::RobotInit() {
m_chooser.AddDefault(kAutoNameDefault, kAutoNameDefault);
m_chooser.AddObject(kAutoNameCustom, kAutoNameCustom);
frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
}
/**
* This is a demo program showing the use of the DifferentialDrive class.
* The SampleRobot class is the base of a robot application that will
* automatically call your Autonomous and OperatorControl methods at the right
* time as controlled by the switches on the driver station or the field
* controls.
* 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.
*
* WARNING: While it may look like a good choice to use for your code if you're
* inexperienced, don't. Unless you know what you are doing, complex code will
* be much more difficult under this system. Use IterativeRobot or Command-Based
* instead if you're new.
* 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.
*/
class Robot : public frc::SampleRobot {
public:
Robot() {
// Note SmartDashboard is not initialized here, wait until
// RobotInit to make SmartDashboard calls
m_robotDrive.SetExpiration(0.1);
void Robot::Autonomous() {
std::string autoSelected = m_chooser.GetSelected();
// std::string autoSelected = frc::SmartDashboard::GetString(
// "Auto Selector", kAutoNameDefault);
std::cout << "Auto selected: " << autoSelected << std::endl;
// MotorSafety improves safety when motors are updated in loops
// but is disabled here because motor updates are not looped in
// this autonomous mode.
m_robotDrive.SetSafetyEnabled(false);
if (autoSelected == kAutoNameCustom) {
// Custom Auto goes here
std::cout << "Running custom Autonomous" << std::endl;
// Spin at half speed for two seconds
m_robotDrive.ArcadeDrive(0.0, 0.5);
frc::Wait(2.0);
// Stop robot
m_robotDrive.ArcadeDrive(0.0, 0.0);
} else {
// Default Auto goes here
std::cout << "Running default Autonomous" << std::endl;
// Drive forwards at half speed for two seconds
m_robotDrive.ArcadeDrive(-0.5, 0.0);
frc::Wait(2.0);
// Stop robot
m_robotDrive.ArcadeDrive(0.0, 0.0);
}
}
void RobotInit() {
m_chooser.AddDefault(kAutoNameDefault, kAutoNameDefault);
m_chooser.AddObject(kAutoNameCustom, kAutoNameCustom);
frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
/**
* Runs the motors with arcade steering.
*/
void Robot::OperatorControl() {
m_robotDrive.SetSafetyEnabled(true);
while (IsOperatorControl() && IsEnabled()) {
// Drive with arcade style (use right stick)
m_robotDrive.ArcadeDrive(-m_stick.GetY(), m_stick.GetX());
// The motors will be updated every 5ms
frc::Wait(0.005);
}
}
/*
* 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 Autonomous() {
std::string autoSelected = m_chooser.GetSelected();
// std::string autoSelected = frc::SmartDashboard::GetString(
// "Auto Selector", kAutoNameDefault);
std::cout << "Auto selected: " << autoSelected << std::endl;
// MotorSafety improves safety when motors are updated in loops
// but is disabled here because motor updates are not looped in
// this autonomous mode.
m_robotDrive.SetSafetyEnabled(false);
if (autoSelected == kAutoNameCustom) {
// Custom Auto goes here
std::cout << "Running custom Autonomous" << std::endl;
// Spin at half speed for two seconds
m_robotDrive.ArcadeDrive(0.0, 0.5);
frc::Wait(2.0);
// Stop robot
m_robotDrive.ArcadeDrive(0.0, 0.0);
} else {
// Default Auto goes here
std::cout << "Running default Autonomous" << std::endl;
// Drive forwards at half speed for two seconds
m_robotDrive.ArcadeDrive(-0.5, 0.0);
frc::Wait(2.0);
// Stop robot
m_robotDrive.ArcadeDrive(0.0, 0.0);
}
}
/*
* Runs the motors with arcade steering.
*/
void OperatorControl() override {
m_robotDrive.SetSafetyEnabled(true);
while (IsOperatorControl() && IsEnabled()) {
// Drive with arcade style (use right stick)
m_robotDrive.ArcadeDrive(
-m_stick.GetY(), m_stick.GetX());
// The motors will be updated every 5ms
frc::Wait(0.005);
}
}
/*
* Runs during test mode
*/
void Test() override {}
private:
// Robot drive system
frc::Spark m_leftMotor{0};
frc::Spark m_rightMotor{1};
frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor};
frc::Joystick m_stick{0};
frc::SendableChooser<std::string> m_chooser;
const std::string kAutoNameDefault = "Default";
const std::string kAutoNameCustom = "My Auto";
};
/**
* Runs during test mode
*/
void Robot::Test() {}
START_ROBOT_CLASS(Robot)

View File

@@ -0,0 +1,50 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <string>
#include <Drive/DifferentialDrive.h>
#include <Joystick.h>
#include <SampleRobot.h>
#include <SmartDashboard/SendableChooser.h>
#include <Spark.h>
/**
* This is a demo program showing the use of the DifferentialDrive class.
* The SampleRobot class is the base of a robot application that will
* automatically call your Autonomous and OperatorControl methods at the right
* time as controlled by the switches on the driver station or the field
* controls.
*
* WARNING: While it may look like a good choice to use for your code if you're
* inexperienced, don't. Unless you know what you are doing, complex code will
* be much more difficult under this system. Use IterativeRobot or Command-Based
* instead if you're new.
*/
class Robot : public frc::SampleRobot {
public:
Robot();
void RobotInit() override;
void Autonomous() override;
void OperatorControl() override;
void Test() override;
private:
// Robot drive system
frc::Spark m_leftMotor{0};
frc::Spark m_rightMotor{1};
frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor};
frc::Joystick m_stick{0};
frc::SendableChooser<std::string> m_chooser;
const std::string kAutoNameDefault = "Default";
const std::string kAutoNameCustom = "My Auto";
};

View File

@@ -5,68 +5,54 @@
/* the project. */
/*----------------------------------------------------------------------------*/
#include "Robot.h"
#include <iostream>
#include <string>
#include <LiveWindow/LiveWindow.h>
#include <SmartDashboard/SendableChooser.h>
#include <SmartDashboard/SmartDashboard.h>
#include <TimedRobot.h>
class Robot : public frc::TimedRobot {
public:
void RobotInit() {
m_chooser.AddDefault(kAutoNameDefault, kAutoNameDefault);
m_chooser.AddObject(kAutoNameCustom, kAutoNameCustom);
frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
void Robot::RobotInit() {
m_chooser.AddDefault(kAutoNameDefault, kAutoNameDefault);
m_chooser.AddObject(kAutoNameCustom, kAutoNameCustom);
frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
}
/**
* 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 Robot::AutonomousInit() {
m_autoSelected = m_chooser.GetSelected();
// m_autoSelected = SmartDashboard::GetString("Auto Selector",
// kAutoNameDefault);
std::cout << "Auto selected: " << m_autoSelected << std::endl;
if (m_autoSelected == kAutoNameCustom) {
// Custom Auto goes here
} else {
// Default Auto goes here
}
}
/*
* This autonomous (along with the chooser code above) shows how to
* select between different autonomous modes using the dashboard. The
* sendable chooser code works with the Java SmartDashboard. If you
* prefer the LabVIEW Dashboard, remove all of the chooser code and
* uncomment the GetString line to get the auto name from the text box
* below the Gyro.
*
* You can add additional auto modes by adding additional comparisons to
* the if-else structure below with additional strings. If using the
* SendableChooser make sure to add them to the chooser code above as
* well.
*/
void AutonomousInit() override {
m_autoSelected = m_chooser.GetSelected();
// m_autoSelected = SmartDashboard::GetString("Auto Selector",
// kAutoNameDefault);
std::cout << "Auto selected: " << m_autoSelected << std::endl;
if (m_autoSelected == kAutoNameCustom) {
// Custom Auto goes here
} else {
// Default Auto goes here
}
void Robot::AutonomousPeriodic() {
if (m_autoSelected == kAutoNameCustom) {
// Custom Auto goes here
} else {
// Default Auto goes here
}
}
void AutonomousPeriodic() {
if (m_autoSelected == kAutoNameCustom) {
// Custom Auto goes here
} else {
// Default Auto goes here
}
}
void Robot::TeleopInit() {}
void TeleopInit() {}
void Robot::TeleopPeriodic() {}
void TeleopPeriodic() {}
void TestPeriodic() {}
private:
frc::LiveWindow& m_lw = *LiveWindow::GetInstance();
frc::SendableChooser<std::string> m_chooser;
const std::string kAutoNameDefault = "Default";
const std::string kAutoNameCustom = "My Auto";
std::string m_autoSelected;
};
void Robot::TestPeriodic() {}
START_ROBOT_CLASS(Robot)

View File

@@ -0,0 +1,29 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <string>
#include <SmartDashboard/SendableChooser.h>
#include <TimedRobot.h>
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
private:
frc::SendableChooser<std::string> m_chooser;
const std::string kAutoNameDefault = "Default";
const std::string kAutoNameCustom = "My Auto";
std::string m_autoSelected;
};

View File

@@ -80,6 +80,10 @@ public class ADXRS450_Gyro extends GyroBase implements Gyro, PIDSource, Sendable
setName("ADXRS450_Gyro", port.value);
}
public boolean isConnected() {
return m_spi != null;
}
@Override
public void calibrate() {
if (m_spi == null) {
@@ -128,7 +132,9 @@ public class ADXRS450_Gyro extends GyroBase implements Gyro, PIDSource, Sendable
@Override
public void reset() {
m_spi.resetAccumulator();
if (m_spi != null) {
m_spi.resetAccumulator();
}
}
/**

View File

@@ -252,39 +252,43 @@ public class CameraServer {
}
NetworkTableEntry entry = table.getEntry(name);
switch (event.propertyKind) {
case kBoolean:
if (isNew) {
entry.setDefaultBoolean(event.value != 0);
} else {
entry.setBoolean(event.value != 0);
}
break;
case kInteger:
case kEnum:
if (isNew) {
entry.setDefaultDouble(event.value);
table.getEntry(infoName + "/min").setDouble(
CameraServerJNI.getPropertyMin(event.propertyHandle));
table.getEntry(infoName + "/max").setDouble(
CameraServerJNI.getPropertyMax(event.propertyHandle));
table.getEntry(infoName + "/step").setDouble(
CameraServerJNI.getPropertyStep(event.propertyHandle));
table.getEntry(infoName + "/default").setDouble(
CameraServerJNI.getPropertyDefault(event.propertyHandle));
} else {
entry.setDouble(event.value);
}
break;
case kString:
if (isNew) {
entry.setDefaultString(event.valueStr);
} else {
entry.setString(event.valueStr);
}
break;
default:
break;
try {
switch (event.propertyKind) {
case kBoolean:
if (isNew) {
entry.setDefaultBoolean(event.value != 0);
} else {
entry.setBoolean(event.value != 0);
}
break;
case kInteger:
case kEnum:
if (isNew) {
entry.setDefaultDouble(event.value);
table.getEntry(infoName + "/min").setDouble(
CameraServerJNI.getPropertyMin(event.propertyHandle));
table.getEntry(infoName + "/max").setDouble(
CameraServerJNI.getPropertyMax(event.propertyHandle));
table.getEntry(infoName + "/step").setDouble(
CameraServerJNI.getPropertyStep(event.propertyHandle));
table.getEntry(infoName + "/default").setDouble(
CameraServerJNI.getPropertyDefault(event.propertyHandle));
} else {
entry.setDouble(event.value);
}
break;
case kString:
if (isNew) {
entry.setDefaultString(event.valueStr);
} else {
entry.setString(event.valueStr);
}
break;
default:
break;
}
} catch (VideoException ex) {
// ignore
}
}
@@ -388,8 +392,12 @@ public class CameraServer {
case kSourcePropertyChoicesUpdated: {
NetworkTable table = m_tables.get(event.sourceHandle);
if (table != null) {
String[] choices = CameraServerJNI.getEnumPropertyChoices(event.propertyHandle);
table.getEntry("PropertyInfo/" + event.name + "/choices").setStringArray(choices);
try {
String[] choices = CameraServerJNI.getEnumPropertyChoices(event.propertyHandle);
table.getEntry("PropertyInfo/" + event.name + "/choices").setStringArray(choices);
} catch (VideoException ex) {
// ignore
}
}
break;
}

View File

@@ -99,6 +99,18 @@ public class Notifier {
}
});
m_thread.setDaemon(true);
m_thread.setUncaughtExceptionHandler((thread, error) -> {
Throwable cause = error.getCause();
if (cause != null) {
error = cause;
}
DriverStation.reportError("Unhandled exception: " + error.toString(), error.getStackTrace());
DriverStation.reportWarning("Robots should not quit, but yours did!", false);
DriverStation.reportError(
"The loopFunc() method (or methods called by it) should have handled "
+ "the exception above.", false);
System.exit(1);
});
m_thread.start();
}

View File

@@ -244,8 +244,8 @@ public class PWM extends SendableBase implements Sendable {
@Override
public void initSendable(SendableBuilder builder) {
builder.setSmartDashboardType("Speed Controller");
builder.setSmartDashboardType("PWM");
builder.setSafeState(this::setDisabled);
builder.addDoubleProperty("Value", this::getSpeed, this::setSpeed);
builder.addDoubleProperty("Value", this::getRaw, value -> setRaw((int) value));
}
}

View File

@@ -7,6 +7,8 @@
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
/**
* Common base class for all PWM Speed Controllers.
*/
@@ -66,4 +68,11 @@ public abstract class PWMSpeedController extends SafePWM implements SpeedControl
public void pidWrite(double output) {
set(output);
}
@Override
public void initSendable(SendableBuilder builder) {
builder.setSmartDashboardType("Speed Controller");
builder.setSafeState(this::setDisabled);
builder.addDoubleProperty("Value", this::getSpeed, this::setSpeed);
}
}

View File

@@ -94,6 +94,42 @@ public class SerialPort {
}
}
/**
* Create an instance of a Serial Port class.
*
* @param baudRate The baud rate to configure the serial port.
* @param port The Serial port to use
* @param portName The direct portName to use
* @param dataBits The number of data bits per transfer. Valid values are between 5 and 8 bits.
* @param parity Select the type of parity checking to use.
* @param stopBits The number of stop bits to use as defined by the enum StopBits.
* @deprecated Will be removed for 2019
*/
@Deprecated
public SerialPort(final int baudRate, String portName, Port port, final int dataBits,
Parity parity, StopBits stopBits) {
m_port = (byte) port.value;
SerialPortJNI.serialInitializePortDirect(m_port, portName);
SerialPortJNI.serialSetBaudRate(m_port, baudRate);
SerialPortJNI.serialSetDataBits(m_port, (byte) dataBits);
SerialPortJNI.serialSetParity(m_port, (byte) parity.value);
SerialPortJNI.serialSetStopBits(m_port, (byte) stopBits.value);
// Set the default read buffer size to 1 to return bytes immediately
setReadBufferSize(1);
// Set the default timeout to 5 seconds.
setTimeout(5.0);
// Don't wait until the buffer is full to transmit.
setWriteBufferMode(WriteBufferMode.kFlushOnAccess);
disableTermination();
HAL.report(tResourceType.kResourceType_SerialPort, 0);
}
/**
* Create an instance of a Serial Port class.
*

View File

@@ -21,7 +21,7 @@ import edu.wpi.first.wpilibj.hal.HAL;
public class TimedRobot extends IterativeRobotBase {
public static final double DEFAULT_PERIOD = 0.02;
private double m_period = DEFAULT_PERIOD;
private volatile double m_period = DEFAULT_PERIOD;
// Prevents loop from starting if user calls setPeriod() in robotInit()
private boolean m_startLoop = false;
@@ -68,4 +68,11 @@ public class TimedRobot extends IterativeRobotBase {
m_loop.startPeriodic(m_period);
}
}
/**
* Get time period between calls to Periodic() functions.
*/
public double getPeriod() {
return m_period;
}
}

View File

@@ -261,6 +261,13 @@ public class DifferentialDrive extends RobotDriveBase {
}
}
// Normalize the wheel speeds
double maxMagnitude = Math.max(Math.abs(leftMotorOutput), Math.abs(rightMotorOutput));
if (maxMagnitude > 1.0) {
leftMotorOutput /= maxMagnitude;
rightMotorOutput /= maxMagnitude;
}
m_leftMotor.set(leftMotorOutput * m_maxOutput);
m_rightMotor.set(-rightMotorOutput * m_maxOutput);

View File

@@ -189,11 +189,11 @@ public class MecanumDrive extends RobotDriveBase {
builder.setSmartDashboardType("MecanumDrive");
builder.addDoubleProperty("Front Left Motor Speed", m_frontLeftMotor::get,
m_frontLeftMotor::set);
builder.addDoubleProperty("Front Right Motor Speed", m_frontRightMotor::get,
m_frontRightMotor::set);
builder.addDoubleProperty("Front Right Motor Speed", () -> -m_frontRightMotor.get(),
value -> m_frontRightMotor.set(-value));
builder.addDoubleProperty("Rear Left Motor Speed", m_rearLeftMotor::get,
m_rearLeftMotor::set);
builder.addDoubleProperty("Rear Right Motor Speed", m_rearRightMotor::get,
m_rearRightMotor::set);
builder.addDoubleProperty("Rear Right Motor Speed", () -> -m_rearRightMotor.get(),
value -> m_rearRightMotor.set(-value));
}
}

View File

@@ -43,9 +43,11 @@ public abstract class RobotDriveBase extends SendableBase implements MotorSafety
}
/**
* Change the default value for deadband scaling. The default value is
* {@value #kDefaultDeadband}. Values smaller then the deadband are set to 0, while values
* larger then the deadband are scaled from 0.0 to 1.0. See {@link #applyDeadband}.
* Sets the deadband applied to the drive inputs (e.g., joystick values).
*
* <p>The default value is {@value #kDefaultDeadband}. Inputs smaller than the deadband are set to
* 0.0 while inputs larger than the deadband are scaled from 0.0 to 1.0. See
* {@link #applyDeadband}.
*
* @param deadband The deadband to set.
*/

View File

@@ -15,8 +15,11 @@ public class DIOJNI extends JNIWrapper {
public static native void freeDIOPort(int dioPortHandle);
// TODO(Thad): Switch this to use boolean
public static native void setDIO(int dioPortHandle, short value);
public static native void setDIODirection(int dioPortHandle, boolean input);
public static native boolean getDIO(int dioPortHandle);
public static native boolean getDIODirection(int dioPortHandle);

View File

@@ -10,6 +10,8 @@ package edu.wpi.first.wpilibj.hal;
public class SerialPortJNI extends JNIWrapper {
public static native void serialInitializePort(byte port);
public static native void serialInitializePortDirect(byte port, String portName);
public static native void serialSetBaudRate(byte port, int baud);
public static native void serialSetDataBits(byte port, byte bits);

View File

@@ -51,6 +51,7 @@ public class SendableChooser<V> extends SendableBase implements Sendable {
* Instantiates a {@link SendableChooser}.
*/
public SendableChooser() {
super(false);
}
/**

View File

@@ -90,6 +90,22 @@ JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_DIOJNI_setDIO(
CheckStatus(env, status);
}
/*
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
* Method: setDIODirection
* Signature: (IZ)V
*/
JNIEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_DIOJNI_setDIODirection(
JNIEnv *env, jclass, jint id, jboolean input) {
// DIOJNI_LOG(logDEBUG) << "Calling DIOJNI setDIO";
// DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
// DIOJNI_LOG(logDEBUG) << "IsInput = " << input;
int32_t status = 0;
HAL_SetDIODirection((HAL_DigitalHandle)id, input, &status);
// DIOJNI_LOG(logDEBUG) << "Status = " << status;
CheckStatus(env, status);
}
/*
* Class: edu_wpi_first_wpilibj_hal_DIOJNI
* Method: getDIO

View File

@@ -36,7 +36,7 @@ extern "C" {
JNIEXPORT jint JNICALL
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_initializeEncoder(
JNIEnv* env, jclass, jint digitalSourceHandleA, jint analogTriggerTypeA,
jint digitalSourceHandleB, jint analogTriggerTypeB, jboolean reverseDirection,
jint digitalSourceHandleB, jint analogTriggerTypeB, jboolean reverseDirection,
jint encodingType) {
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI initializeEncoder";
ENCODERJNI_LOG(logDEBUG) << "Source Handle A = " << digitalSourceHandleA;
@@ -49,10 +49,10 @@ Java_edu_wpi_first_wpilibj_hal_EncoderJNI_initializeEncoder(
ENCODERJNI_LOG(logDEBUG) << "EncodingType = " << encodingType;
int32_t status = 0;
auto encoder = HAL_InitializeEncoder(
(HAL_Handle)digitalSourceHandleA, (HAL_AnalogTriggerType)analogTriggerTypeA,
(HAL_Handle)digitalSourceHandleA, (HAL_AnalogTriggerType)analogTriggerTypeA,
(HAL_Handle)digitalSourceHandleB, (HAL_AnalogTriggerType)analogTriggerTypeB,
reverseDirection, (HAL_EncoderEncodingType)encodingType, &status);
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
ENCODERJNI_LOG(logDEBUG) << "ENCODER Handle = " << encoder;
CheckStatusForceThrow(env, status);
@@ -340,7 +340,7 @@ Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncoderSamplesToAverage(
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_wpilibj_hal_EncoderJNI_setEncoderIndexSource(
JNIEnv* env, jclass, jint id, jint digitalSourceHandle,
JNIEnv* env, jclass, jint id, jint digitalSourceHandle,
jint analogTriggerType, jint type) {
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI setEncoderIndexSource";
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
@@ -349,8 +349,8 @@ Java_edu_wpi_first_wpilibj_hal_EncoderJNI_setEncoderIndexSource(
<< analogTriggerType;
ENCODERJNI_LOG(logDEBUG) << "IndexingType = " << type;
int32_t status = 0;
HAL_SetEncoderIndexSource((HAL_EncoderHandle)id, (HAL_Handle)digitalSourceHandle,
(HAL_AnalogTriggerType)analogTriggerType,
HAL_SetEncoderIndexSource((HAL_EncoderHandle)id, (HAL_Handle)digitalSourceHandle,
(HAL_AnalogTriggerType)analogTriggerType,
(HAL_EncoderIndexingType)type, &status);
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
CheckStatus(env, status);
@@ -405,7 +405,7 @@ Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncoderDecodingScaleFactor(
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderSamplesToAverage";
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
int32_t status = 0;
jint returnValue = HAL_GetEncoderDecodingScaleFactor((HAL_EncoderHandle)id, &status);
jdouble returnValue = HAL_GetEncoderDecodingScaleFactor((HAL_EncoderHandle)id, &status);
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
ENCODERJNI_LOG(logDEBUG) << "getEncoderSamplesToAverageResult = "
<< returnValue;
@@ -424,7 +424,7 @@ Java_edu_wpi_first_wpilibj_hal_EncoderJNI_getEncoderDistancePerPulse(
ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderSamplesToAverage";
ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
int32_t status = 0;
jint returnValue = HAL_GetEncoderDistancePerPulse((HAL_EncoderHandle)id, &status);
jdouble returnValue = HAL_GetEncoderDistancePerPulse((HAL_EncoderHandle)id, &status);
ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
ENCODERJNI_LOG(logDEBUG) << "getEncoderSamplesToAverageResult = "
<< returnValue;

View File

@@ -45,6 +45,25 @@ Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialInitializePort(
CheckStatusForceThrow(env, status);
}
/*
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
* Method: serialInitializePortDirect
* Signature: (BLjava/lang/String;)V
*/
JNIEXPORT void JNICALL
Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialInitializePortDirect(
JNIEnv* env, jclass, jbyte port, jstring portName) {
SERIALJNI_LOG(logDEBUG) << "Calling Serial Initialize Direct";
SERIALJNI_LOG(logDEBUG) << "Port = " << (jint)port;
JStringRef portNameRef{env, portName};
SERIALJNI_LOG(logDEBUG) << "PortName = " << portNameRef.c_str();
int32_t status = 0;
HAL_InitializeSerialPortDirect(static_cast<HAL_SerialPort>(port),
portNameRef.c_str(), &status);
SERIALJNI_LOG(logDEBUG) << "Status = " << status;
CheckStatusForceThrow(env, status);
}
/*
* Class: edu_wpi_first_wpilibj_hal_SerialPortJNI
* Method: serialSetBaudRate
@@ -247,7 +266,7 @@ JNIEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_SerialPortJNI_serialRead(
llvm::SmallVector<char, 128> recvBuf;
recvBuf.resize(size);
int32_t status = 0;
jint retVal = HAL_ReadSerial(static_cast<HAL_SerialPort>(port), recvBuf.data(),
jint retVal = HAL_ReadSerial(static_cast<HAL_SerialPort>(port), recvBuf.data(),
size, &status);
env->SetByteArrayRegion(dataReceived, 0, size,
reinterpret_cast<const jbyte *>(recvBuf.data()));

View File

@@ -23,8 +23,7 @@ import edu.wpi.first.wpilibj.templates.commandbased.subsystems.ExampleSubsystem;
* project.
*/
public class Robot extends TimedRobot {
public static final ExampleSubsystem kExampleSubsystem
= new ExampleSubsystem();
public static ExampleSubsystem m_subsystem = new ExampleSubsystem();
public static OI m_oi;
Command m_autonomousCommand;

View File

@@ -16,7 +16,7 @@ import edu.wpi.first.wpilibj.templates.commandbased.Robot;
public class ExampleCommand extends Command {
public ExampleCommand() {
// Use requires() here to declare subsystem dependencies
requires(Robot.kExampleSubsystem);
requires(Robot.m_subsystem);
}
// Called just before this Command runs the first time