mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Compare commits
10 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
96e9a6989c | ||
|
|
14228d82f3 | ||
|
|
5175829bab | ||
|
|
9d7293734a | ||
|
|
1e5ec362f7 | ||
|
|
7bb3e4efc3 | ||
|
|
67de595c85 | ||
|
|
82152e90fe | ||
|
|
1e7d439899 | ||
|
|
979984fa6b |
@@ -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'
|
||||
|
||||
@@ -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;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -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) {
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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);
|
||||
|
||||
@@ -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) {
|
||||
|
||||
@@ -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) {
|
||||
}
|
||||
|
||||
|
||||
@@ -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.
|
||||
*/
|
||||
|
||||
@@ -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); });
|
||||
}
|
||||
|
||||
@@ -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); });
|
||||
}
|
||||
|
||||
@@ -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.
|
||||
*/
|
||||
|
||||
@@ -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) {}
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -23,6 +23,7 @@ namespace frc {
|
||||
*/
|
||||
class SendableChooserBase : public SendableBase {
|
||||
public:
|
||||
SendableChooserBase();
|
||||
~SendableChooserBase() override = default;
|
||||
|
||||
protected:
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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)
|
||||
|
||||
40
wpilibcExamples/src/main/cpp/templates/commandbased/Robot.h
Normal file
40
wpilibcExamples/src/main/cpp/templates/commandbased/Robot.h
Normal 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;
|
||||
};
|
||||
@@ -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)
|
||||
|
||||
29
wpilibcExamples/src/main/cpp/templates/iterative/Robot.h
Normal file
29
wpilibcExamples/src/main/cpp/templates/iterative/Robot.h
Normal 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;
|
||||
};
|
||||
@@ -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)
|
||||
|
||||
50
wpilibcExamples/src/main/cpp/templates/sample/Robot.h
Normal file
50
wpilibcExamples/src/main/cpp/templates/sample/Robot.h
Normal 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";
|
||||
};
|
||||
@@ -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)
|
||||
|
||||
29
wpilibcExamples/src/main/cpp/templates/timed/Robot.h
Normal file
29
wpilibcExamples/src/main/cpp/templates/timed/Robot.h
Normal 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;
|
||||
};
|
||||
@@ -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();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -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;
|
||||
}
|
||||
|
||||
@@ -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));
|
||||
}
|
||||
}
|
||||
|
||||
@@ -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);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -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.
|
||||
*
|
||||
|
||||
@@ -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.
|
||||
*/
|
||||
|
||||
@@ -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);
|
||||
|
||||
@@ -51,6 +51,7 @@ public class SendableChooser<V> extends SendableBase implements Sendable {
|
||||
* Instantiates a {@link SendableChooser}.
|
||||
*/
|
||||
public SendableChooser() {
|
||||
super(false);
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -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()));
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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
|
||||
|
||||
Reference in New Issue
Block a user