diff --git a/wpilibc/wpilibC++/include/ADXL345_I2C.h b/wpilibc/wpilibC++/include/ADXL345_I2C.h index b9f588436b..4bd20baaa3 100644 --- a/wpilibc/wpilibC++/include/ADXL345_I2C.h +++ b/wpilibc/wpilibC++/include/ADXL345_I2C.h @@ -11,7 +11,7 @@ class I2C; /** * ADXL345 Accelerometer on I2C. - * + * * This class alows access to a Analog Devices ADXL345 3-axis accelerometer on an I2C bus. * This class assumes the default (not alternate) sensor address of 0x3A (8-bit address). */ @@ -38,7 +38,7 @@ public: }; public: - explicit ADXL345_I2C(uint8_t moduleNumber, DataFormat_Range range=kRange_2G); + explicit ADXL345_I2C(DataFormat_Range range=kRange_2G); virtual ~ADXL345_I2C(); virtual double GetAcceleration(Axes axis); virtual AllAxes GetAccelerations(); diff --git a/wpilibc/wpilibC++/include/ADXL345_SPI.h b/wpilibc/wpilibC++/include/ADXL345_SPI.h index f48811432f..f47f4da3d2 100644 --- a/wpilibc/wpilibC++/include/ADXL345_SPI.h +++ b/wpilibc/wpilibC++/include/ADXL345_SPI.h @@ -13,7 +13,7 @@ class SPI; /** * ADXL345 Accelerometer on SPI. - * + * * This class alows access to an Analog Devices ADXL345 3-axis accelerometer via SPI. * This class assumes the sensor is wired in 4-wire SPI mode. */ @@ -44,7 +44,7 @@ public: DigitalOutput &cs, DataFormat_Range range=kRange_2G); ADXL345_SPI(DigitalOutput *clk, DigitalOutput *mosi, DigitalInput *miso, DigitalOutput *cs, DataFormat_Range range=kRange_2G); - ADXL345_SPI(uint8_t moduleNumber, uint32_t clk, uint32_t mosi, uint32_t miso, uint32_t cs, + ADXL345_SPI(uint32_t clk, uint32_t mosi, uint32_t miso, uint32_t cs, DataFormat_Range range=kRange_2G); virtual ~ADXL345_SPI(); virtual double GetAcceleration(Axes axis); diff --git a/wpilibc/wpilibC++/include/Accelerometer.h b/wpilibc/wpilibC++/include/Accelerometer.h index 87bfd01459..dc3b5feba3 100644 --- a/wpilibc/wpilibC++/include/Accelerometer.h +++ b/wpilibc/wpilibC++/include/Accelerometer.h @@ -10,7 +10,7 @@ #include "PIDSource.h" #include "LiveWindow/LiveWindowSendable.h" -/** +/** * Handle operation of the accelerometer. * The accelerometer reads acceleration directly through the sensor. Many sensors have * multiple axis and can be treated as multiple devices. Each is calibrated by finding @@ -19,7 +19,6 @@ class Accelerometer : public SensorBase, public PIDSource, public LiveWindowSendable { public: explicit Accelerometer(uint32_t channel); - Accelerometer(uint8_t moduleNumber, uint32_t channel); explicit Accelerometer(AnalogInput *channel); virtual ~Accelerometer(); @@ -42,6 +41,6 @@ private: float m_voltsPerG; float m_zeroGVoltage; bool m_allocatedChannel; - + ITable *m_table; }; diff --git a/wpilibc/wpilibC++/include/AnalogInput.h b/wpilibc/wpilibC++/include/AnalogInput.h index cc18272f29..be0dc77662 100644 --- a/wpilibc/wpilibC++/include/AnalogInput.h +++ b/wpilibc/wpilibC++/include/AnalogInput.h @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) FIRST 2008. All Rights Reserved. */ +/* Copyright (c) FIRST 2008. 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 $(WIND_BASE)/WPILib. */ /*----------------------------------------------------------------------------*/ @@ -9,12 +9,11 @@ #include "SensorBase.h" #include "PIDSource.h" #include "LiveWindow/LiveWindowSendable.h" - -class AnalogModule; +#include "AnalogModule.h" /** * Analog input class. - * + * * Connected to each analog channel is an averaging and oversampling engine. This engine accumulates * the specified ( by SetAverageBits() and SetOversampleBits() ) number of samples before returning a new * value. This is not a sliding window average. The only difference between the oversampled samples and @@ -29,11 +28,10 @@ public: static const uint32_t kAccumulatorNumChannels = 2; static const uint32_t kAccumulatorChannels[kAccumulatorNumChannels]; - AnalogInput(uint8_t moduleNumber, uint32_t channel); explicit AnalogInput(uint32_t channel); virtual ~AnalogInput(); - AnalogModule *GetModule(); + AnalogModule *GetModule() { return AnalogModule::GetInstance(1); } int16_t GetValue(); int32_t GetAverageValue(); @@ -41,7 +39,6 @@ public: float GetVoltage(); float GetAverageVoltage(); - uint8_t GetModuleNumber(); uint32_t GetChannel(); void SetAverageBits(uint32_t bits); @@ -72,8 +69,8 @@ public: ITable * GetTable(); private: - void InitAnalogInput(uint8_t moduleNumber, uint32_t channel); - uint32_t m_channel, m_module; + void InitAnalogInput(uint32_t channel); + uint32_t m_channel; void* m_port; int64_t m_accumulatorOffset; diff --git a/wpilibc/wpilibC++/include/AnalogPotentiometer.h b/wpilibc/wpilibC++/include/AnalogPotentiometer.h index be6fbaf825..dbdf91c803 100644 --- a/wpilibc/wpilibC++/include/AnalogPotentiometer.h +++ b/wpilibc/wpilibC++/include/AnalogPotentiometer.h @@ -1,7 +1,7 @@ #include "AnalogInput.h" #include "interfaces/Potentiometer.h" -#include "LiveWindow/LiveWindowSendable.h" +#include "LiveWindow/LiveWindowSendable.h" /** * Class for reading analog potentiometers. Analog potentiometers read @@ -13,23 +13,6 @@ */ class AnalogPotentiometer : public Potentiometer, public LiveWindowSendable { public: - /** - * AnalogPotentiometer constructor. - * - * Use the scaling and offset values so that the output produces - * meaningful values. I.E: you have a 270 degree potentiometer and - * you want the output to be degrees with the halfway point as 0 - * degrees. The scale value is 270.0(degrees)/5.0(volts) and the - * offset is -135.0 since the halfway point after scaling is 135 - * degrees. - * - * @param slot The analog module this potentiometer is plugged into. - * @param channel The analog channel this potentiometer is plugged into. - * @param scale The scaling to multiply the voltage by to get a meaningful unit. - * @param offset The offset to add to the scaled value for controlling the zero value - */ - AnalogPotentiometer(int slot, int channel, double scale, double offset); - /** * AnalogPotentiometer constructor. * @@ -82,7 +65,7 @@ public: * @return The current reading. */ virtual double PIDGet(); - + /* * Live Window code, only does anything if live window is activated. */ @@ -95,14 +78,14 @@ public: * AnalogPotentiometers don't have to do anything special when entering the LiveWindow. */ virtual void StartLiveWindowMode() {} - + /** * AnalogPotentiometers don't have to do anything special when exiting the LiveWindow. */ virtual void StopLiveWindowMode() {} - + private: - int m_module, m_channel; + int m_channel; double m_scale, m_offset; AnalogInput* m_analog_channel; ITable* m_table; @@ -110,5 +93,5 @@ private: /** * Common initialization code called by all constructors. */ - void initPot(int slot, int channel, double scale, double offset); + void initPot(int channel, double scale, double offset); }; diff --git a/wpilibc/wpilibC++/include/AnalogTrigger.h b/wpilibc/wpilibC++/include/AnalogTrigger.h index 2083c40bf0..1dc34feab2 100644 --- a/wpilibc/wpilibC++/include/AnalogTrigger.h +++ b/wpilibc/wpilibC++/include/AnalogTrigger.h @@ -16,7 +16,6 @@ class AnalogTrigger : public SensorBase { friend class AnalogTriggerOutput; public: - AnalogTrigger(uint8_t moduleNumber, uint32_t channel); explicit AnalogTrigger(uint32_t channel); explicit AnalogTrigger(AnalogInput *channel); virtual ~AnalogTrigger(); @@ -31,7 +30,7 @@ public: AnalogTriggerOutput *CreateOutput(AnalogTriggerType type); private: - void InitTrigger(uint8_t moduleNumber, uint32_t channel); + void InitTrigger(uint32_t channel); uint8_t m_index; void* m_trigger; diff --git a/wpilibc/wpilibC++/include/Compressor.h b/wpilibc/wpilibC++/include/Compressor.h index 9a695a1393..6e6cc7e3e7 100644 --- a/wpilibc/wpilibC++/include/Compressor.h +++ b/wpilibc/wpilibC++/include/Compressor.h @@ -1,6 +1,8 @@ -/* - * Compressor.h - */ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) FIRST 2014. 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 $(WIND_BASE)/WPILib. */ +/*----------------------------------------------------------------------------*/ #ifndef Compressor_H_ #define Compressor_H_ @@ -11,24 +13,20 @@ #include "LiveWindow/LiveWindowSendable.h" /** - * CAN pneumatic control module compressor - * - * Created on: May 28, 2014 - * Author: Thomas Clark - * + * PCM compressor */ class Compressor: public SensorBase, public LiveWindowSendable, public ITableListener { public: - Compressor(uint8_t module); + explicit Compressor(uint8_t pcmID); Compressor(); - ~Compressor(); + virtual ~Compressor(); void Start(); void Stop(); bool Enabled(); bool GetPressureSwitchValue(); - + float GetCompressorCurrent(); void SetClosedLoopControl(bool on); diff --git a/wpilibc/wpilibC++/include/Counter.h b/wpilibc/wpilibC++/include/Counter.h index dd6685dc89..5241e30da6 100644 --- a/wpilibc/wpilibC++/include/Counter.h +++ b/wpilibc/wpilibC++/include/Counter.h @@ -23,7 +23,6 @@ public: Counter(); explicit Counter(uint32_t channel); - Counter(uint8_t moduleNumber, uint32_t channel); explicit Counter(DigitalSource *source); explicit Counter(DigitalSource &source); explicit Counter(AnalogTrigger *trigger); @@ -33,7 +32,6 @@ public: virtual ~Counter(); void SetUpSource(uint32_t channel); - void SetUpSource(uint8_t moduleNumber, uint32_t channel); void SetUpSource(AnalogTrigger *analogTrigger, AnalogTriggerType triggerType); void SetUpSource(AnalogTrigger &analogTrigger, AnalogTriggerType triggerType); void SetUpSource(DigitalSource *source); @@ -42,7 +40,6 @@ public: void ClearUpSource(); void SetDownSource(uint32_t channel); - void SetDownSource(uint8_t moduleNumber, uint32_t channel); void SetDownSource(AnalogTrigger *analogTrigger, AnalogTriggerType triggerType); void SetDownSource(AnalogTrigger &analogTrigger, AnalogTriggerType triggerType); void SetDownSource(DigitalSource *source); @@ -73,7 +70,7 @@ public: { return m_index; } - + void UpdateTable(); void StartLiveWindowMode(); void StopLiveWindowMode(); @@ -83,13 +80,13 @@ public: protected: DigitalSource *m_upSource; ///< What makes the counter count up. DigitalSource *m_downSource; ///< What makes the counter count down. - void* m_counter; ///< The FPGA counter object. + void* m_counter; ///< The FPGA counter object. private: void InitCounter(Mode mode = kTwoPulse); bool m_allocatedUpSource; ///< Was the upSource allocated locally? bool m_allocatedDownSource; ///< Was the downSource allocated locally? uint32_t m_index; ///< The index of this counter. - + ITable *m_table; }; diff --git a/wpilibc/wpilibC++/include/DigitalInput.h b/wpilibc/wpilibC++/include/DigitalInput.h index 9d8cc547ec..0aecae8c2a 100644 --- a/wpilibc/wpilibC++/include/DigitalInput.h +++ b/wpilibc/wpilibC++/include/DigitalInput.h @@ -21,7 +21,6 @@ class DigitalInput : public DigitalSource, public LiveWindowSendable { public: explicit DigitalInput(uint32_t channel); - DigitalInput(uint8_t moduleNumber, uint32_t channel); virtual ~DigitalInput(); uint32_t Get(); uint32_t GetChannel(); @@ -44,7 +43,7 @@ public: ITable * GetTable(); private: - void InitDigitalInput(uint8_t moduleNumber, uint32_t channel); + void InitDigitalInput(uint32_t channel); uint32_t m_channel; DigitalModule *m_module; bool m_lastValue; diff --git a/wpilibc/wpilibC++/include/DigitalOutput.h b/wpilibc/wpilibC++/include/DigitalOutput.h index 636fd559a3..081766b1e0 100644 --- a/wpilibc/wpilibC++/include/DigitalOutput.h +++ b/wpilibc/wpilibC++/include/DigitalOutput.h @@ -20,7 +20,6 @@ class DigitalOutput : public DigitalSource, public ITableListener, public LiveWi { public: explicit DigitalOutput(uint32_t channel); - DigitalOutput(uint8_t moduleNumber, uint32_t channel); virtual ~DigitalOutput(); void Set(uint32_t value); uint32_t GetChannel(); @@ -49,7 +48,7 @@ public: ITable * GetTable(); private: - void InitDigitalOutput(uint8_t moduleNumber, uint32_t channel); + void InitDigitalOutput(uint32_t channel); uint32_t m_channel; uint32_t m_pwmGenerator; diff --git a/wpilibc/wpilibC++/include/DriverStation.h b/wpilibc/wpilibC++/include/DriverStation.h index 5e282792ab..115e7b01c9 100644 --- a/wpilibc/wpilibC++/include/DriverStation.h +++ b/wpilibc/wpilibC++/include/DriverStation.h @@ -29,7 +29,6 @@ public: virtual ~DriverStation(); static DriverStation *GetInstance(); - static const uint32_t kBatteryModuleNumber = 1; static const uint32_t kBatteryChannel = 7; static const uint32_t kJoystickPorts = 4; static const uint32_t kJoystickAxes = 6; diff --git a/wpilibc/wpilibC++/include/Encoder.h b/wpilibc/wpilibC++/include/Encoder.h index 10caa70670..a4b6389d95 100644 --- a/wpilibc/wpilibC++/include/Encoder.h +++ b/wpilibc/wpilibC++/include/Encoder.h @@ -21,7 +21,7 @@ class DigitalSource; * reverse direction counting. When creating QuadEncoders, a direction is supplied that changes the * sense of the output to make code more readable if the encoder is mounted such that forward movement * generates negative values. Quadrature encoders have two digital outputs, an A Channel and a B Channel - * that are out of phase with each other to allow the FPGA to do direction sensing. + * that are out of phase with each other to allow the FPGA to do direction sensing. */ class Encoder : public SensorBase, public CounterBase, public PIDSource, public LiveWindowSendable { @@ -29,8 +29,6 @@ public: Encoder(uint32_t aChannel, uint32_t bChannel, bool reverseDirection = false, EncodingType encodingType = k4X); - Encoder(uint8_t aModuleNumber, uint32_t aChannel, uint8_t bModuleNumber, uint32_t _bChannel, - bool reverseDirection = false, EncodingType encodingType = k4X); Encoder(DigitalSource *aSource, DigitalSource *bSource, bool reverseDirection = false, EncodingType encodingType = k4X); Encoder(DigitalSource &aSource, DigitalSource &bSource, bool reverseDirection = false, @@ -77,6 +75,6 @@ private: Counter *m_counter; // Counter object for 1x and 2x encoding EncodingType m_encodingType; // Encoding type PIDSourceParameter m_pidSource; // Encoder parameter that sources a PID controller - + ITable *m_table; }; diff --git a/wpilibc/wpilibC++/include/GearTooth.h b/wpilibc/wpilibC++/include/GearTooth.h index 7ca82924cd..2df3c765ca 100644 --- a/wpilibc/wpilibC++/include/GearTooth.h +++ b/wpilibc/wpilibC++/include/GearTooth.h @@ -19,7 +19,6 @@ public: /// 55 uSec for threshold static constexpr double kGearToothThreshold = 55e-6; GearTooth(uint32_t channel, bool directionSensitive = false); - GearTooth(uint8_t moduleNumber, uint32_t channel, bool directionSensitive = false); GearTooth(DigitalSource *source, bool directionSensitive = false); GearTooth(DigitalSource &source, bool directionSensitive = false); virtual ~GearTooth(); diff --git a/wpilibc/wpilibC++/include/Gyro.h b/wpilibc/wpilibC++/include/Gyro.h index 0f777bc750..36e529be4d 100644 --- a/wpilibc/wpilibC++/include/Gyro.h +++ b/wpilibc/wpilibC++/include/Gyro.h @@ -10,7 +10,6 @@ #include "LiveWindow/LiveWindowSendable.h" class AnalogInput; -class AnalogModule; /** * Use a rate gyro to return the robots heading relative to a starting position. @@ -18,7 +17,7 @@ class AnalogModule; * rotates the new heading is computed by integrating the rate of rotation returned * by the sensor. When the class is instantiated, it does a short calibration routine * where it samples the gyro while at rest to determine the default offset. This is - * subtracted from each sample to determine the heading. This gyro class must be used + * subtracted from each sample to determine the heading. This gyro class must be used * with a channel that is assigned one of the Analog accumulators from the FPGA. See * AnalogInput for the current accumulator assignments. */ @@ -31,7 +30,6 @@ public: static constexpr float kCalibrationSampleTime = 5.0; static constexpr float kDefaultVoltsPerDegreePerSecond = 0.007; - Gyro(uint8_t moduleNumber, uint32_t channel); explicit Gyro(uint32_t channel); explicit Gyro(AnalogInput *channel); explicit Gyro(AnalogInput &channel); diff --git a/wpilibc/wpilibC++/include/HiTechnicColorSensor.h b/wpilibc/wpilibC++/include/HiTechnicColorSensor.h index fc6d017dfe..fbcb350ec1 100644 --- a/wpilibc/wpilibC++/include/HiTechnicColorSensor.h +++ b/wpilibc/wpilibC++/include/HiTechnicColorSensor.h @@ -36,7 +36,7 @@ public: uint16_t blue; uint16_t green; }; - explicit HiTechnicColorSensor(uint8_t moduleNumber); + HiTechnicColorSensor(); virtual ~HiTechnicColorSensor(); uint8_t GetColor(); uint8_t GetRed(); diff --git a/wpilibc/wpilibC++/include/HiTechnicCompass.h b/wpilibc/wpilibC++/include/HiTechnicCompass.h index 6aedba6dce..f0474e4d3d 100644 --- a/wpilibc/wpilibC++/include/HiTechnicCompass.h +++ b/wpilibc/wpilibC++/include/HiTechnicCompass.h @@ -12,23 +12,23 @@ class I2C; /** * HiTechnic NXT Compass. - * + * * This class alows access to a HiTechnic NXT Compass on an I2C bus. * These sensors to not allow changing addresses so you cannot have more * than one on a single bus. - * + * * Details on the sensor can be found here: * http://www.hitechnic.com/index.html?lang=en-us&target=d17.html - * + * * @todo Implement a calibration method for the sensor. */ class HiTechnicCompass : public SensorBase, public LiveWindowSendable { public: - explicit HiTechnicCompass(uint8_t moduleNumber); + HiTechnicCompass(); virtual ~HiTechnicCompass(); float GetAngle(); - + void UpdateTable(); void StartLiveWindowMode(); void StopLiveWindowMode(); @@ -45,6 +45,6 @@ private: static const uint8_t kHeadingRegister = 0x44; I2C* m_i2c; - + ITable *m_table; }; diff --git a/wpilibc/wpilibC++/include/Jaguar.h b/wpilibc/wpilibC++/include/Jaguar.h index d562f4bfd1..51ac4fe8c8 100644 --- a/wpilibc/wpilibC++/include/Jaguar.h +++ b/wpilibc/wpilibC++/include/Jaguar.h @@ -16,7 +16,6 @@ class Jaguar : public SafePWM, public SpeedController { public: explicit Jaguar(uint32_t channel); - Jaguar(uint8_t moduleNumber, uint32_t channel); virtual ~Jaguar(); virtual void Set(float value, uint8_t syncGroup = 0); virtual float Get(); diff --git a/wpilibc/wpilibC++/include/LiveWindow/LiveWindow.h b/wpilibc/wpilibC++/include/LiveWindow/LiveWindow.h index ca05c1b964..93f9cca4cd 100644 --- a/wpilibc/wpilibC++/include/LiveWindow/LiveWindow.h +++ b/wpilibc/wpilibC++/include/LiveWindow/LiveWindow.h @@ -35,9 +35,10 @@ public: void Run(); void AddSensor(const char *subsystem, const char *name, LiveWindowSendable *component); void AddActuator(const char *subsystem, const char *name, LiveWindowSendable *component); - void AddSensor(std::string type, int module, int channel, LiveWindowSendable *component); + void AddSensor(std::string type, int channel, LiveWindowSendable *component); + void AddActuator(std::string type, int channel, LiveWindowSendable *component); void AddActuator(std::string type, int module, int channel, LiveWindowSendable *component); - + bool IsEnabled() { return m_enabled; } void SetEnabled(bool enabled); @@ -49,19 +50,18 @@ private: void UpdateValues(); void Initialize(); void InitializeLiveWindowComponents(); - + std::vector m_sensors; std::map m_components; - + static LiveWindow *m_instance; ITable *m_liveWindowTable; ITable *m_statusTable; - + Scheduler *m_scheduler; - + bool m_enabled; bool m_firstTime; }; #endif - diff --git a/wpilibc/wpilibC++/include/PWM.h b/wpilibc/wpilibC++/include/PWM.h index b7696a3b3e..4c72c416cc 100644 --- a/wpilibc/wpilibC++/include/PWM.h +++ b/wpilibc/wpilibC++/include/PWM.h @@ -13,12 +13,12 @@ class DigitalModule; /** * Class implements the PWM generation in the FPGA. - * + * * The values supplied as arguments for PWM outputs range from -1.0 to 1.0. They are mapped * to the hardware dependent values, in this case 0-255 for the FPGA. * Changes are immediately sent to the FPGA, and the update occurs at the next * FPGA cycle. There is no delay. - * + * * As of revision 0.1.10 of the FPGA, the FPGA interprets the 0-255 values as follows: * - 255 = full "forward" * - 254 to 129 = linear scaling from "full forward" to "center" @@ -39,7 +39,6 @@ public: }; explicit PWM(uint32_t channel); - PWM(uint8_t moduleNumber, uint32_t channel); virtual ~PWM(); virtual void SetRaw(unsigned short value); virtual unsigned short GetRaw(); @@ -52,7 +51,6 @@ public: { return m_channel; } - uint32_t GetModuleNumber(); protected: /** @@ -105,7 +103,7 @@ protected: ITable *m_table; private: - void InitPWM(uint8_t moduleNumber, uint32_t channel); + void InitPWM(uint32_t channel); uint32_t m_channel; DigitalModule *m_module; int32_t GetMaxPositivePwm() diff --git a/wpilibc/wpilibC++/include/Relay.h b/wpilibc/wpilibC++/include/Relay.h index f018a8fe9d..4a5ef4dba0 100644 --- a/wpilibc/wpilibC++/include/Relay.h +++ b/wpilibc/wpilibC++/include/Relay.h @@ -16,7 +16,7 @@ class DigitalModule; * Class for Spike style relay outputs. * Relays are intended to be connected to spikes or similar relays. The relay channels controls * a pair of pins that are either both off, one on, the other on, or both on. This translates into - * two spike outputs at 0v, one at 12v and one at 0v, one at 0v and the other at 12v, or two + * two spike outputs at 0v, one at 12v and one at 0v, one at 0v and the other at 12v, or two * spike outputs at 12V. This allows off, full forward, or full reverse control of motors without * variable speed. It also allows the two channels (forward and reverse) to be used independently * for something that does not care about voltage polatiry (like a solenoid). @@ -39,7 +39,6 @@ public: }; Relay(uint32_t channel, Direction direction = kBothDirections); - Relay(uint8_t moduleNumber, uint32_t channel, Direction direction = kBothDirections); virtual ~Relay(); void Set(Value value); @@ -56,7 +55,7 @@ public: ITable *m_table; private: - void InitRelay(uint8_t moduleNumber); + void InitRelay(); uint32_t m_channel; Direction m_direction; diff --git a/wpilibc/wpilibC++/include/SafePWM.h b/wpilibc/wpilibC++/include/SafePWM.h index cc303b14fe..bed5c214f5 100644 --- a/wpilibc/wpilibC++/include/SafePWM.h +++ b/wpilibc/wpilibC++/include/SafePWM.h @@ -21,7 +21,6 @@ class SafePWM : public PWM, public MotorSafety { public: explicit SafePWM(uint32_t channel); - SafePWM(uint8_t moduleNumber, uint32_t channel); ~SafePWM(); void SetExpiration(float timeout); diff --git a/wpilibc/wpilibC++/include/SensorBase.h b/wpilibc/wpilibC++/include/SensorBase.h index 29d1de7c9f..eaecc44b15 100644 --- a/wpilibc/wpilibC++/include/SensorBase.h +++ b/wpilibc/wpilibC++/include/SensorBase.h @@ -20,22 +20,12 @@ public: SensorBase(); virtual ~SensorBase(); static void DeleteSingletons(); - static uint32_t GetDefaultAnalogModule() + + static uint32_t GetDefaultSolenoidModule() { return 1; } - static uint32_t GetDefaultDigitalModule() - { - return 1; - } - static uint32_t GetDefaultSolenoidModule() - { - return 1; - } - static bool CheckAnalogModule(uint8_t moduleNumber); - static bool CheckDigitalModule(uint8_t moduleNumber); - static bool CheckPWMModule(uint8_t moduleNumber); - static bool CheckRelayModule(uint8_t moduleNumber); + static bool CheckSolenoidModule(uint8_t moduleNumber); static bool CheckDigitalChannel(uint32_t channel); static bool CheckRelayChannel(uint32_t channel); @@ -48,8 +38,6 @@ public: static const uint32_t kDigitalChannels = 20; static const uint32_t kAnalogInputs = 8; static const uint32_t kAnalogOutputs = 2; - static const uint32_t kAnalogModules = 2; - static const uint32_t kDigitalModules = 2; static const uint32_t kSolenoidChannels = 8; static const uint32_t kSolenoidModules = 2; static const uint32_t kPwmChannels = 20; diff --git a/wpilibc/wpilibC++/include/Servo.h b/wpilibc/wpilibC++/include/Servo.h index 0107e32e1b..01cba943da 100644 --- a/wpilibc/wpilibC++/include/Servo.h +++ b/wpilibc/wpilibC++/include/Servo.h @@ -10,7 +10,7 @@ /** * Standard hobby style servo. - * + * * The range parameters default to the appropriate values for the Hitec HS-322HD servo provided * in the FIRST Kit of Parts in 2008. */ @@ -18,7 +18,6 @@ class Servo : public SafePWM { public: explicit Servo(uint32_t channel); - Servo(uint8_t moduleNumber, uint32_t channel); virtual ~Servo(); void Set(float value); void SetOffline(); diff --git a/wpilibc/wpilibC++/include/SolenoidBase.h b/wpilibc/wpilibC++/include/SolenoidBase.h index 741ecae696..78bb67d37f 100644 --- a/wpilibc/wpilibC++/include/SolenoidBase.h +++ b/wpilibc/wpilibC++/include/SolenoidBase.h @@ -21,7 +21,7 @@ public: uint8_t GetAll(); protected: - explicit SolenoidBase(uint8_t moduleNumber); + explicit SolenoidBase(uint8_t pcmID); void Set(uint8_t value, uint8_t mask); virtual void InitSolenoid() = 0; diff --git a/wpilibc/wpilibC++/include/Talon.h b/wpilibc/wpilibC++/include/Talon.h index 3279d17a3a..d9fb0ef12d 100644 --- a/wpilibc/wpilibC++/include/Talon.h +++ b/wpilibc/wpilibC++/include/Talon.h @@ -16,7 +16,6 @@ class Talon : public SafePWM, public SpeedController { public: explicit Talon(uint32_t channel); - Talon(uint8_t moduleNumber, uint32_t channel); virtual ~Talon(); virtual void Set(float value, uint8_t syncGroup = 0); virtual float Get(); diff --git a/wpilibc/wpilibC++/include/Ultrasonic.h b/wpilibc/wpilibC++/include/Ultrasonic.h index de7d3785ec..c595b1e69d 100644 --- a/wpilibc/wpilibC++/include/Ultrasonic.h +++ b/wpilibc/wpilibC++/include/Ultrasonic.h @@ -36,8 +36,6 @@ public: Ultrasonic(DigitalOutput *pingChannel, DigitalInput *echoChannel, DistanceUnit units = kInches); Ultrasonic(DigitalOutput &pingChannel, DigitalInput &echoChannel, DistanceUnit units = kInches); Ultrasonic(uint32_t pingChannel, uint32_t echoChannel, DistanceUnit units = kInches); - Ultrasonic(uint8_t pingModuleNumber, uint32_t pingChannel, uint8_t echoModuleNumber, - uint32_t echoChannel, DistanceUnit units = kInches); virtual ~Ultrasonic(); void Ping(); @@ -53,7 +51,7 @@ public: { m_enabled = enable; } - + double PIDGet(); void SetDistanceUnits(DistanceUnit units); DistanceUnit GetDistanceUnits(); @@ -90,4 +88,3 @@ private: ITable *m_table; }; - diff --git a/wpilibc/wpilibC++/include/Victor.h b/wpilibc/wpilibC++/include/Victor.h index e1d8a2e190..fce4139f05 100644 --- a/wpilibc/wpilibC++/include/Victor.h +++ b/wpilibc/wpilibC++/include/Victor.h @@ -16,7 +16,6 @@ class Victor : public SafePWM, public SpeedController { public: explicit Victor(uint32_t channel); - Victor(uint8_t moduleNumber, uint32_t channel); virtual ~Victor(); virtual void Set(float value, uint8_t syncGroup = 0); virtual float Get(); diff --git a/wpilibc/wpilibC++/lib/ADXL345_I2C.cpp b/wpilibc/wpilibC++/lib/ADXL345_I2C.cpp index e9c3640cc2..7ed3371aaf 100644 --- a/wpilibc/wpilibC++/lib/ADXL345_I2C.cpp +++ b/wpilibc/wpilibC++/lib/ADXL345_I2C.cpp @@ -17,14 +17,13 @@ constexpr double ADXL345_I2C::kGsPerLSB; /** * Constructor. - * - * @param moduleNumber The digital module that the sensor is plugged into (1 or 2). + * * @param range The range (+ or -) that the accelerometer will measure. */ -ADXL345_I2C::ADXL345_I2C(uint8_t moduleNumber, ADXL345_I2C::DataFormat_Range range) +ADXL345_I2C::ADXL345_I2C(ADXL345_I2C::DataFormat_Range range) : m_i2c (NULL) { - DigitalModule *module = DigitalModule::GetInstance(moduleNumber); + DigitalModule *module = DigitalModule::GetInstance(1); if (module) { m_i2c = module->GetI2C(kAddress); @@ -34,7 +33,7 @@ ADXL345_I2C::ADXL345_I2C(uint8_t moduleNumber, ADXL345_I2C::DataFormat_Range ran // Specify the data format to read m_i2c->Write(kDataFormatRegister, kDataFormat_FullRes | (uint8_t)range); - HALReport(HALUsageReporting::kResourceType_ADXL345, HALUsageReporting::kADXL345_I2C, moduleNumber - 1); + HALReport(HALUsageReporting::kResourceType_ADXL345, HALUsageReporting::kADXL345_I2C, 0); } } @@ -49,7 +48,7 @@ ADXL345_I2C::~ADXL345_I2C() /** * Get the acceleration of one axis in Gs. - * + * * @param axis The axis to read from. * @return Acceleration of the ADXL345 in Gs. */ @@ -68,7 +67,7 @@ double ADXL345_I2C::GetAcceleration(ADXL345_I2C::Axes axis) /** * Get the acceleration of all axes in Gs. - * + * * @return Acceleration measured on all axes of the ADXL345 in Gs. */ ADXL345_I2C::AllAxes ADXL345_I2C::GetAccelerations() @@ -91,4 +90,3 @@ ADXL345_I2C::AllAxes ADXL345_I2C::GetAccelerations() } return data; } - diff --git a/wpilibc/wpilibC++/lib/ADXL345_SPI.cpp b/wpilibc/wpilibC++/lib/ADXL345_SPI.cpp index 92d6506dbe..5e0e9e8f0d 100644 --- a/wpilibc/wpilibC++/lib/ADXL345_SPI.cpp +++ b/wpilibc/wpilibC++/lib/ADXL345_SPI.cpp @@ -17,7 +17,7 @@ constexpr double ADXL345_SPI::kGsPerLSB; /** * Constructor. - * + * * @param clk The GPIO the clock signal is wired to. * @param mosi The GPIO the MOSI (Master Out Slave In) signal is wired to. * @param miso The GPIO the MISO (Master In Slave Out) signal is wired to. @@ -37,7 +37,7 @@ ADXL345_SPI::ADXL345_SPI(DigitalOutput &clk, DigitalOutput &mosi, DigitalInput & /** * Constructor. - * + * * @param clk The GPIO the clock signal is wired to. * @param mosi The GPIO the MOSI (Master Out Slave In) signal is wired to. * @param miso The GPIO the MISO (Master In Slave Out) signal is wired to. @@ -57,15 +57,14 @@ ADXL345_SPI::ADXL345_SPI(DigitalOutput *clk, DigitalOutput *mosi, DigitalInput * /** * Constructor. - * - * @param moduleNumber The digital module with the sensor attached. + * * @param clk The GPIO the clock signal is wired to. * @param mosi The GPIO the MOSI (Master Out Slave In) signal is wired to. * @param miso The GPIO the MISO (Master In Slave Out) signal is wired to. * @param cs The GPIO the CS (Chip Select) signal is wired to. * @param range The range (+ or -) that the accelerometer will measure. */ -ADXL345_SPI::ADXL345_SPI(uint8_t moduleNumber, uint32_t clk, uint32_t mosi, uint32_t miso, +ADXL345_SPI::ADXL345_SPI(uint32_t clk, uint32_t mosi, uint32_t miso, uint32_t cs, ADXL345_SPI::DataFormat_Range range) : m_clk (NULL) , m_mosi (NULL) @@ -73,10 +72,10 @@ ADXL345_SPI::ADXL345_SPI(uint8_t moduleNumber, uint32_t clk, uint32_t mosi, uint , m_cs (NULL) , m_spi (NULL) { - m_clk = new DigitalOutput(moduleNumber, clk); - m_mosi = new DigitalOutput(moduleNumber, mosi); - m_miso = new DigitalInput(moduleNumber, miso); - m_cs = new DigitalOutput(moduleNumber, cs); + m_clk = new DigitalOutput(clk); + m_mosi = new DigitalOutput(mosi); + m_miso = new DigitalInput(miso); + m_cs = new DigitalOutput(cs); Init(m_clk, m_mosi, m_miso, m_cs, range); } @@ -132,7 +131,7 @@ ADXL345_SPI::~ADXL345_SPI() /** * Get the acceleration of one axis in Gs. - * + * * @param axis The axis to read from. * @return Acceleration of the ADXL345 in Gs. */ @@ -152,7 +151,7 @@ double ADXL345_SPI::GetAcceleration(ADXL345_SPI::Axes axis) /** * Get the acceleration of all axes in Gs. - * + * * @return Acceleration measured on all axes of the ADXL345 in Gs. */ ADXL345_SPI::AllAxes ADXL345_SPI::GetAccelerations() @@ -210,4 +209,3 @@ ADXL345_SPI::AllAxes ADXL345_SPI::GetAccelerations() } return data; } - diff --git a/wpilibc/wpilibC++/lib/Accelerometer.cpp b/wpilibc/wpilibC++/lib/Accelerometer.cpp index 799ca43a33..de82744f7a 100644 --- a/wpilibc/wpilibC++/lib/Accelerometer.cpp +++ b/wpilibc/wpilibC++/lib/Accelerometer.cpp @@ -5,7 +5,6 @@ /*----------------------------------------------------------------------------*/ #include "Accelerometer.h" -#include "AnalogModule.h" //#include "NetworkCommunication/UsageReporting.h" #include "WPIErrors.h" #include "LiveWindow/LiveWindow.h" @@ -18,15 +17,14 @@ void Accelerometer::InitAccelerometer() m_table = NULL; m_voltsPerG = 1.0; m_zeroGVoltage = 2.5; - HALReport(HALUsageReporting::kResourceType_Accelerometer, m_AnalogInput->GetChannel(), m_AnalogInput->GetModuleNumber() - 1); - LiveWindow::GetInstance()->AddSensor("Accelerometer", m_AnalogInput->GetModuleNumber(), m_AnalogInput->GetChannel(), this); + HALReport(HALUsageReporting::kResourceType_Accelerometer, m_AnalogInput->GetChannel()); + LiveWindow::GetInstance()->AddSensor("Accelerometer", m_AnalogInput->GetChannel(), this); } /** * Create a new instance of an accelerometer. - * - * The accelerometer is assumed to be in the first analog module in the given analog channel. The - * constructor allocates desired analog channel. + * + * The constructor allocates desired analog input. */ Accelerometer::Accelerometer(uint32_t channel) { @@ -35,22 +33,6 @@ Accelerometer::Accelerometer(uint32_t channel) InitAccelerometer(); } -/** - * Create new instance of accelerometer. - * - * Make a new instance of the accelerometer given a module and channel. The constructor allocates - * the desired analog channel from the specified module - * - * @param moduleNumber The analog module (1 or 2). - * @param channel The analog channel (1..8) - */ -Accelerometer::Accelerometer(uint8_t moduleNumber, uint32_t channel) -{ - m_AnalogInput = new AnalogInput(moduleNumber, channel); - m_allocatedChannel = true; - InitAccelerometer(); -} - /** * Create a new instance of Accelerometer from an existing AnalogInput. * Make a new instance of accelerometer given an AnalogInput. This is particularly @@ -70,7 +52,7 @@ Accelerometer::Accelerometer(AnalogInput *channel) } m_allocatedChannel = false; } - + /** * Delete the analog components used for the accelerometer. */ @@ -84,9 +66,9 @@ Accelerometer::~Accelerometer() /** * Return the acceleration in Gs. - * + * * The acceleration is returned units of Gs. - * + * * @return The current acceleration of the sensor in Gs. */ float Accelerometer::GetAcceleration() @@ -96,10 +78,10 @@ float Accelerometer::GetAcceleration() /** * Set the accelerometer sensitivity. - * + * * This sets the sensitivity of the accelerometer used for calculating the acceleration. * The sensitivity varys by accelerometer model. There are constants defined for various models. - * + * * @param sensitivity The sensitivity of accelerometer in Volts per G. */ void Accelerometer::SetSensitivity(float sensitivity) @@ -109,9 +91,9 @@ void Accelerometer::SetSensitivity(float sensitivity) /** * Set the voltage that corresponds to 0 G. - * + * * The zero G voltage varys by accelerometer model. There are constants defined for various models. - * + * * @param zero The zero G voltage. */ void Accelerometer::SetZero(float zero) @@ -121,9 +103,9 @@ void Accelerometer::SetZero(float zero) /** * Get the Acceleration for the PID Source parent. - * + * * @return The current acceleration in Gs. - */ + */ double Accelerometer::PIDGet() { return GetAcceleration(); @@ -153,4 +135,3 @@ void Accelerometer::InitTable(ITable *subTable) { ITable * Accelerometer::GetTable() { return m_table; } - diff --git a/wpilibc/wpilibC++/lib/AnalogInput.cpp b/wpilibc/wpilibC++/lib/AnalogInput.cpp index 584847136e..968825f4a8 100644 --- a/wpilibc/wpilibC++/lib/AnalogInput.cpp +++ b/wpilibc/wpilibC++/lib/AnalogInput.cpp @@ -1,11 +1,10 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) FIRST 2008. All Rights Reserved. */ +/* Copyright (c) FIRST 2008. 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 $(WIND_BASE)/WPILib. */ /*----------------------------------------------------------------------------*/ #include "AnalogInput.h" -#include "AnalogModule.h" //#include "NetworkCommunication/UsageReporting.h" #include "Resource.h" #include "WPIErrors.h" @@ -20,61 +19,45 @@ const uint32_t AnalogInput::kAccumulatorChannels[] = {0, 1}; /** * Common initialization. */ -void AnalogInput::InitAnalogInput(uint8_t moduleNumber, uint32_t channel) +void AnalogInput::InitAnalogInput(uint32_t channel) { m_table = NULL; char buf[64]; - Resource::CreateResourceObject(&inputs, kAnalogModules * kAnalogInputs); - if (!checkAnalogModule(moduleNumber)) - { - snprintf(buf, 64, "Analog Module %d", moduleNumber); - wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf); - return; - } - if (!checkAnalogInputChannel(channel)) + Resource::CreateResourceObject(&inputs, kAnalogInputs); + + if (!checkAnalogInputChannel(channel)) { snprintf(buf, 64, "analog input %d", channel); wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf); return; } - snprintf(buf, 64, "Analog Input %d (Module: %d)", channel, moduleNumber); - if (inputs->Allocate((moduleNumber - 1) * kAnalogInputs + channel, buf) == ~0ul) + snprintf(buf, 64, "Analog Input %d", channel); + if (inputs->Allocate(channel, buf) == ~0ul) { CloneError(inputs); return; } - m_channel = channel; - m_module = moduleNumber; - void* port = getPortWithModule(moduleNumber, channel); + m_channel = channel; + + void* port = getPort(channel); int32_t status = 0; m_port = initializeAnalogInputPort(port, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); - LiveWindow::GetInstance()->AddSensor("AnalogInput",channel, GetModuleNumber(), this); - HALReport(HALUsageReporting::kResourceType_AnalogChannel, channel, GetModuleNumber() - 1); + LiveWindow::GetInstance()->AddSensor("AnalogInput",channel, this); + HALReport(HALUsageReporting::kResourceType_AnalogChannel, channel); } /** - * Construct an analog input on a specified module. - * - * @param moduleNumber The analog module (1 or 2). - * @param channel The channel number to represent. - */ -AnalogInput::AnalogInput(uint8_t moduleNumber, uint32_t channel) -{ - InitAnalogInput(moduleNumber, channel); -} - -/** - * Construct an analog input on the default module. + * Construct an analog input. * * @param channel The channel number to represent. */ AnalogInput::AnalogInput(uint32_t channel) { - InitAnalogInput(GetDefaultAnalogModule(), channel); + InitAnalogInput(channel); } /** @@ -82,24 +65,14 @@ AnalogInput::AnalogInput(uint32_t channel) */ AnalogInput::~AnalogInput() { - inputs->Free((m_module - 1) * kAnalogInputs + m_channel); + inputs->Free(m_channel); } /** - * Get the analog module that this channel is on. - * @return A pointer to the AnalogModule that this channel is on. - */ -AnalogModule *AnalogInput::GetModule() -{ - if (StatusIsFatal()) return NULL; - return AnalogModule::GetInstance(m_module); -} - -/** - * Get a sample straight from this channel on the module. + * Get a sample straight from this channel. * The sample is a 12-bit value representing the -10V to 10V range of the A/D converter in the module. * The units are in A/D converter codes. Use GetVoltage() to get the analog value in calibrated units. - * @return A sample straight from this channel on the module. + * @return A sample straight from this channel. */ int16_t AnalogInput::GetValue() { @@ -129,9 +102,9 @@ int32_t AnalogInput::GetAverageValue() } /** - * Get a scaled sample straight from this channel on the module. + * Get a scaled sample straight from this channel. * The value is scaled to units of Volts using the calibrated scaling data from GetLSBWeight() and GetOffset(). - * @return A scaled sample straight from this channel on the module. + * @return A scaled sample straight from this channel. */ float AnalogInput::GetVoltage() { @@ -160,8 +133,6 @@ float AnalogInput::GetAverageVoltage() /** * Get the factory scaling least significant bit weight constant. - * The least significant bit weight constant for the channel that was calibrated in - * manufacturing and stored in an eeprom in the module. * * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9) * @@ -178,8 +149,6 @@ uint32_t AnalogInput::GetLSBWeight() /** * Get the factory scaling offset constant. - * The offset constant for the channel that was calibrated in manufacturing and stored - * in an eeprom in the module. * * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9) * @@ -204,16 +173,6 @@ uint32_t AnalogInput::GetChannel() return m_channel; } -/** - * Get the module number. - * @return The module number. - */ -uint8_t AnalogInput::GetModuleNumber() -{ - if (StatusIsFatal()) return 0; - return m_module; -} - /** * Set the number of averaging bits. * This sets the number of averaging bits. The actual number of averaged samples is 2**bits. diff --git a/wpilibc/wpilibC++/lib/AnalogOutput.cpp b/wpilibc/wpilibC++/lib/AnalogOutput.cpp index b5ec5fd9cb..37887b124f 100644 --- a/wpilibc/wpilibC++/lib/AnalogOutput.cpp +++ b/wpilibc/wpilibC++/lib/AnalogOutput.cpp @@ -39,7 +39,7 @@ void AnalogOutput::InitAnalogOutput(uint32_t channel) { m_port = initializeAnalogOutputPort(port, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); - LiveWindow::GetInstance()->AddActuator("AnalogOutput", m_channel, 1, this); + LiveWindow::GetInstance()->AddActuator("AnalogOutput", m_channel, this); HALReport(HALUsageReporting::kResourceType_AnalogChannel, m_channel, 0); } diff --git a/wpilibc/wpilibC++/lib/AnalogPotentiometer.cpp b/wpilibc/wpilibC++/lib/AnalogPotentiometer.cpp index f762f608b4..1e682e5a35 100644 --- a/wpilibc/wpilibC++/lib/AnalogPotentiometer.cpp +++ b/wpilibc/wpilibC++/lib/AnalogPotentiometer.cpp @@ -1,35 +1,30 @@ #include "AnalogPotentiometer.h" -void AnalogPotentiometer::initPot(int slot, int channel, double scale, double offset) { - m_module = slot; +void AnalogPotentiometer::initPot(int channel, double scale, double offset) { m_channel = channel; m_scale = scale; m_offset = offset; - m_analog_channel = new AnalogInput(slot, channel); -} - -AnalogPotentiometer::AnalogPotentiometer(int slot, int channel, double scale, double offset) { - initPot(slot, channel, scale, offset); + m_analog_channel = new AnalogInput(channel); } AnalogPotentiometer::AnalogPotentiometer(int channel, double scale, double offset) { - initPot(1, channel, scale, offset); + initPot(channel, scale, offset); } AnalogPotentiometer::AnalogPotentiometer(int channel, double scale) { - initPot(1, channel, scale, 0); + initPot(channel, scale, 0); } AnalogPotentiometer::AnalogPotentiometer(int channel) { - initPot(1, channel, 1, 0); + initPot(channel, 1, 0); } double AnalogPotentiometer::Get() { return m_analog_channel->GetVoltage() * m_scale + m_offset; } - + double AnalogPotentiometer::PIDGet() { return Get(); } diff --git a/wpilibc/wpilibC++/lib/AnalogTrigger.cpp b/wpilibc/wpilibC++/lib/AnalogTrigger.cpp index d2c161f1e2..9d12c8238c 100644 --- a/wpilibc/wpilibC++/lib/AnalogTrigger.cpp +++ b/wpilibc/wpilibC++/lib/AnalogTrigger.cpp @@ -13,51 +13,38 @@ #include "WPIErrors.h" /** - * Initialize an analog trigger from a slot and channel. - * This is the common code for the two constructors that use a slot and channel. + * Initialize an analog trigger from a channel. */ -void AnalogTrigger::InitTrigger(uint8_t moduleNumber, uint32_t channel) +void AnalogTrigger::InitTrigger(uint32_t channel) { - void* port = getPortWithModule(moduleNumber, channel); + void* port = getPort(channel); int32_t status = 0; uint32_t index = 0; m_trigger = initializeAnalogTrigger(port, &index, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); m_index = index; - - HALReport(HALUsageReporting::kResourceType_AnalogTrigger, channel, moduleNumber - 1); + + HALReport(HALUsageReporting::kResourceType_AnalogTrigger, channel); } /** * Constructor for an analog trigger given a channel number. - * The default module is used in this case. * - * @param channel The analog channel (1..8). + * @param channel The analog channel (0..7). */ AnalogTrigger::AnalogTrigger(uint32_t channel) { - InitTrigger(GetDefaultAnalogModule(), channel); + InitTrigger(channel); } /** - * Constructor for an analog trigger given both the slot and channel. - * - * @param moduleNumber The analog module (1 or 2). - * @param channel The analog channel (1..8). + * Construct an analog trigger given an analog input. + * This should be used in the case of sharing an analog channel between the + * trigger and an analog input object. */ -AnalogTrigger::AnalogTrigger(uint8_t moduleNumber, uint32_t channel) +AnalogTrigger::AnalogTrigger(AnalogInput *input) { - InitTrigger(moduleNumber, channel); -} - -/** - * Construct an analog trigger given an analog channel. - * This should be used in the case of sharing an analog channel between the trigger - * and an analog input object. - */ -AnalogTrigger::AnalogTrigger(AnalogInput *channel) -{ - InitTrigger(channel->GetModuleNumber(), channel->GetChannel()); + InitTrigger(input->GetChannel()); } AnalogTrigger::~AnalogTrigger() @@ -171,4 +158,3 @@ AnalogTriggerOutput *AnalogTrigger::CreateOutput(AnalogTriggerType type) if (StatusIsFatal()) return NULL; return new AnalogTriggerOutput(this, type); } - diff --git a/wpilibc/wpilibC++/lib/CANJaguar.cpp b/wpilibc/wpilibC++/lib/CANJaguar.cpp index 4e71f80b7b..f9158aa0c1 100644 --- a/wpilibc/wpilibC++/lib/CANJaguar.cpp +++ b/wpilibc/wpilibC++/lib/CANJaguar.cpp @@ -82,12 +82,12 @@ void CANJaguar::InitCANJaguar() m_safetyHelper = new MotorSafetyHelper(this); HALReport(HALUsageReporting::kResourceType_CANJaguar, m_deviceNumber, m_controlMode); - LiveWindow::GetInstance()->AddActuator("CANJaguar", m_deviceNumber, 0, this); + LiveWindow::GetInstance()->AddActuator("CANJaguar", m_deviceNumber, this); } /** * Constructor - * + * * @param deviceNumber The the address of the Jaguar on the CAN bus. */ CANJaguar::CANJaguar(uint8_t deviceNumber, ControlMode controlMode) @@ -109,15 +109,15 @@ CANJaguar::~CANJaguar() } /** - * Set the output set-point value. - * + * Set the output set-point value. + * * The scale and the units depend on the mode the Jaguar is in. * In PercentVbus Mode, the outputValue is from -1.0 to 1.0 (same as PWM Jaguar). * In Voltage Mode, the outputValue is in Volts. * In Current Mode, the outputValue is in Amps. * In Speed Mode, the outputValue is in Rotations/Minute. * In Position Mode, the outputValue is in Rotations. - * + * * @param outputValue The set-point to sent to the motor controller. * @param syncGroup The update group to add this Set() to, pending UpdateSyncGroup(). If 0, update immediately. */ @@ -231,7 +231,7 @@ void CANJaguar::SetNoAck(float outputValue, uint8_t syncGroup) dataSize++; } { //setTransaction(messageID, dataBuffer, dataSize); - + //uint32_t ackMessageID = LM_API_ACK | m_deviceNumber; int32_t localStatus = 0; @@ -245,11 +245,11 @@ void CANJaguar::SetNoAck(float outputValue, uint8_t syncGroup) // Throw away any stale acks. //receiveMessage(&ackMessageID, NULL, 0, 0.0f); - + // Send the message with the data. localStatus = sendMessage(messageID | m_deviceNumber, dataBuffer, dataSize); wpi_setErrorWithContext(localStatus, "sendMessage"); - + // Wait for an ack. //localStatus = receiveMessage(&ackMessageID, NULL, 0); //wpi_setErrorWithContext(localStatus, "receiveMessage"); @@ -257,21 +257,21 @@ void CANJaguar::SetNoAck(float outputValue, uint8_t syncGroup) // Transaction complete. giveMutex(m_transactionSemaphore); } - - + + if (m_safetyHelper) m_safetyHelper->Feed(); } /** * Get the recently set outputValue setpoint. - * + * * The scale and the units depend on the mode the Jaguar is in. * In PercentVbus Mode, the outputValue is from -1.0 to 1.0 (same as PWM Jaguar). * In Voltage Mode, the outputValue is in Volts. * In Current Mode, the outputValue is in Amps. * In Speed Mode, the outputValue is in Rotations/Minute. * In Position Mode, the outputValue is in Rotations. - * + * * @return The most recently set outputValue setpoint. */ float CANJaguar::Get() @@ -322,7 +322,7 @@ float CANJaguar::Get() /** * Common interface for disabling a motor. - * + * * @deprecated Call DisableControl instead. */ void CANJaguar::Disable() @@ -332,9 +332,9 @@ void CANJaguar::Disable() /** * Write out the PID value as seen in the PIDOutput base object. - * + * * @deprecated Call Set instead. - * + * * @param output Write out the PercentVbus value as was computed by the PIDController */ void CANJaguar::PIDWrite(float output) @@ -417,10 +417,10 @@ int32_t CANJaguar::unpackint32_t(uint8_t *buffer) /** * Send a message on the CAN bus through the CAN driver in FRC_NetworkCommunication - * + * * Trusted messages require a 2-byte token at the beginning of the data payload. * If the message being sent is trusted, make space for the token. - * + * * @param messageID The messageID to be used on the CAN bus * @param data The up to 8 bytes of data to be sent with the message * @param dataSize Specify how much of the data in "data" to send @@ -464,7 +464,7 @@ int32_t CANJaguar::sendMessage(uint32_t messageID, const uint8_t *data, uint8_t /** * Receive a message from the CAN bus through the CAN driver in FRC_NetworkCommunication - * + * * @param messageID The messageID to read from the CAN bus * @param data The up to 8 bytes of data that was received with the message * @param dataSize Indicates how much data was received @@ -482,10 +482,10 @@ int32_t CANJaguar::receiveMessage(uint32_t *messageID, uint8_t *data, uint8_t *d /** * Execute a transaction with a Jaguar that sets some property. - * + * * Jaguar always acks when it receives a message. If we don't wait for an ack, * the message object in the Jaguar could get overwritten before it is handled. - * + * * @param messageID The messageID to be used on the CAN bus (device number is added internally) * @param data The up to 8 bytes of data to be sent with the message * @param dataSize Specify how much of the data in "data" to send @@ -518,9 +518,9 @@ void CANJaguar::setTransaction(uint32_t messageID, const uint8_t *data, uint8_t /** * Execute a transaction with a Jaguar that gets some property. - * + * * Jaguar always generates a message with the same message ID when replying. - * + * * @param messageID The messageID to read from the CAN bus (device number is added internally) * @param data The up to 8 bytes of data that was received with the message * @param dataSize Indicates how much data was received @@ -559,9 +559,9 @@ void CANJaguar::getTransaction(uint32_t messageID, uint8_t *data, uint8_t *dataS /** * Set the reference source device for speed controller mode. - * + * * Choose encoder as the source of speed feedback when in speed control mode. - * + * * @param reference Specify a SpeedReference. */ void CANJaguar::SetSpeedReference(SpeedReference reference) @@ -574,7 +574,7 @@ void CANJaguar::SetSpeedReference(SpeedReference reference) /** * Get the reference source device for speed controller mode. - * + * * @return A SpeedReference indicating the currently selected reference device for speed controller mode. */ CANJaguar::SpeedReference CANJaguar::GetSpeedReference() @@ -592,10 +592,10 @@ CANJaguar::SpeedReference CANJaguar::GetSpeedReference() /** * Set the reference source device for position controller mode. - * + * * Choose between using and encoder and using a potentiometer * as the source of position feedback when in position control mode. - * + * * @param reference Specify a PositionReference. */ void CANJaguar::SetPositionReference(PositionReference reference) @@ -608,7 +608,7 @@ void CANJaguar::SetPositionReference(PositionReference reference) /** * Get the reference source device for position controller mode. - * + * * @return A PositionReference indicating the currently selected reference device for position controller mode. */ CANJaguar::PositionReference CANJaguar::GetPositionReference() @@ -626,7 +626,7 @@ CANJaguar::PositionReference CANJaguar::GetPositionReference() /** * Set the P, I, and D constants for the closed loop modes. - * + * * @param p The proportional gain of the Jaguar's PID controller. * @param i The integral gain of the Jaguar's PID controller. * @param d The differential gain of the Jaguar's PID controller. @@ -671,7 +671,7 @@ void CANJaguar::SetPID(double p, double i, double d) /** * Get the Proportional gain of the controller. - * + * * @return The proportional gain. */ double CANJaguar::GetP() @@ -712,7 +712,7 @@ double CANJaguar::GetP() /** * Get the Intregral gain of the controller. - * + * * @return The integral gain. */ double CANJaguar::GetI() @@ -753,7 +753,7 @@ double CANJaguar::GetI() /** * Get the Differential gain of the controller. - * + * * @return The differential gain. */ double CANJaguar::GetD() @@ -794,12 +794,12 @@ double CANJaguar::GetD() /** * Enable the closed loop controller. - * + * * Start actually controlling the output based on the feedback. * If starting a position controller with an encoder reference, * use the encoderInitialPosition parameter to initialize the * encoder state. - * + * * @param encoderInitialPosition Encoder position to set if position with encoder reference. Ignored otherwise. */ void CANJaguar::EnableControl(double encoderInitialPosition) @@ -830,7 +830,7 @@ void CANJaguar::EnableControl(double encoderInitialPosition) /** * Disable the closed loop controller. - * + * * Stop driving the output based on the feedback. */ void CANJaguar::DisableControl() @@ -860,10 +860,10 @@ void CANJaguar::DisableControl() /** * Change the control mode of this Jaguar object. - * + * * After changing modes, configure any PID constants or other settings needed * and then EnableControl() to actually change the mode on the Jaguar. - * + * * @param controlMode The new mode. */ void CANJaguar::ChangeControlMode(ControlMode controlMode) @@ -879,9 +879,9 @@ void CANJaguar::ChangeControlMode(ControlMode controlMode) /** * Get the active control mode from the Jaguar. - * + * * Ask the Jag what mode it is in. - * + * * @return ControlMode that the Jag is in. */ CANJaguar::ControlMode CANJaguar::GetControlMode() @@ -899,7 +899,7 @@ CANJaguar::ControlMode CANJaguar::GetControlMode() /** * Get the voltage at the battery input terminals of the Jaguar. - * + * * @return The bus voltage in Volts. */ float CANJaguar::GetBusVoltage() @@ -917,7 +917,7 @@ float CANJaguar::GetBusVoltage() /** * Get the voltage being output from the motor terminals of the Jaguar. - * + * * @return The output voltage in Volts. */ float CANJaguar::GetOutputVoltage() @@ -936,7 +936,7 @@ float CANJaguar::GetOutputVoltage() /** * Get the current through the motor terminals of the Jaguar. - * + * * @return The output current in Amps. */ float CANJaguar::GetOutputCurrent() @@ -954,7 +954,7 @@ float CANJaguar::GetOutputCurrent() /** * Get the internal temperature of the Jaguar. - * + * * @return The temperature of the Jaguar in degrees Celsius. */ float CANJaguar::GetTemperature() @@ -972,7 +972,7 @@ float CANJaguar::GetTemperature() /** * Get the position of the encoder or potentiometer. - * + * * @return The position of the motor in rotations based on the configured feedback. */ double CANJaguar::GetPosition() @@ -990,7 +990,7 @@ double CANJaguar::GetPosition() /** * Get the speed of the encoder. - * + * * @return The speed of the motor in RPM based on the configured feedback. */ double CANJaguar::GetSpeed() @@ -1008,7 +1008,7 @@ double CANJaguar::GetSpeed() /** * Get the status of the forward limit switch. - * + * * @return The motor is allowed to turn in the forward direction when true. */ bool CANJaguar::GetForwardLimitOK() @@ -1026,7 +1026,7 @@ bool CANJaguar::GetForwardLimitOK() /** * Get the status of the reverse limit switch. - * + * * @return The motor is allowed to turn in the reverse direction when true. */ bool CANJaguar::GetReverseLimitOK() @@ -1044,7 +1044,7 @@ bool CANJaguar::GetReverseLimitOK() /** * Get the status of any faults the Jaguar has detected. - * + * * @return A bit-mask of faults defined by the "Faults" enum. */ uint16_t CANJaguar::GetFaults() @@ -1062,10 +1062,10 @@ uint16_t CANJaguar::GetFaults() /** * Check if the Jaguar's power has been cycled since this was last called. - * + * * This should return true the first time called after a Jaguar power up, * and false after that. - * + * * @return The Jaguar was power cycled since the last call to this function. */ bool CANJaguar::GetPowerCycled() @@ -1092,10 +1092,10 @@ bool CANJaguar::GetPowerCycled() /** * Set the maximum voltage change rate. - * + * * When in PercentVbus or Voltage output mode, the rate at which the voltage changes can * be limited to reduce current spikes. Set this to 0.0 to disable rate limiting. - * + * * @param rampRate The maximum rate of voltage change in Percent Voltage mode in V/s. */ void CANJaguar::SetVoltageRampRate(double rampRate) @@ -1120,7 +1120,7 @@ void CANJaguar::SetVoltageRampRate(double rampRate) /** * Get the version of the firmware running on the Jaguar. - * + * * @return The firmware version. 0 if the device did not respond. */ uint32_t CANJaguar::GetFirmwareVersion() @@ -1139,7 +1139,7 @@ uint32_t CANJaguar::GetFirmwareVersion() /** * Get the version of the Jaguar hardware. - * + * * @return The hardware version. 1: Jaguar, 2: Black Jaguar */ uint8_t CANJaguar::GetHardwareVersion() @@ -1161,9 +1161,9 @@ uint8_t CANJaguar::GetHardwareVersion() /** * Configure what the controller does to the H-Bridge when neutral (not driving the output). - * + * * This allows you to override the jumper configuration for brake or coast. - * + * * @param mode Select to use the jumper setting or to override it to coast or brake. */ void CANJaguar::ConfigNeutralMode(NeutralMode mode) @@ -1176,7 +1176,7 @@ void CANJaguar::ConfigNeutralMode(NeutralMode mode) /** * Configure how many codes per revolution are generated by your encoder. - * + * * @param codesPerRev The number of counts per revolution in 1X mode. */ void CANJaguar::ConfigEncoderCodesPerRev(uint16_t codesPerRev) @@ -1190,10 +1190,10 @@ void CANJaguar::ConfigEncoderCodesPerRev(uint16_t codesPerRev) /** * Configure the number of turns on the potentiometer. - * + * * There is no special support for continuous turn potentiometers. * Only integer numbers of turns are supported. - * + * * @param turns The number of turns of the potentiometer */ void CANJaguar::ConfigPotentiometerTurns(uint16_t turns) @@ -1207,11 +1207,11 @@ void CANJaguar::ConfigPotentiometerTurns(uint16_t turns) /** * Configure Soft Position Limits when in Position Controller mode. - * + * * When controlling position, you can add additional limits on top of the limit switch inputs * that are based on the position feedback. If the position limit is reached or the * switch is opened, that direction will be disabled. - * + * * @param forwardLimitPosition The position that if exceeded will disable the forward direction. * @param reverseLimitPosition The position that if exceeded will disable the reverse direction. @@ -1235,7 +1235,7 @@ void CANJaguar::ConfigSoftPositionLimits(double forwardLimitPosition, double rev /** * Disable Soft Position Limits if previously enabled. - * + * * Soft Position Limits are disabled by default. */ void CANJaguar::DisableSoftPositionLimits() @@ -1248,10 +1248,10 @@ void CANJaguar::DisableSoftPositionLimits() /** * Configure the maximum voltage that the Jaguar will ever output. - * + * * This can be used to limit the maximum output voltage in all modes so that * motors which cannot withstand full bus voltage can be used safely. - * + * * @param voltage The maximum voltage output by the Jaguar. */ void CANJaguar::ConfigMaxOutputVoltage(double voltage) @@ -1266,10 +1266,10 @@ void CANJaguar::ConfigMaxOutputVoltage(double voltage) /** * Configure how long the Jaguar waits in the case of a fault before resuming operation. - * + * * Faults include over temerature, over current, and bus under voltage. * The default is 3.0 seconds, but can be reduced to as low as 0.5 seconds. - * + * * @param faultTime The time to wait before resuming operation, in seconds. */ void CANJaguar::ConfigFaultTime(float faultTime) @@ -1284,7 +1284,7 @@ void CANJaguar::ConfigFaultTime(float faultTime) /** * Update all the motors that have pending sets in the syncGroup. - * + * * @param syncGroup A bitmask of groups to generate synchronous output. */ void CANJaguar::UpdateSyncGroup(uint8_t syncGroup) @@ -1329,7 +1329,7 @@ void CANJaguar::GetDescription(char *desc) /** * Common interface for stopping the motor * Part of the MotorSafety interface - * + * * @deprecated Call DisableControl instead. */ void CANJaguar::StopMotor() @@ -1371,5 +1371,3 @@ void CANJaguar::InitTable(ITable *subTable) { ITable * CANJaguar::GetTable() { return m_table; } - - diff --git a/wpilibc/wpilibC++/lib/Compressor.cpp b/wpilibc/wpilibC++/lib/Compressor.cpp index 4bb9ccc2a6..2717120eb7 100644 --- a/wpilibc/wpilibC++/lib/Compressor.cpp +++ b/wpilibc/wpilibC++/lib/Compressor.cpp @@ -5,9 +5,9 @@ #include "Compressor.h" #include "WPIErrors.h" -void Compressor::InitCompressor(uint8_t module) { +void Compressor::InitCompressor(uint8_t pcmID) { m_table = 0; - m_pcm_pointer = initializeCompressor(module); + m_pcm_pointer = initializeCompressor(pcmID); SetClosedLoopControl(true); } @@ -26,8 +26,8 @@ Compressor::Compressor() { * * @param module The module number to use (1 or 2) */ -Compressor::Compressor(uint8_t module) { - InitCompressor(module); +Compressor::Compressor(uint8_t pcmID) { + InitCompressor(pcmID); } Compressor::~Compressor() { @@ -160,4 +160,3 @@ void Compressor::ValueChanged(ITable* source, const std::string& key, EntryValue else Stop(); } - diff --git a/wpilibc/wpilibC++/lib/Counter.cpp b/wpilibc/wpilibC++/lib/Counter.cpp index c49dfd6395..3be1b8f258 100644 --- a/wpilibc/wpilibC++/lib/Counter.cpp +++ b/wpilibc/wpilibC++/lib/Counter.cpp @@ -18,12 +18,12 @@ void Counter::InitCounter(Mode mode) { m_table = NULL; - + int32_t status = 0; uint32_t index = 0; m_counter = initializeCounter(mode, &index, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); - + m_upSource = NULL; m_downSource = NULL; m_allocatedUpSource = false; @@ -72,7 +72,7 @@ Counter::Counter(DigitalSource &source) : /** * Create an instance of a Counter object. - * Create an up-Counter instance given a channel. The default digital module is assumed. + * Create an up-Counter instance given a channel. */ Counter::Counter(uint32_t channel) : m_upSource(NULL), @@ -84,22 +84,6 @@ Counter::Counter(uint32_t channel) : ClearDownSource(); } -/** - * Create an instance of a Counter object. - * Create an instance of an up-Counter given a digital module and a channel. - * @param moduleNumber The digital module (1 or 2). - * @param channel The channel in the digital module - */ -Counter::Counter(uint8_t moduleNumber, uint32_t channel) : - m_upSource(NULL), - m_downSource(NULL), - m_counter(NULL) -{ - InitCounter(); - SetUpSource(moduleNumber, channel); - ClearDownSource(); -} - /** * Create an instance of a Counter object. * Create an instance of a simple up-Counter given an analog trigger. @@ -173,35 +157,21 @@ Counter::~Counter() delete m_downSource; m_downSource = NULL; } - + int32_t status = 0; freeCounter(m_counter, &status); wpi_setErrorWithContext(status, getHALErrorMessage(status)); m_counter = NULL; } -/** - * Set the up source for the counter as digital input channel and slot. - * - * @param moduleNumber The digital module (1 or 2). - * @param channel The digital channel (1..14). - */ -void Counter::SetUpSource(uint8_t moduleNumber, uint32_t channel) -{ - if (StatusIsFatal()) return; - SetUpSource(new DigitalInput(moduleNumber, channel)); - m_allocatedUpSource = true; -} - /** * Set the upsource for the counter as a digital input channel. - * The slot will be the default digital module slot. */ void Counter::SetUpSource(uint32_t channel) { - if (StatusIsFatal()) return; - SetUpSource(GetDefaultDigitalModule(), channel); - m_allocatedUpSource = true; + if (StatusIsFatal()) return; + SetUpSource(new DigitalInput(channel)); + m_allocatedUpSource = true; } /** @@ -297,7 +267,6 @@ void Counter::ClearUpSource() /** * Set the down counting source to be a digital input channel. - * The slot will be set to the default digital module slot. */ void Counter::SetDownSource(uint32_t channel) { @@ -306,19 +275,6 @@ void Counter::SetDownSource(uint32_t channel) m_allocatedDownSource = true; } -/** - * Set the down counting source to be a digital input slot and channel. - * - * @param moduleNumber The digital module (1 or 2). - * @param channel The digital channel (1..14). - */ -void Counter::SetDownSource(uint8_t moduleNumber, uint32_t channel) -{ - if (StatusIsFatal()) return; - SetDownSource(new DigitalInput(moduleNumber, channel)); - m_allocatedDownSource = true; -} - /** * Set the down counting source to be an analog trigger. * @param analogTrigger The analog trigger object that is used for the Down Source @@ -437,7 +393,7 @@ void Counter::SetExternalDirectionMode() /** * Set Semi-period mode on this counter. - * Counts up on both rising and falling edges. + * Counts up on both rising and falling edges. */ void Counter::SetSemiPeriodMode(bool highSemiPeriod) { @@ -460,10 +416,10 @@ void Counter::SetPulseLengthMode(float threshold) wpi_setErrorWithContext(status, getHALErrorMessage(status)); } - + /** - * Get the Samples to Average which specifies the number of samples of the timer to - * average when calculating the period. Perform averaging to account for + * Get the Samples to Average which specifies the number of samples of the timer to + * average when calculating the period. Perform averaging to account for * mechanical imperfections or as oversampling to increase resolution. * @return SamplesToAverage The number of samples being averaged (from 1 to 127) */ @@ -476,8 +432,8 @@ int Counter::GetSamplesToAverage() } /** - * Set the Samples to Average which specifies the number of samples of the timer to - * average when calculating the period. Perform averaging to account for + * Set the Samples to Average which specifies the number of samples of the timer to + * average when calculating the period. Perform averaging to account for * mechanical imperfections or as oversampling to increase resolution. * @param samplesToAverage The number of samples to average from 1 to 127. */ @@ -645,11 +601,11 @@ void Counter::UpdateTable() { } void Counter::StartLiveWindowMode() { - + } void Counter::StopLiveWindowMode() { - + } std::string Counter::GetSmartDashboardType() { @@ -664,4 +620,3 @@ void Counter::InitTable(ITable *subTable) { ITable * Counter::GetTable() { return m_table; } - diff --git a/wpilibc/wpilibC++/lib/DigitalInput.cpp b/wpilibc/wpilibC++/lib/DigitalInput.cpp index bede57e9e7..4ea8e203ec 100644 --- a/wpilibc/wpilibC++/lib/DigitalInput.cpp +++ b/wpilibc/wpilibC++/lib/DigitalInput.cpp @@ -15,20 +15,15 @@ Resource *interruptsResource = NULL; /** * Create an instance of a DigitalInput. - * Creates a digital input given a slot and channel. Common creation routine - * for all constructors. + * Creates a digital input given a channel. Common creation routine for all + * constructors. */ -void DigitalInput::InitDigitalInput(uint8_t moduleNumber, uint32_t channel) +void DigitalInput::InitDigitalInput(uint32_t channel) { m_table = NULL; char buf[64]; Resource::CreateResourceObject(&interruptsResource, interrupt_kNumSystems); - if (!CheckDigitalModule(moduleNumber)) - { - snprintf(buf, 64, "Digital Module %d", moduleNumber); - wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf); - return; - } + if (!CheckDigitalChannel(channel)) { snprintf(buf, 64, "Digital Channel %d", channel); @@ -36,33 +31,21 @@ void DigitalInput::InitDigitalInput(uint8_t moduleNumber, uint32_t channel) return; } m_channel = channel; - m_module = DigitalModule::GetInstance(moduleNumber); + m_module = DigitalModule::GetInstance(1); m_module->AllocateDIO(channel, true); - HALReport(HALUsageReporting::kResourceType_DigitalInput, channel, moduleNumber - 1); + HALReport(HALUsageReporting::kResourceType_DigitalInput, channel); } /** * Create an instance of a Digital Input class. - * Creates a digital input given a channel and uses the default module. + * Creates a digital input given a channel. * - * @param channel The digital channel (1..14). + * @param channel The digital channel (0..19). */ DigitalInput::DigitalInput(uint32_t channel) { - InitDigitalInput(GetDefaultDigitalModule(), channel); -} - -/** - * Create an instance of a Digital Input class. - * Creates a digital input given an channel and module. - * - * @param moduleNumber The digital module (1 or 2). - * @param channel The digital channel (1..14). - */ -DigitalInput::DigitalInput(uint8_t moduleNumber, uint32_t channel) -{ - InitDigitalInput(moduleNumber, channel); + InitDigitalInput(channel); } /** @@ -204,11 +187,11 @@ void DigitalInput::UpdateTable() { } void DigitalInput::StartLiveWindowMode() { - + } void DigitalInput::StopLiveWindowMode() { - + } std::string DigitalInput::GetSmartDashboardType() { diff --git a/wpilibc/wpilibC++/lib/DigitalOutput.cpp b/wpilibc/wpilibC++/lib/DigitalOutput.cpp index 0570df493d..fcb3711664 100644 --- a/wpilibc/wpilibC++/lib/DigitalOutput.cpp +++ b/wpilibc/wpilibC++/lib/DigitalOutput.cpp @@ -1,5 +1,5 @@ /*----------------------------------------------------------------------------*/ -/* Copyright (c) FIRST 2008. All Rights Reserved. */ +/* Copyright (c) FIRST 2008. 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 $(WIND_BASE)/WPILib. */ /*----------------------------------------------------------------------------*/ @@ -14,19 +14,14 @@ extern Resource *interruptsResource; /** * Create an instance of a DigitalOutput. - * Creates a digital output given a slot and channel. Common creation routine - * for all constructors. + * Creates a digital output given a channel. Common creation routine for all + * constructors. */ -void DigitalOutput::InitDigitalOutput(uint8_t moduleNumber, uint32_t channel) +void DigitalOutput::InitDigitalOutput(uint32_t channel) { m_table = NULL; char buf[64]; - if (!CheckDigitalModule(moduleNumber)) - { - snprintf(buf, 64, "Digital Module %d", moduleNumber); - wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf); - return; - } + if (!CheckDigitalChannel(channel)) { snprintf(buf, 64, "Digital Channel %d", channel); @@ -35,33 +30,21 @@ void DigitalOutput::InitDigitalOutput(uint8_t moduleNumber, uint32_t channel) } m_channel = channel; m_pwmGenerator = ~0ul; - m_module = DigitalModule::GetInstance(moduleNumber); + m_module = DigitalModule::GetInstance(1); m_module->AllocateDIO(m_channel, false); - HALReport(HALUsageReporting::kResourceType_DigitalOutput, channel, moduleNumber - 1); + HALReport(HALUsageReporting::kResourceType_DigitalOutput, channel); } /** * Create an instance of a digital output. - * Create a digital output given a channel. The default module is used. + * Create a digital output given a channel. * - * @param channel The digital channel (1..14). + * @param channel The digital channel (0..19) */ DigitalOutput::DigitalOutput(uint32_t channel) { - InitDigitalOutput(GetDefaultDigitalModule(), channel); -} - -/** - * Create an instance of a digital output. - * Create an instance of a digital output given a module number and channel. - * - * @param moduleNumber The digital module (1 or 2). - * @param channel The digital channel (1..14). - */ -DigitalOutput::DigitalOutput(uint8_t moduleNumber, uint32_t channel) -{ - InitDigitalOutput(moduleNumber, channel); + InitDigitalOutput(channel); } /** @@ -117,11 +100,11 @@ bool DigitalOutput::IsPulsing() /** * Change the PWM frequency of the PWM output on a Digital Output line. - * + * * The valid range is from 0.6 Hz to 19 kHz. The frequency resolution is logarithmic. - * + * * There is only one PWM frequency per digital module. - * + * * @param rate The frequency to output all digital output PWM signals on this module. */ void DigitalOutput::SetPWMRate(float rate) @@ -132,14 +115,14 @@ void DigitalOutput::SetPWMRate(float rate) /** * Enable a PWM Output on this line. - * + * * Allocate one of the 4 DO PWM generator resources from this module. - * + * * Supply the initial duty-cycle to output so as to avoid a glitch when first starting. - * + * * The resolution of the duty cycle is 8-bit for low frequencies (1kHz or less) * but is reduced the higher the frequency of the PWM signal is. - * + * * @param initialDutyCycle The duty-cycle to start generating. [0..1] */ void DigitalOutput::EnablePWM(float initialDutyCycle) @@ -153,7 +136,7 @@ void DigitalOutput::EnablePWM(float initialDutyCycle) /** * Change this line from a PWM output back to a static Digital Output line. - * + * * Free up one of the 4 DO PWM generator resources that were in use. */ void DigitalOutput::DisablePWM() @@ -167,10 +150,10 @@ void DigitalOutput::DisablePWM() /** * Change the duty-cycle that is being generated on the line. - * + * * The resolution of the duty cycle is 8-bit for low frequencies (1kHz or less) * but is reduced the higher the frequency of the PWM signal is. - * + * * @param dutyCycle The duty-cycle to change to. [0..1] */ void DigitalOutput::UpdateDutyCycle(float dutyCycle) @@ -192,8 +175,8 @@ uint32_t DigitalOutput::GetChannelForRouting() */ uint32_t DigitalOutput::GetModuleForRouting() { - if (StatusIsFatal()) return 0; - return m_module->GetNumber() - 1; + if (StatusIsFatal()) return 0; + return m_module->GetNumber() - 1; } /** @@ -227,7 +210,7 @@ void DigitalOutput::RequestInterrupts(InterruptHandlerFunction handler, void *pa AllocateInterrupts(false); int32_t status = 0; - requestInterrupts(m_interrupt, GetModuleForRouting(), GetChannelForRouting(), + requestInterrupts(m_interrupt, 1, GetChannelForRouting(), GetAnalogTriggerForRouting(), &status); SetUpSourceEdge(true, false); attachInterruptHandler(m_interrupt, handler, param, &status); @@ -307,5 +290,3 @@ void DigitalOutput::InitTable(ITable *subTable) { ITable * DigitalOutput::GetTable() { return m_table; } - - diff --git a/wpilibc/wpilibC++/lib/DoubleSolenoid.cpp b/wpilibc/wpilibC++/lib/DoubleSolenoid.cpp index 607104bdd3..d97601b6c0 100644 --- a/wpilibc/wpilibC++/lib/DoubleSolenoid.cpp +++ b/wpilibc/wpilibC++/lib/DoubleSolenoid.cpp @@ -54,12 +54,12 @@ void DoubleSolenoid::InitSolenoid() HALReport(HALUsageReporting::kResourceType_Solenoid, m_forwardChannel, m_moduleNumber - 1); HALReport(HALUsageReporting::kResourceType_Solenoid, m_reverseChannel, m_moduleNumber - 1); - LiveWindow::GetInstance()->AddActuator("DoubleSolenoid", m_moduleNumber, m_forwardChannel, this); + LiveWindow::GetInstance()->AddActuator("DoubleSolenoid", m_forwardChannel, this); } /** * Constructor. - * + * * @param forwardChannel The forward channel on the module to control. * @param reverseChannel The reverse channel on the module to control. */ @@ -73,7 +73,7 @@ DoubleSolenoid::DoubleSolenoid(uint32_t forwardChannel, uint32_t reverseChannel) /** * Constructor. - * + * * @param moduleNumber The solenoid module (1 or 2). * @param forwardChannel The forward channel on the module to control. * @param reverseChannel The reverse channel on the module to control. @@ -100,7 +100,7 @@ DoubleSolenoid::~DoubleSolenoid() /** * Set the value of a solenoid. - * + * * @param value Move the solenoid to forward, reverse, or don't move it. */ void DoubleSolenoid::Set(Value value) @@ -126,7 +126,7 @@ void DoubleSolenoid::Set(Value value) /** * Read the current value of the solenoid. - * + * * @return The current value of the solenoid. */ DoubleSolenoid::Value DoubleSolenoid::Get() @@ -181,4 +181,3 @@ void DoubleSolenoid::InitTable(ITable *subTable) { ITable * DoubleSolenoid::GetTable() { return m_table; } - diff --git a/wpilibc/wpilibC++/lib/DriverStation.cpp b/wpilibc/wpilibC++/lib/DriverStation.cpp index 80f151b87d..546f7ecfdf 100644 --- a/wpilibc/wpilibC++/lib/DriverStation.cpp +++ b/wpilibc/wpilibC++/lib/DriverStation.cpp @@ -23,7 +23,6 @@ TLogLevel dsLogLevel = logDEBUG; if (level > dsLogLevel) ; \ else Log().Get(level) -const uint32_t DriverStation::kBatteryModuleNumber; const uint32_t DriverStation::kBatteryChannel; const uint32_t DriverStation::kJoystickPorts; const uint32_t DriverStation::kJoystickAxes; @@ -33,7 +32,7 @@ uint8_t DriverStation::m_updateNumber = 0; /** * DriverStation contructor. - * + * * This is only called once the first time GetInstance() is called */ DriverStation::DriverStation() @@ -61,7 +60,7 @@ DriverStation::DriverStation() m_newControlData = initializeSemaphore(SEMAPHORE_EMPTY); // Register that semaphore with the network communications task. - // It will signal when new packet data is available. + // It will signal when new packet data is available. HALSetNewDataSem(m_packetDataAvailableSem); m_waitForDataSem = initializeMultiWait(); @@ -93,7 +92,7 @@ DriverStation::DriverStation() m_controlData->analog4 = 0; m_controlData->dsDigitalIn = 0; - m_batteryChannel = new AnalogInput(kBatteryModuleNumber, kBatteryChannel); + m_batteryChannel = new AnalogInput(kBatteryChannel); AddToSingletonList(); @@ -170,7 +169,7 @@ void DriverStation::GetData() HALGetCommonControlData(m_controlData, HAL_WAIT_FOREVER); - if (!lastEnabled && IsEnabled()) + if (!lastEnabled && IsEnabled()) { // If starting teleop, assume that autonomous just took up 15 seconds if (IsAutonomous()) @@ -202,17 +201,17 @@ void DriverStation::SetData() m_dashboardInUseLow->GetStatusBuffer(&userStatusDataLow, &userStatusDataLowSize); HALSetStatusData(GetBatteryVoltage(), m_digitalOut, m_updateNumber, userStatusDataHigh, userStatusDataHighSize, userStatusDataLow, userStatusDataLowSize, HAL_WAIT_FOREVER); - + m_dashboardInUseHigh->Flush(); m_dashboardInUseLow->Flush(); } /** * Read the battery voltage from the specified AnalogInput. - * + * * This accessor assumes that the battery voltage is being measured * through the voltage divider on an analog breakout. - * + * * @return The battery voltage. */ float DriverStation::GetBatteryVoltage() @@ -229,7 +228,7 @@ float DriverStation::GetBatteryVoltage() /** * Get the value of the axis on a joystick. * This depends on the mapping of the joystick connected to the specified port. - * + * * @param stick The joystick to read. * @param axis The analog axis value to read from the joystick. * @return The value of the axis on the joystick. @@ -261,7 +260,7 @@ float DriverStation::GetStickAxis(uint32_t stick, uint32_t axis) wpi_setWPIError(BadJoystickIndex); return 0.0; } - + float result; if (value < 0) result = ((float) value) / 128.0; @@ -278,7 +277,7 @@ float DriverStation::GetStickAxis(uint32_t stick, uint32_t axis) /** * The state of the buttons on the joystick. * 12 buttons (4 msb are unused) from the joystick. - * + * * @param stick The joystick to read. * @return The state of the buttons on the joystick. */ @@ -309,7 +308,7 @@ short DriverStation::GetStickButtons(uint32_t stick) * The analog values are returned as voltage values for the Driver Station analog inputs. * These inputs are typically used for advanced operator interfaces consisting of potentiometers * or resistor networks representing values on a rotary switch. - * + * * @param channel The analog input channel on the driver station to read from. Valid range is 1 - 4. * @return The analog voltage on the input. */ @@ -362,14 +361,14 @@ bool DriverStation::GetDigitalIn(uint32_t channel) /** * Set a value for the digital outputs on the Driver Station. - * + * * Control digital outputs on the Drivers Station. These values are typically used for * giving feedback on a custom operator station such as LEDs. - * + * * @param channel The digital output to set. Valid range is 1 - 8. * @param value The state to set the digital output. */ -void DriverStation::SetDigitalOut(uint32_t channel, bool value) +void DriverStation::SetDigitalOut(uint32_t channel, bool value) { if (channel < 1 || channel > 8) wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 8"); @@ -390,7 +389,7 @@ void DriverStation::SetDigitalOut(uint32_t channel, bool value) * @param channel The digital ouput to monitor. Valid range is 1 through 8. * @return A digital value being output on the Drivers Station. */ -bool DriverStation::GetDigitalOut(uint32_t channel) +bool DriverStation::GetDigitalOut(uint32_t channel) { if (channel < 1 || channel > 8) wpi_setWPIErrorWithContext(ParameterOutOfRange, "channel must be between 1 and 8"); diff --git a/wpilibc/wpilibC++/lib/Encoder.cpp b/wpilibc/wpilibC++/lib/Encoder.cpp index 86a47c8326..27c6651aaa 100644 --- a/wpilibc/wpilibC++/lib/Encoder.cpp +++ b/wpilibc/wpilibC++/lib/Encoder.cpp @@ -63,40 +63,12 @@ void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) m_pidSource = kDistance; HALReport(HALUsageReporting::kResourceType_Encoder, index, encodingType); - LiveWindow::GetInstance()->AddSensor("Encoder", m_aSource->GetModuleForRouting(), m_aSource->GetChannelForRouting(), this); + LiveWindow::GetInstance()->AddSensor("Encoder", m_aSource->GetChannelForRouting(), this); } /** * Encoder constructor. - * Construct a Encoder given a and b modules and channels fully specified. - * @param aModuleNumber The a channel digital input module. - * @param aChannel The a channel digital input channel. - * @param bModuleNumber The b channel digital input module. - * @param bChannel The b channel digital input channel. - * @param reverseDirection represents the orientation of the encoder and inverts the output values - * if necessary so forward represents positive values. - * @param encodingType either k1X, k2X, or k4X to indicate 1X, 2X or 4X decoding. If 4X is - * selected, then an encoder FPGA object is used and the returned counts will be 4x the encoder - * spec'd value since all rising and falling edges are counted. If 1X or 2X are selected then - * a counter object will be used and the returned value will either exactly match the spec'd count - * or be double (2x) the spec'd count. - */ -Encoder::Encoder(uint8_t aModuleNumber, uint32_t aChannel, - uint8_t bModuleNumber, uint32_t bChannel, - bool reverseDirection, EncodingType encodingType) : - m_encoder(NULL), - m_counter(NULL) -{ - m_aSource = new DigitalInput(aModuleNumber, aChannel); - m_bSource = new DigitalInput(bModuleNumber, bChannel); - InitEncoder(reverseDirection, encodingType); - m_allocatedASource = true; - m_allocatedBSource = true; -} - -/** - * Encoder constructor. - * Construct a Encoder given a and b channels assuming the default module. + * Construct a Encoder given a and b channels. * @param aChannel The a channel digital input channel. * @param bChannel The b channel digital input channel. * @param reverseDirection represents the orientation of the encoder and inverts the output values @@ -251,7 +223,7 @@ int32_t Encoder::GetRaw() * Gets the current count. * Returns the current count on the Encoder. * This method compensates for the decoding type. - * + * * @return Current count from the Encoder adjusted for the 1x, 2x, or 4x scale factor. */ int32_t Encoder::Get() @@ -281,7 +253,7 @@ void Encoder::Reset() * Returns the period of the most recent pulse. * Returns the period of the most recent Encoder pulse in seconds. * This method compenstates for the decoding type. - * + * * @deprecated Use GetRate() in favor of this method. This returns unscaled periods and GetRate() scales using value from SetDistancePerPulse(). * * @return Period in seconds of the most recent pulse. @@ -309,9 +281,9 @@ double Encoder::GetPeriod() * that the attached device is stopped. This timeout allows users to determine if the wheels or * other shaft has stopped rotating. * This method compensates for the decoding type. - * + * * @deprecated Use SetMinRate() in favor of this method. This takes unscaled periods and SetMinRate() scales using value from SetDistancePerPulse(). - * + * * @param maxPeriod The maximum time between rising and falling edges before the FPGA will * report the device stopped. This is expressed in seconds. */ @@ -389,12 +361,12 @@ double Encoder::DecodingScaleFactor() return 0.25; default: return 0.0; - } + } } /** * Get the distance the robot has driven since the last reset. - * + * * @return The distance driven since the last reset as scaled by the value from SetDistancePerPulse(). */ double Encoder::GetDistance() @@ -406,7 +378,7 @@ double Encoder::GetDistance() /** * Get the current rate of the encoder. * Units are distance per second as scaled by the value from SetDistancePerPulse(). - * + * * @return The current rate of the encoder. */ double Encoder::GetRate() @@ -417,7 +389,7 @@ double Encoder::GetRate() /** * Set the minimum rate of the device before the hardware reports it stopped. - * + * * @param minRate The minimum rate. The units are in distance per second as scaled by the value from SetDistancePerPulse(). */ void Encoder::SetMinRate(double minRate) @@ -434,7 +406,7 @@ void Encoder::SetMinRate(double minRate) * Set this value based on the encoder's rated Pulses per Revolution and * factor in gearing reductions following the encoder shaft. * This distance can be in any units you like, linear or angular. - * + * * @param distancePerPulse The scale factor that will be used to convert pulses to useful units. */ void Encoder::SetDistancePerPulse(double distancePerPulse) @@ -464,10 +436,10 @@ void Encoder::SetReverseDirection(bool reverseDirection) } } - + /** - * Set the Samples to Average which specifies the number of samples of the timer to - * average when calculating the period. Perform averaging to account for + * Set the Samples to Average which specifies the number of samples of the timer to + * average when calculating the period. Perform averaging to account for * mechanical imperfections or as oversampling to increase resolution. * @param samplesToAverage The number of samples to average from 1 to 127. */ @@ -489,10 +461,10 @@ void Encoder::SetSamplesToAverage(int samplesToAverage) break; } } - + /** - * Get the Samples to Average which specifies the number of samples of the timer to - * average when calculating the period. Perform averaging to account for + * Get the Samples to Average which specifies the number of samples of the timer to + * average when calculating the period. Perform averaging to account for * mechanical imperfections or as oversampling to increase resolution. * @return SamplesToAverage The number of samples being averaged (from 1 to 127) */ @@ -517,7 +489,7 @@ int Encoder::GetSamplesToAverage() /** * Set which parameter of the encoder you are using as a process control variable. - * + * * @param pidSource An enum to select the parameter. */ void Encoder::SetPIDSourceParameter(PIDSourceParameter pidSource) @@ -528,7 +500,7 @@ void Encoder::SetPIDSourceParameter(PIDSourceParameter pidSource) /** * Implement the PIDSource interface. - * + * * @return The current value of the selected source parameter. */ double Encoder::PIDGet() @@ -554,11 +526,11 @@ void Encoder::UpdateTable() { } void Encoder::StartLiveWindowMode() { - + } void Encoder::StopLiveWindowMode() { - + } std::string Encoder::GetSmartDashboardType() { @@ -576,4 +548,3 @@ void Encoder::InitTable(ITable *subTable) { ITable * Encoder::GetTable() { return m_table; } - diff --git a/wpilibc/wpilibC++/lib/GearTooth.cpp b/wpilibc/wpilibC++/lib/GearTooth.cpp index 118b9f6bfa..024525042f 100644 --- a/wpilibc/wpilibC++/lib/GearTooth.cpp +++ b/wpilibc/wpilibC++/lib/GearTooth.cpp @@ -22,36 +22,21 @@ void GearTooth::EnableDirectionSensing(bool directionSensitive) /** * Construct a GearTooth sensor given a channel. - * - * The default module is assumed. - * - * @param channel The GPIO channel on the digital module that the sensor is connected to. + * + * @param channel The GPIO channel that the sensor is connected to. * @param directionSensitive Enable the pulse length decoding in hardware to specify count direction. */ GearTooth::GearTooth(uint32_t channel, bool directionSensitive) : Counter(channel) { EnableDirectionSensing(directionSensitive); -} - -/** - * Construct a GearTooth sensor given a channel and module. - * - * @param moduleNumber The digital module (1 or 2). - * @param channel The GPIO channel on the digital module that the sensor is connected to. - * @param directionSensitive Enable the pulse length decoding in hardware to specify count direction. - */ -GearTooth::GearTooth(uint8_t moduleNumber, uint32_t channel, bool directionSensitive) - : Counter(moduleNumber, channel) -{ - EnableDirectionSensing(directionSensitive); - LiveWindow::GetInstance()->AddSensor("GearTooth", moduleNumber, channel, this); + LiveWindow::GetInstance()->AddSensor("GearTooth", channel, this); } /** * Construct a GearTooth sensor given a digital input. * This should be used when sharing digial inputs. - * + * * @param source An object that fully descibes the input that the sensor is connected to. * @param directionSensitive Enable the pulse length decoding in hardware to specify count direction. */ @@ -77,4 +62,3 @@ GearTooth::~GearTooth() std::string GearTooth::GetSmartDashboardType() { return "GearTooth"; } - diff --git a/wpilibc/wpilibC++/lib/Gyro.cpp b/wpilibc/wpilibC++/lib/Gyro.cpp index d4a1428767..a17513457c 100644 --- a/wpilibc/wpilibC++/lib/Gyro.cpp +++ b/wpilibc/wpilibC++/lib/Gyro.cpp @@ -32,7 +32,7 @@ void Gyro::InitGyro() if (!m_analog->IsAccumulatorChannel()) { wpi_setWPIErrorWithContext(ParameterOutOfRange, - "moduleNumber and/or channel (must be accumulator channel)"); + " channel (must be accumulator channel)"); if (m_channelAllocated) { delete m_analog; @@ -44,7 +44,7 @@ void Gyro::InitGyro() m_voltsPerDegreePerSecond = kDefaultVoltsPerDegreePerSecond; m_analog->SetAverageBits(kAverageBits); m_analog->SetOversampleBits(kOversampleBits); - float sampleRate = kSamplesPerSecond * + float sampleRate = kSamplesPerSecond * (1 << (kAverageBits + kOversampleBits)); m_analog->GetModule()->SetSampleRate(sampleRate); Wait(1.0); @@ -63,31 +63,16 @@ void Gyro::InitGyro() m_analog->SetAccumulatorCenter(m_center); m_analog->SetAccumulatorDeadband(0); ///< TODO: compute / parameterize this m_analog->ResetAccumulator(); - + SetPIDSourceParameter(kAngle); - HALReport(HALUsageReporting::kResourceType_Gyro, m_analog->GetChannel(), m_analog->GetModuleNumber() - 1); - LiveWindow::GetInstance()->AddSensor("Gyro", m_analog->GetModuleNumber(), m_analog->GetChannel(), this); + HALReport(HALUsageReporting::kResourceType_Gyro, m_analog->GetChannel()); + LiveWindow::GetInstance()->AddSensor("Gyro", m_analog->GetChannel(), this); } /** - * Gyro constructor given a slot and a channel. - * - * @param moduleNumber The analog module the gyro is connected to (1). - * @param channel The analog channel the gyro is connected to (1 or 2). - */ -Gyro::Gyro(uint8_t moduleNumber, uint32_t channel) -{ - m_analog = new AnalogInput(moduleNumber, channel); - m_channelAllocated = true; - InitGyro(); -} - -/** - * Gyro constructor with only a channel. - * - * Use the default analog module slot. - * + * Gyro constructor with only a channel.. + * * @param channel The analog channel the gyro is connected to. */ Gyro::Gyro(uint32_t channel) @@ -145,12 +130,12 @@ Gyro::~Gyro() /** * Return the actual angle in degrees that the robot is currently facing. - * + * * The angle is based on the current accumulator value corrected by the oversampling rate, the * gyro type and the A/D calibration values. * The angle is continuous, that is can go beyond 360 degrees. This make algorithms that wouldn't * want to see a discontinuity in the gyro output as it sweeps past 0 on the second time around. - * + * * @return the current heading of the robot in degrees. This heading is based on integration * of the returned rate from the gyro. */ @@ -171,14 +156,14 @@ float Gyro::GetAngle( void ) /** * Return the rate of rotation of the gyro - * + * * The rate is based on the most recent reading of the gyro analog value - * + * * @return the current rate in degrees per second */ double Gyro::GetRate( void ) { - return (m_analog->GetAverageValue() - ((double)m_center + m_offset)) * 1e-9 * m_analog->GetLSBWeight() + return (m_analog->GetAverageValue() - ((double)m_center + m_offset)) * 1e-9 * m_analog->GetLSBWeight() / ((1 << m_analog->GetOversampleBits()) * m_voltsPerDegreePerSecond); } @@ -187,7 +172,7 @@ double Gyro::GetRate( void ) * Set the gyro type based on the sensitivity. * This takes the number of volts/degree/second sensitivity of the gyro and uses it in subsequent * calculations to allow the code to work with multiple gyros. - * + * * @param voltsPerDegreePerSecond The type of gyro specified as the voltage that represents one degree/second. */ void Gyro::SetSensitivity( float voltsPerDegreePerSecond ) @@ -204,7 +189,7 @@ void Gyro::SetPIDSourceParameter(PIDSourceParameter pidSource) /** * Get the angle in degrees for the PIDSource base object. - * + * * @return The angle in degrees. */ double Gyro::PIDGet() @@ -226,11 +211,11 @@ void Gyro::UpdateTable() { } void Gyro::StartLiveWindowMode() { - + } void Gyro::StopLiveWindowMode() { - + } std::string Gyro::GetSmartDashboardType() { @@ -245,4 +230,3 @@ void Gyro::InitTable(ITable *subTable) { ITable * Gyro::GetTable() { return m_table; } - diff --git a/wpilibc/wpilibC++/lib/HiTechnicColorSensor.cpp b/wpilibc/wpilibC++/lib/HiTechnicColorSensor.cpp index bd19fd3040..c51ca2f007 100644 --- a/wpilibc/wpilibC++/lib/HiTechnicColorSensor.cpp +++ b/wpilibc/wpilibC++/lib/HiTechnicColorSensor.cpp @@ -27,20 +27,18 @@ const uint8_t HiTechnicColorSensor::kRawBlueRegister; /** * Constructor. - * - * @param moduleNumber The digital module that the sensor is plugged into (1 or 2). */ -HiTechnicColorSensor::HiTechnicColorSensor(uint8_t moduleNumber) +HiTechnicColorSensor::HiTechnicColorSensor() : m_i2c (NULL) { m_table = NULL; - DigitalModule *module = DigitalModule::GetInstance(moduleNumber); + DigitalModule *module = DigitalModule::GetInstance(1); m_mode = kActive; - + if (module) { m_i2c = module->GetI2C(kAddress); - + // Verify Sensor const uint8_t kExpectedManufacturer[] = "HiTechnc"; const uint8_t kExpectedSensorType[] = "ColorPD "; @@ -53,8 +51,8 @@ HiTechnicColorSensor::HiTechnicColorSensor(uint8_t moduleNumber) { wpi_setWPIError(CompassTypeError); } - - HALReport(HALUsageReporting::kResourceType_HiTechnicColorSensor, moduleNumber - 1); + + HALReport(HALUsageReporting::kResourceType_HiTechnicColorSensor, 0); } } @@ -79,7 +77,7 @@ HiTechnicColorSensor::~HiTechnicColorSensor() uint8_t HiTechnicColorSensor::GetColor() { uint8_t color = 0; - + if(m_mode != kActive) { SetMode(kActive); @@ -95,7 +93,7 @@ uint8_t HiTechnicColorSensor::GetColor() * Get the Red value. * * Gets the (0-255) red value from the sensor. - * + * * The sensor must be in active mode to access the regular RGB data * if the sensor is not in active mode, it will be placed into active * mode by this method. @@ -105,7 +103,7 @@ uint8_t HiTechnicColorSensor::GetColor() uint8_t HiTechnicColorSensor::GetRed() { uint8_t red = 0; - + if(m_mode != kActive) { SetMode(kActive); @@ -121,17 +119,17 @@ uint8_t HiTechnicColorSensor::GetRed() * Get the Green value. * * Gets the(0-255) green value from the sensor. - * + * * The sensor must be in active mode to access the regular RGB data * if the sensor is not in active mode, it will be placed into active * mode by this method. - * + * * @return The Green sensor value. */ uint8_t HiTechnicColorSensor::GetGreen() { uint8_t green = 0; - + if(m_mode != kActive) { SetMode(kActive); @@ -147,17 +145,17 @@ uint8_t HiTechnicColorSensor::GetGreen() * Get the Blue value. * * Gets the raw (0-255) blue value from the sensor. - * + * * The sensor must be in active mode to access the regular RGB data * if the sensor is not in active mode, it will be placed into active * mode by this method. - * + * * @return The Blue sensor value. */ uint8_t HiTechnicColorSensor::GetBlue() { uint8_t blue = 0; - + if(m_mode != kActive) { SetMode(kActive); @@ -174,18 +172,18 @@ uint8_t HiTechnicColorSensor::GetBlue() * Using this method ensures that all three values come from the * same sensor reading, using the individual color methods provides * no such guarantee. - * + * * The sensor must be in active mode to access the regular RGB data. * If the sensor is not in active mode, it will be placed into active * mode by this method. - * + * * @return RGB object with the three color values */ HiTechnicColorSensor::RGB HiTechnicColorSensor::GetRGB() { uint8_t colors[3] = {0,0,0}; RGB result; - + if(m_mode != kActive) { SetMode(kActive); @@ -194,11 +192,11 @@ HiTechnicColorSensor::RGB HiTechnicColorSensor::GetRGB() { m_i2c->Read(kRawRedRegister, sizeof(colors), (uint8_t*)&colors); } - + result.red = colors[0]; result.green = colors[1]; result.blue = colors[2]; - + return result; } @@ -206,7 +204,7 @@ HiTechnicColorSensor::RGB HiTechnicColorSensor::GetRGB() * Get the Raw Red value. * * Gets the (0-65536) raw red value from the sensor. - * + * * The sensor must be in raw or passive mode to access the regular RGB data * if the sensor is not in raw or passive mode, it will be placed into raw * mode by this method. @@ -216,7 +214,7 @@ HiTechnicColorSensor::RGB HiTechnicColorSensor::GetRGB() uint16_t HiTechnicColorSensor::GetRawRed() { uint16_t rawRed = 0; - + if(m_mode == kActive) { SetMode(kRaw); @@ -232,7 +230,7 @@ uint16_t HiTechnicColorSensor::GetRawRed() * Get the Raw Green value. * * Gets the (0-65536) raw green value from the sensor. - * + * * The sensor must be in raw or passive mode to access the regular RGB data * if the sensor is not in raw or passive mode, it will be placed into raw * mode by this method. @@ -242,7 +240,7 @@ uint16_t HiTechnicColorSensor::GetRawRed() uint16_t HiTechnicColorSensor::GetRawGreen() { uint16_t rawGreen = 0; - + if(m_mode == kActive) { SetMode(kRaw); @@ -258,7 +256,7 @@ uint16_t HiTechnicColorSensor::GetRawGreen() * Get the Raw Blue value. * * Gets the (0-65536) raw blue value from the sensor. - * + * * The sensor must be in raw or passive mode to access the regular RGB data * if the sensor is not in raw or passive mode, it will be placed into raw * mode by this method. @@ -268,7 +266,7 @@ uint16_t HiTechnicColorSensor::GetRawGreen() uint16_t HiTechnicColorSensor::GetRawBlue() { uint16_t rawBlue = 0; - + if(m_mode == kActive) { SetMode(kRaw); @@ -287,7 +285,7 @@ uint16_t HiTechnicColorSensor::GetRawBlue() * no such guarantee. * * Gets the (0-65536) raw color values from the sensor. - * + * * The sensor must be in raw or passive mode to access the regular RGB data * if the sensor is not in raw or passive mode, it will be placed into raw * mode by this method. @@ -298,7 +296,7 @@ HiTechnicColorSensor::RGB HiTechnicColorSensor::GetRawRGB() { uint8_t colors[6] = {0,0,0,0,0,0}; RGB result; - + if(m_mode != kActive) { SetMode(kActive); @@ -307,11 +305,11 @@ HiTechnicColorSensor::RGB HiTechnicColorSensor::GetRawRGB() { m_i2c->Read(kRedRegister, sizeof(colors), (uint8_t*)&colors); } - + result.red = (colors[0]<<8) + colors[1]; result.green = (colors[2]<<8) + colors[3]; result.blue = (colors[4]<<8) + colors[5]; - + return result; } @@ -376,7 +374,7 @@ ITable* HiTechnicColorSensor::GetTable() */ void HiTechnicColorSensor::StartLiveWindowMode() { - + } /** @@ -384,5 +382,5 @@ void HiTechnicColorSensor::StartLiveWindowMode() */ void HiTechnicColorSensor::StopLiveWindowMode() { - + } diff --git a/wpilibc/wpilibC++/lib/HiTechnicCompass.cpp b/wpilibc/wpilibC++/lib/HiTechnicCompass.cpp index ca6dc1a246..4c9e165b79 100644 --- a/wpilibc/wpilibC++/lib/HiTechnicCompass.cpp +++ b/wpilibc/wpilibC++/lib/HiTechnicCompass.cpp @@ -20,18 +20,16 @@ const uint8_t HiTechnicCompass::kHeadingRegister; /** * Constructor. - * - * @param moduleNumber The digital module that the sensor is plugged into (1 or 2). */ -HiTechnicCompass::HiTechnicCompass(uint8_t moduleNumber) +HiTechnicCompass::HiTechnicCompass() : m_i2c (NULL) { m_table = NULL; - DigitalModule *module = DigitalModule::GetInstance(moduleNumber); + DigitalModule *module = DigitalModule::GetInstance(1); if (module) { m_i2c = module->GetI2C(kAddress); - + // Verify Sensor const uint8_t kExpectedManufacturer[] = "HiTechnc"; const uint8_t kExpectedSensorType[] = "Compass "; @@ -45,8 +43,8 @@ HiTechnicCompass::HiTechnicCompass(uint8_t moduleNumber) wpi_setWPIError(CompassTypeError); } - HALReport(HALUsageReporting::kResourceType_HiTechnicCompass, moduleNumber - 1); - LiveWindow::GetInstance()->AddSensor("HiTechnicCompass", moduleNumber, 0, this); + HALReport(HALUsageReporting::kResourceType_HiTechnicCompass, 0); + LiveWindow::GetInstance()->AddSensor("HiTechnicCompass", 1, this); } } @@ -61,9 +59,9 @@ HiTechnicCompass::~HiTechnicCompass() /** * Get the compass angle in degrees. - * + * * The resolution of this reading is 1 degree. - * + * * @return Angle of the compass in degrees. */ float HiTechnicCompass::GetAngle() @@ -86,11 +84,11 @@ void HiTechnicCompass::UpdateTable() { } void HiTechnicCompass::StartLiveWindowMode() { - + } void HiTechnicCompass::StopLiveWindowMode() { - + } std::string HiTechnicCompass::GetSmartDashboardType() { @@ -105,4 +103,3 @@ void HiTechnicCompass::InitTable(ITable *subTable) { ITable * HiTechnicCompass::GetTable() { return m_table; } - diff --git a/wpilibc/wpilibC++/lib/Jaguar.cpp b/wpilibc/wpilibC++/lib/Jaguar.cpp index 79daa0ac4a..ced5d23a01 100644 --- a/wpilibc/wpilibC++/lib/Jaguar.cpp +++ b/wpilibc/wpilibC++/lib/Jaguar.cpp @@ -7,7 +7,6 @@ #include "Jaguar.h" //#include "NetworkCommunication/UsageReporting.h" -#include "DigitalModule.h" #include "LiveWindow/LiveWindow.h" /** @@ -17,7 +16,7 @@ void Jaguar::InitJaguar() { /* * Input profile defined by Luminary Micro. - * + * * Full reverse ranges from 0.671325ms to 0.6972211ms * Proportional reverse ranges from 0.6972211ms to 1.4482078ms * Neutral ranges from 1.4482078ms to 1.5517922ms @@ -28,41 +27,28 @@ void Jaguar::InitJaguar() SetPeriodMultiplier(kPeriodMultiplier_1X); SetRaw(m_centerPwm); - HALReport(HALUsageReporting::kResourceType_Jaguar, GetChannel(), GetModuleNumber() - 1); - LiveWindow::GetInstance()->AddActuator("Jaguar", GetModuleNumber(), GetChannel(), this); + HALReport(HALUsageReporting::kResourceType_Jaguar, GetChannel()); + LiveWindow::GetInstance()->AddActuator("Jaguar", GetChannel(), this); } /** - * Constructor that assumes the default digital module. - * - * @param channel The PWM channel on the digital module that the Jaguar is attached to. + * @param channel The PWM channel that the Jaguar is attached to. */ Jaguar::Jaguar(uint32_t channel) : SafePWM(channel) { InitJaguar(); } -/** - * Constructor that specifies the digital module. - * - * @param moduleNumber The digital module (1 or 2). - * @param channel The PWM channel on the digital module that the Jaguar is attached to. - */ -Jaguar::Jaguar(uint8_t moduleNumber, uint32_t channel) : SafePWM(moduleNumber, channel) -{ - InitJaguar(); -} - Jaguar::~Jaguar() { } /** - * Set the PWM value. - * + * Set the PWM value. + * * The PWM value is set using a range of -1.0 to 1.0, appropriately * scaling the value for the FPGA. - * + * * @param speed The speed value between -1.0 and 1.0 to set. * @param syncGroup Unused interface. */ @@ -73,7 +59,7 @@ void Jaguar::Set(float speed, uint8_t syncGroup) /** * Get the recently set value of the PWM. - * + * * @return The most recently set value for the PWM between -1.0 and 1.0. */ float Jaguar::Get() @@ -91,11 +77,10 @@ void Jaguar::Disable() /** * Write out the PID value as seen in the PIDOutput base object. - * + * * @param output Write out the PWM value as was found in the PIDController */ void Jaguar::PIDWrite(float output) { Set(output); } - diff --git a/wpilibc/wpilibC++/lib/LiveWindow/LiveWindow.cpp b/wpilibc/wpilibC++/lib/LiveWindow/LiveWindow.cpp index 409892d463..6d28f0d79a 100644 --- a/wpilibc/wpilibC++/lib/LiveWindow/LiveWindow.cpp +++ b/wpilibc/wpilibC++/lib/LiveWindow/LiveWindow.cpp @@ -102,10 +102,10 @@ void LiveWindow::AddActuator(const char *subsystem, const char *name, /** * INTERNAL */ -void LiveWindow::AddSensor(std::string type, int module, int channel, LiveWindowSendable *component) +void LiveWindow::AddSensor(std::string type, int channel, LiveWindowSendable *component) { std::ostringstream oss; - oss << type << "[" << module << "," << channel << "]"; + oss << type << "[" << channel << "]"; std::string types(oss.str()); char* cc = new char[types.size() + 1]; types.copy(cc, types.size()); @@ -118,10 +118,10 @@ void LiveWindow::AddSensor(std::string type, int module, int channel, LiveWindow /** * INTERNAL */ -void LiveWindow::AddActuator(std::string type, int module, int channel, LiveWindowSendable *component) +void LiveWindow::AddActuator(std::string type, int channel, LiveWindowSendable *component) { std::ostringstream oss; - oss << type << "[" << module << "," << channel << "]"; + oss << type << "[" << channel << "]"; std::string types(oss.str()); char* cc = new char[types.size() + 1]; types.copy(cc, types.size()); @@ -129,6 +129,20 @@ void LiveWindow::AddActuator(std::string type, int module, int channel, LiveWind AddActuator("Ungrouped", cc, component); } +/** + * INTERNAL + */ +void LiveWindow::AddActuator(std::string type, int module, int channel, LiveWindowSendable *component) +{ + std::ostringstream oss; + oss << type << "[" << module << "," << channel << "]"; + std::string types(oss.str()); + char* cc = new char[types.size() + 1]; + types.copy(cc, types.size()); + cc[types.size()]='\0'; + AddActuator("Ungrouped", cc, component); +} + /** * Tell all the sensors to update (send) their values * Actuators are handled through callbacks on their value changing from the @@ -184,4 +198,3 @@ void LiveWindow::InitializeLiveWindowComponents() } } } - diff --git a/wpilibc/wpilibC++/lib/PWM.cpp b/wpilibc/wpilibC++/lib/PWM.cpp index 9729857d5f..7efd8de061 100644 --- a/wpilibc/wpilibC++/lib/PWM.cpp +++ b/wpilibc/wpilibC++/lib/PWM.cpp @@ -19,23 +19,18 @@ const int32_t PWM::kPwmDisabled; static Resource *allocated = NULL; /** - * Initialize PWMs given an module and channel. - * + * Initialize PWMs given a channel. + * * This method is private and is the common path for all the constructors for creating PWM - * instances. Checks module and channel value ranges and allocates the appropriate channel. + * instances. Checks channel value range and allocates the appropriate channel. * The allocation is only done to help users ensure that they don't double assign channels. */ -void PWM::InitPWM(uint8_t moduleNumber, uint32_t channel) +void PWM::InitPWM(uint32_t channel) { m_table = NULL; char buf[64]; - Resource::CreateResourceObject(&allocated, dio_kNumSystems * kPwmChannels); - if (!CheckPWMModule(moduleNumber)) - { - snprintf(buf, 64, "Digital Module %d", moduleNumber); - wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf); - return; - } + Resource::CreateResourceObject(&allocated, kPwmChannels); + if (!CheckPWMChannel(channel)) { snprintf(buf, 64, "PWM Channel %d", channel); @@ -43,50 +38,34 @@ void PWM::InitPWM(uint8_t moduleNumber, uint32_t channel) return; } - snprintf(buf, 64, "PWM %d (Module: %d)", channel, moduleNumber); - if (allocated->Allocate((moduleNumber - 1) * kPwmChannels + channel, buf) == ~0ul) + snprintf(buf, 64, "PWM %d", channel); + if (allocated->Allocate(channel, buf) == ~0ul) { CloneError(allocated); return; } m_channel = channel; - m_module = DigitalModule::GetInstance(moduleNumber); + m_module = DigitalModule::GetInstance(1); m_module->SetPWM(m_channel, kPwmDisabled); m_eliminateDeadband = false; - HALReport(HALUsageReporting::kResourceType_PWM, channel, moduleNumber - 1); + HALReport(HALUsageReporting::kResourceType_PWM, channel); } /** - * Allocate a PWM given a module and channel. - * Allocate a PWM using a module and channel number. - * - * @param moduleNumber The digital module (1 or 2). - * @param channel The PWM channel on the digital module (1..10). - */ -PWM::PWM(uint8_t moduleNumber, uint32_t channel) - : m_module(NULL) -{ - InitPWM(moduleNumber, channel); -} - -/** - * Allocate a PWM in the default module given a channel. - * - * Using a default module allocate a PWM given the channel number. The default module is the first - * slot numerically in the cRIO chassis. - * - * @param channel The PWM channel on the digital module. + * Allocate a PWM given a channel number. + * + * @param channel The PWM channel. */ PWM::PWM(uint32_t channel) : m_module(NULL) { - InitPWM(GetDefaultDigitalModule(), channel); + InitPWM(channel); } /** * Free the PWM channel. - * + * * Free the resource associated with the PWM channel and set the value to 0. */ PWM::~PWM() @@ -94,7 +73,7 @@ PWM::~PWM() if (m_module) { m_module->SetPWM(m_channel, kPwmDisabled); - allocated->Free((m_module->GetNumber() - 1) * kPwmChannels + m_channel); + allocated->Free(m_channel); } } @@ -155,19 +134,14 @@ void PWM::SetBounds(double max, double deadbandMax, double center, double deadba // printf("Calculated m_minPwm: %d min: %lf loopTime: %lf defaultStepsDown: %d\n", m_minPwm, min, loopTime, kDefaultPwmStepsDown); } -uint32_t PWM::GetModuleNumber() -{ - return m_module->GetNumber(); -} - /** * Set the PWM value based on a position. - * + * * This is intended to be used by servos. - * + * * @pre SetMaxPositivePwm() called. * @pre SetMinNegativePwm() called. - * + * * @param pos The position to set the servo between 0.0 and 1.0. */ void PWM::SetPosition(float pos) @@ -195,12 +169,12 @@ void PWM::SetPosition(float pos) /** * Get the PWM value in terms of a position. - * + * * This is intended to be used by servos. - * + * * @pre SetMaxPositivePwm() called. * @pre SetMinNegativePwm() called. - * + * * @return The position the servo is set to between 0.0 and 1.0. */ float PWM::GetPosition() @@ -223,15 +197,15 @@ float PWM::GetPosition() /** * Set the PWM value based on a speed. - * + * * This is intended to be used by speed controllers. - * + * * @pre SetMaxPositivePwm() called. * @pre SetMinPositivePwm() called. * @pre SetCenterPwm() called. * @pre SetMaxNegativePwm() called. * @pre SetMinNegativePwm() called. - * + * * @param speed The speed to set the speed controller between -1.0 and 1.0. */ void PWM::SetSpeed(float speed) @@ -274,14 +248,14 @@ void PWM::SetSpeed(float speed) /** * Get the PWM value in terms of speed. - * + * * This is intended to be used by speed controllers. - * + * * @pre SetMaxPositivePwm() called. * @pre SetMinPositivePwm() called. * @pre SetMaxNegativePwm() called. * @pre SetMinNegativePwm() called. - * + * * @return The most recently set speed between -1.0 and 1.0. */ float PWM::GetSpeed() @@ -316,9 +290,9 @@ float PWM::GetSpeed() /** * Set the PWM value directly to the hardware. - * + * * Write a raw value to a PWM channel. - * + * * @param value Raw PWM value. */ void PWM::SetRaw(unsigned short value) @@ -329,9 +303,9 @@ void PWM::SetRaw(unsigned short value) /** * Get the PWM value directly from the hardware. - * + * * Read a raw value from a PWM channel. - * + * * @return Raw PWM control value. */ unsigned short PWM::GetRaw() @@ -342,7 +316,7 @@ unsigned short PWM::GetRaw() /** * Slow down the PWM signal for old devices. - * + * * @param mult The period multiplier to apply to this channel */ void PWM::SetPeriodMultiplier(PeriodMultiplier mult) @@ -401,4 +375,3 @@ void PWM::InitTable(ITable *subTable) { ITable * PWM::GetTable() { return m_table; } - diff --git a/wpilibc/wpilibC++/lib/Relay.cpp b/wpilibc/wpilibC++/lib/Relay.cpp index 4ef9d1d5ed..608495374a 100644 --- a/wpilibc/wpilibC++/lib/Relay.cpp +++ b/wpilibc/wpilibC++/lib/Relay.cpp @@ -19,21 +19,12 @@ static Resource *relayChannels = NULL; * Common relay intitialization methode. * This code is common to all Relay constructors and initializes the relay and reserves * all resources that need to be locked. Initially the relay is set to both lines at 0v. - * @param slot The module slot number this relay is connected to. - * - * @param moduleNumber The digital module this relay is connected to (1 or 2). */ -void Relay::InitRelay (uint8_t moduleNumber) +void Relay::InitRelay() { m_table = NULL; char buf[64]; Resource::CreateResourceObject(&relayChannels, dio_kNumSystems * kRelayChannels * 2); - if (!SensorBase::CheckRelayModule(moduleNumber)) - { - snprintf(buf, 64, "Digital Module %d", moduleNumber); - wpi_setWPIErrorWithContext(ModuleIndexOutOfRange, buf); - return; - } if (!SensorBase::CheckRelayChannel(m_channel)) { snprintf(buf, 64, "Relay Channel %d", m_channel); @@ -43,56 +34,42 @@ void Relay::InitRelay (uint8_t moduleNumber) if (m_direction == kBothDirections || m_direction == kForwardOnly) { - snprintf(buf, 64, "Forward Relay %d (Module: %d)", m_channel, moduleNumber); - if (relayChannels->Allocate(((moduleNumber - 1) * kRelayChannels + m_channel) * 2, buf) == ~0ul) + snprintf(buf, 64, "Forward Relay %d", m_channel); + if (relayChannels->Allocate(m_channel * 2, buf) == ~0ul) { CloneError(relayChannels); return; } - HALReport(HALUsageReporting::kResourceType_Relay, m_channel, moduleNumber - 1); + HALReport(HALUsageReporting::kResourceType_Relay, m_channel); } if (m_direction == kBothDirections || m_direction == kReverseOnly) { - snprintf(buf, 64, "Reverse Relay %d (Module: %d)", m_channel, moduleNumber); - if (relayChannels->Allocate(((moduleNumber - 1) * kRelayChannels + m_channel) * 2 + 1, buf) == ~0ul) + snprintf(buf, 64, "Reverse Relay %d", m_channel); + if (relayChannels->Allocate(m_channel * 2 + 1, buf) == ~0ul) { CloneError(relayChannels); return; } - HALReport(HALUsageReporting::kResourceType_Relay, m_channel + 128, moduleNumber - 1); + HALReport(HALUsageReporting::kResourceType_Relay, m_channel + 128); } - m_module = DigitalModule::GetInstance(moduleNumber); + m_module = DigitalModule::GetInstance(1); m_module->SetRelayForward(m_channel, false); m_module->SetRelayReverse(m_channel, false); - LiveWindow::GetInstance()->AddActuator("Relay", moduleNumber, m_channel, this); + LiveWindow::GetInstance()->AddActuator("Relay", 1, m_channel, this); } /** - * Relay constructor given the module and the channel. - * - * @param moduleNumber The digital module this relay is connected to (1 or 2). - * @param channel The channel number within the module for this relay. - * @param direction The direction that the Relay object will control. - */ -Relay::Relay(uint8_t moduleNumber, uint32_t channel, Relay::Direction direction) - : m_channel (channel) - , m_direction (direction) -{ - InitRelay(moduleNumber); -} - -/** - * Relay constructor given a channel only where the default digital module is used. - * @param channel The channel number within the default module for this relay. + * Relay constructor given a channel. + * @param channel The channel number. * @param direction The direction that the Relay object will control. */ Relay::Relay(uint32_t channel, Relay::Direction direction) : m_channel (channel) , m_direction (direction) { - InitRelay(GetDefaultDigitalModule()); + InitRelay(); } /** @@ -106,26 +83,26 @@ Relay::~Relay() if (m_direction == kBothDirections || m_direction == kForwardOnly) { - relayChannels->Free(((m_module->GetNumber() - 1) * kRelayChannels + m_channel) * 2); + relayChannels->Free(m_channel * 2); } if (m_direction == kBothDirections || m_direction == kReverseOnly) { - relayChannels->Free(((m_module->GetNumber() - 1) * kRelayChannels + m_channel) * 2 + 1); + relayChannels->Free(m_channel * 2 + 1); } } /** * Set the relay state. - * + * * Valid values depend on which directions of the relay are controlled by the object. - * + * * When set to kBothDirections, the relay can be any of the four states: * 0v-0v, 0v-12v, 12v-0v, 12v-12v - * + * * When set to kForwardOnly or kReverseOnly, you can specify the constant for the * direction or you can simply specify kOff and kOn. Using only kOff and kOn is * recommended. - * + * * @param value The state to set the relay. */ void Relay::Set(Relay::Value value) @@ -188,12 +165,12 @@ void Relay::Set(Relay::Value value) /** * Get the Relay State - * + * * Gets the current state of the relay. - * + * * When set to kForwardOnly or kReverseOnly, value is returned as kOn/kOff not * kForward/kReverse (per the recommendation in Set) - * + * * @return The current state of the relay as a Relay::Value */ Relay::Value Relay::Get() { @@ -217,7 +194,7 @@ Relay::Value Relay::Get() { } else { return kOff; } - } + } } void Relay::ValueChanged(ITable* source, const std::string& key, EntryValue value, bool isNew) { @@ -268,5 +245,3 @@ void Relay::InitTable(ITable *subTable) { ITable * Relay::GetTable() { return m_table; } - - diff --git a/wpilibc/wpilibC++/lib/RobotDrive.cpp b/wpilibc/wpilibC++/lib/RobotDrive.cpp index 9b4f97f6a3..97509dfde3 100644 --- a/wpilibc/wpilibC++/lib/RobotDrive.cpp +++ b/wpilibc/wpilibC++/lib/RobotDrive.cpp @@ -47,8 +47,8 @@ void RobotDrive::InitRobotDrive() { * Set up parameters for a two wheel drive system where the * left and right motor pwm channels are specified in the call. * This call assumes Jaguars for controlling the motors. - * @param leftMotorChannel The PWM channel number on the default digital module that drives the left motor. - * @param rightMotorChannel The PWM channel number on the default digital module that drives the right motor. + * @param leftMotorChannel The PWM channel number that drives the left motor. + * @param rightMotorChannel The PWM channel number that drives the right motor. */ RobotDrive::RobotDrive(uint32_t leftMotorChannel, uint32_t rightMotorChannel) { @@ -68,10 +68,10 @@ RobotDrive::RobotDrive(uint32_t leftMotorChannel, uint32_t rightMotorChannel) * Set up parameters for a four wheel drive system where all four motor * pwm channels are specified in the call. * This call assumes Jaguars for controlling the motors. - * @param frontLeftMotor Front left motor channel number on the default digital module - * @param rearLeftMotor Rear Left motor channel number on the default digital module - * @param frontRightMotor Front right motor channel number on the default digital module - * @param rearRightMotor Rear Right motor channel number on the default digital module + * @param frontLeftMotor Front left motor channel number + * @param rearLeftMotor Rear Left motor channel number + * @param frontRightMotor Front right motor channel number + * @param rearRightMotor Rear Right motor channel number */ RobotDrive::RobotDrive(uint32_t frontLeftMotor, uint32_t rearLeftMotor, uint32_t frontRightMotor, uint32_t rearRightMotor) @@ -472,7 +472,7 @@ void RobotDrive::ArcadeDrive(float moveValue, float rotateValue, bool squaredInp * A method for driving with Mecanum wheeled robots. There are 4 wheels * on the robot, arranged so that the front and back wheels are toed in 45 degrees. * When looking at the wheels from the top, the roller axles should form an X across the robot. - * + * * This is designed to be directly driven by joystick axes. * * @param x The speed that the robot should drive in the X direction. [-1.0..1.0] @@ -514,7 +514,7 @@ void RobotDrive::MecanumDrive_Cartesian(float x, float y, float rotation, float m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_invertedMotors[kRearRightMotor] * m_maxOutput, syncGroup); CANJaguar::UpdateSyncGroup(syncGroup); - + m_safetyHelper->Feed(); } @@ -563,7 +563,7 @@ void RobotDrive::MecanumDrive_Polar(float magnitude, float direction, float rota m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_invertedMotors[kRearRightMotor] * m_maxOutput, syncGroup); CANJaguar::UpdateSyncGroup(syncGroup); - + m_safetyHelper->Feed(); } @@ -679,7 +679,7 @@ void RobotDrive::SetInvertedMotor(MotorType motor, bool isInverted) /** * Set the turning sensitivity. - * + * * This only impacts the Drive() entry-point. * @param sensitivity Effectively sets the turning sensitivity (or turn radius for a given value) */ diff --git a/wpilibc/wpilibC++/lib/SafePWM.cpp b/wpilibc/wpilibC++/lib/SafePWM.cpp index 8cecab654b..fb51f32fc4 100644 --- a/wpilibc/wpilibC++/lib/SafePWM.cpp +++ b/wpilibc/wpilibC++/lib/SafePWM.cpp @@ -18,24 +18,14 @@ void SafePWM::InitSafePWM() } /** - * Constructor for a SafePWM object taking a channel number - * @param channel The channel number to be used for the underlying PWM object + * Constructor for a SafePWM object taking a channel number. + * @param channel The PWM channel number (0..19). */ SafePWM::SafePWM(uint32_t channel): PWM(channel) { InitSafePWM(); } -/** - * Constructor for a SafePWM object taking channel and slot numbers. - * @param moduleNumber The digital module (1 or 2). - * @param channel The PWM channel number on the module (1..10). - */ -SafePWM::SafePWM(uint8_t moduleNumber, uint32_t channel): PWM(moduleNumber, channel) -{ - InitSafePWM(); -} - SafePWM::~SafePWM() { delete m_safetyHelper; @@ -100,7 +90,7 @@ bool SafePWM::IsSafetyEnabled() void SafePWM::GetDescription(char *desc) { - sprintf(desc, "PWM %d on module %d", GetChannel(), GetModuleNumber()); + sprintf(desc, "PWM %d", GetChannel()); } /** @@ -114,4 +104,3 @@ void SafePWM::SetSpeed(float speed) PWM::SetSpeed(speed); m_safetyHelper->Feed(); } - diff --git a/wpilibc/wpilibC++/lib/SensorBase.cpp b/wpilibc/wpilibC++/lib/SensorBase.cpp index 2af63a99b7..bc0fe2ceec 100644 --- a/wpilibc/wpilibC++/lib/SensorBase.cpp +++ b/wpilibc/wpilibC++/lib/SensorBase.cpp @@ -11,8 +11,6 @@ const uint32_t SensorBase::kDigitalChannels; const uint32_t SensorBase::kAnalogInputs; -const uint32_t SensorBase::kAnalogModules; -const uint32_t SensorBase::kDigitalModules; const uint32_t SensorBase::kSolenoidChannels; const uint32_t SensorBase::kSolenoidModules; const uint32_t SensorBase::kPwmChannels; @@ -66,50 +64,6 @@ void SensorBase::DeleteSingletons() m_singletonList = NULL; } -/** - * Check that the analog module number is valid. - * - * @return Analog module is valid and present - */ -bool SensorBase::CheckAnalogModule(uint8_t moduleNumber) -{ - if (nLoadOut::getModulePresence(nLoadOut::kModuleType_Analog, moduleNumber - 1)) - return true; - return false; -} - -/** - * Check that the digital module number is valid. - * - * @return Digital module is valid and present - */ -bool SensorBase::CheckDigitalModule(uint8_t moduleNumber) -{ - if (nLoadOut::getModulePresence(nLoadOut::kModuleType_Digital, moduleNumber - 1)) - return true; - return false; -} - -/** - * Check that the digital module number is valid. - * - * @return Digital module is valid and present - */ -bool SensorBase::CheckPWMModule(uint8_t moduleNumber) -{ - return CheckDigitalModule(moduleNumber); -} - -/** - * Check that the digital module number is valid. - * - * @return Digital module is valid and present - */ -bool SensorBase::CheckRelayModule(uint8_t moduleNumber) -{ - return CheckDigitalModule(moduleNumber); -} - /** * Check that the solenoid module number is valid. * diff --git a/wpilibc/wpilibC++/lib/Servo.cpp b/wpilibc/wpilibC++/lib/Servo.cpp index 46ddec89f0..e15a5f2451 100644 --- a/wpilibc/wpilibC++/lib/Servo.cpp +++ b/wpilibc/wpilibC++/lib/Servo.cpp @@ -27,14 +27,12 @@ void Servo::InitServo() SetBounds(kDefaultMaxServoPWM, 0.0, 0.0, 0.0, kDefaultMinServoPWM); SetPeriodMultiplier(kPeriodMultiplier_4X); - LiveWindow::GetInstance()->AddActuator("Servo", GetModuleNumber(), GetChannel(), this); - HALReport(HALUsageReporting::kResourceType_Servo, GetChannel(), GetModuleNumber() - 1); + LiveWindow::GetInstance()->AddActuator("Servo", GetChannel(), this); + HALReport(HALUsageReporting::kResourceType_Servo, GetChannel()); } /** - * Constructor that assumes the default digital module. - * - * @param channel The PWM channel on the digital module to which the servo is attached. + * @param channel The PWM channel to which the servo is attached. */ Servo::Servo(uint32_t channel) : SafePWM(channel) { @@ -42,17 +40,6 @@ Servo::Servo(uint32_t channel) : SafePWM(channel) // printf("Done initializing servo %d\n", channel); } -/** - * Constructor that specifies the digital module. - * - * @param moduleNumber The digital module (1 or 2). - * @param channel The PWM channel on the digital module to which the servo is attached (1..10). - */ -Servo::Servo(uint8_t moduleNumber, uint32_t channel) : SafePWM(moduleNumber, channel) -{ - InitServo(); -} - Servo::~Servo() { } @@ -71,7 +58,7 @@ void Servo::Set(float value) /** * Set the servo to offline. - * + * * Set the servo raw value to 0 (undriven) */ void Servo::SetOffline() { @@ -160,5 +147,3 @@ void Servo::InitTable(ITable *subTable) { ITable * Servo::GetTable() { return m_table; } - - diff --git a/wpilibc/wpilibC++/lib/Solenoid.cpp b/wpilibc/wpilibC++/lib/Solenoid.cpp index f02551ec6f..8c343fc9c8 100644 --- a/wpilibc/wpilibC++/lib/Solenoid.cpp +++ b/wpilibc/wpilibC++/lib/Solenoid.cpp @@ -43,7 +43,7 @@ void Solenoid::InitSolenoid() /** * Constructor. - * + * * @param channel The channel on the solenoid module to control (1..8). */ Solenoid::Solenoid(uint32_t channel) @@ -55,7 +55,7 @@ Solenoid::Solenoid(uint32_t channel) /** * Constructor. - * + * * @param moduleNumber The solenoid module (1 or 2). * @param channel The channel on the solenoid module to control (1..8). */ @@ -79,7 +79,7 @@ Solenoid::~Solenoid() /** * Set the value of a solenoid. - * + * * @param on Turn the solenoid output off or on. */ void Solenoid::Set(bool on) @@ -93,7 +93,7 @@ void Solenoid::Set(bool on) /** * Read the current value of the solenoid. - * + * * @return The current value of the solenoid. */ bool Solenoid::Get() @@ -140,4 +140,3 @@ void Solenoid::InitTable(ITable *subTable) { ITable * Solenoid::GetTable() { return m_table; } - diff --git a/wpilibc/wpilibC++/lib/Talon.cpp b/wpilibc/wpilibC++/lib/Talon.cpp index e00fad7508..39d6bf187b 100644 --- a/wpilibc/wpilibC++/lib/Talon.cpp +++ b/wpilibc/wpilibC++/lib/Talon.cpp @@ -6,7 +6,6 @@ #include "Talon.h" -#include "DigitalModule.h" //#include "NetworkCommunication/UsageReporting.h" #include "LiveWindow/LiveWindow.h" @@ -17,7 +16,7 @@ * most controllers, but if users experience issues such as asymmetric behavior around * the deadband or inability to saturate the controller in either direction, calibration is recommended. * The calibration procedure can be found in the Talon User Manual available from CTRE. - * + * * - 211 = full "forward" * - 133 = the "high end" of the deadband range * - 129 = center of the deadband range (off) @@ -29,41 +28,28 @@ void Talon::InitTalon() { SetPeriodMultiplier(kPeriodMultiplier_2X); SetRaw(m_centerPwm); - HALReport(HALUsageReporting::kResourceType_Talon, GetChannel(), GetModuleNumber() - 1); - LiveWindow::GetInstance()->AddActuator("Talon", GetModuleNumber(), GetChannel(), this); + HALReport(HALUsageReporting::kResourceType_Talon, GetChannel()); + LiveWindow::GetInstance()->AddActuator("Talon", GetChannel(), this); } /** - * Constructor that assumes the default digital module. - * - * @param channel The PWM channel on the digital module that the Talon is attached to. + * @param channel The PWM channel that the Talon is attached to. */ Talon::Talon(uint32_t channel) : SafePWM(channel) { InitTalon(); } -/** - * Constructor that specifies the digital module. - * - * @param moduleNumber The digital module (1 or 2). - * @param channel The PWM channel on the digital module that the Talon is attached to (1..10). - */ -Talon::Talon(uint8_t moduleNumber, uint32_t channel) : SafePWM(moduleNumber, channel) -{ - InitTalon(); -} - Talon::~Talon() { } /** - * Set the PWM value. - * + * Set the PWM value. + * * The PWM value is set using a range of -1.0 to 1.0, appropriately * scaling the value for the FPGA. - * + * * @param speed The speed value between -1.0 and 1.0 to set. * @param syncGroup Unused interface. */ @@ -74,7 +60,7 @@ void Talon::Set(float speed, uint8_t syncGroup) /** * Get the recently set value of the PWM. - * + * * @return The most recently set value for the PWM between -1.0 and 1.0. */ float Talon::Get() @@ -92,11 +78,10 @@ void Talon::Disable() /** * Write out the PID value as seen in the PIDOutput base object. - * + * * @param output Write out the PWM value as was found in the PIDController */ -void Talon::PIDWrite(float output) +void Talon::PIDWrite(float output) { Set(output); } - diff --git a/wpilibc/wpilibC++/lib/Ultrasonic.cpp b/wpilibc/wpilibC++/lib/Ultrasonic.cpp index 3a041a43a7..59617822a9 100644 --- a/wpilibc/wpilibC++/lib/Ultrasonic.cpp +++ b/wpilibc/wpilibC++/lib/Ultrasonic.cpp @@ -27,7 +27,7 @@ SEMAPHORE_ID Ultrasonic::m_semaphore = 0; /** * Background task that goes through the list of ultrasonic sensors and pings each one in turn. The counter * is configured to read the timing of the returned echo pulse. - * + * * DANGER WILL ROBINSON, DANGER WILL ROBINSON: * This code runs as a task and assumes that none of the ultrasonic sensors will change while it's * running. If one does, then this will certainly break. Make sure to disable automatic mode before changing @@ -78,13 +78,12 @@ void Ultrasonic::Initialize() static int instances = 0; instances++; HALReport(HALUsageReporting::kResourceType_Ultrasonic, instances); - LiveWindow::GetInstance()->AddSensor("Ultrasonic", m_echoChannel->GetModuleForRouting(), m_echoChannel->GetChannel(), this); + LiveWindow::GetInstance()->AddSensor("Ultrasonic", m_echoChannel->GetChannel(), this); } /** - * Create an instance of the Ultrasonic Sensor using the default module. - * This is designed to supchannel the Daventech SRF04 and Vex ultrasonic sensors. This - * constructor assumes that both digital I/O channels are in the default digital module. + * Create an instance of the Ultrasonic Sensor + * This is designed to supchannel the Daventech SRF04 and Vex ultrasonic sensors. * @param pingChannel The digital output channel that sends the pulse to initiate the sensor sending * the ping. * @param echoChannel The digital input channel that receives the echo. The length of time that the @@ -137,28 +136,6 @@ Ultrasonic::Ultrasonic(DigitalOutput &pingChannel, DigitalInput &echoChannel, Di Initialize(); } -/** - * Create an instance of the Ultrasonic sensor using specified modules. - * This is designed to supchannel the Daventech SRF04 and Vex ultrasonic sensors. This - * constructors takes the channel and module slot for each of the required digital I/O channels. - * @param pingModuleNumber The digital module that the pingChannel is on. - * @param pingChannel The digital output channel that sends the pulse to initiate the sensor - * sending the ping. - * @param echoModuleNumber The digital module that the echoChannel is on. - * @param echoChannel The digital input channel that receives the echo. The length of time - * that the echo is high represents the round trip time of the ping, and the distance. - * @param units The units returned in either kInches or kMilliMeters - */ -Ultrasonic::Ultrasonic(uint8_t pingModuleNumber, uint32_t pingChannel, - uint8_t echoModuleNumber, uint32_t echoChannel, DistanceUnit units) -{ - m_pingChannel = new DigitalOutput(pingModuleNumber, pingChannel); - m_echoChannel = new DigitalInput(echoModuleNumber, echoChannel); - m_allocatedChannels = true; - m_units = units; - Initialize(); -} - /** * Destructor for the ultrasonic sensor. * Delete the instance of the ultrasonic sensor by freeing the allocated digital channels. @@ -296,12 +273,12 @@ double Ultrasonic::GetRangeMM() /** * Get the range in the current DistanceUnit for the PIDSource base object. - * + * * @return The range in DistanceUnit */ double Ultrasonic::PIDGet() { - switch(m_units) + switch(m_units) { case Ultrasonic::kInches: return GetRangeInches(); @@ -314,7 +291,7 @@ double Ultrasonic::PIDGet() /** * Set the current DistanceUnit that should be used for the PIDSource base object. - * + * * @param units The DistanceUnit that should be used. */ void Ultrasonic::SetDistanceUnits(DistanceUnit units) @@ -324,7 +301,7 @@ void Ultrasonic::SetDistanceUnits(DistanceUnit units) /** * Get the current DistanceUnit that is used for the PIDSource base object. - * + * * @return The type of DistanceUnit that is being used. */ Ultrasonic::DistanceUnit Ultrasonic::GetDistanceUnits() @@ -339,11 +316,11 @@ void Ultrasonic::UpdateTable() { } void Ultrasonic::StartLiveWindowMode() { - + } void Ultrasonic::StopLiveWindowMode() { - + } std::string Ultrasonic::GetSmartDashboardType() { @@ -358,4 +335,3 @@ void Ultrasonic::InitTable(ITable *subTable) { ITable * Ultrasonic::GetTable() { return m_table; } - diff --git a/wpilibc/wpilibC++/lib/Victor.cpp b/wpilibc/wpilibC++/lib/Victor.cpp index 36478ae6c0..173e9c1801 100644 --- a/wpilibc/wpilibC++/lib/Victor.cpp +++ b/wpilibc/wpilibC++/lib/Victor.cpp @@ -6,7 +6,6 @@ #include "Victor.h" -#include "DigitalModule.h" //#include "NetworkCommunication/UsageReporting.h" #include "LiveWindow/LiveWindow.h" @@ -18,7 +17,7 @@ * Victor 884 controllers as well but if users experience issues such as asymmetric behavior around * the deadband or inability to saturate the controller in either direction, calibration is recommended. * The calibration procedure can be found in the Victor 884 User Manual available from IFI. - * + * * - 206 = full "forward" * - 131 = the "high end" of the deadband range * - 128 = center of the deadband range (off) @@ -27,45 +26,32 @@ */ void Victor::InitVictor() { SetBounds(2.027, 1.525, 1.507, 1.49, 1.026); - + SetPeriodMultiplier(kPeriodMultiplier_2X); SetRaw(m_centerPwm); - LiveWindow::GetInstance()->AddActuator("Victor", GetModuleNumber(), GetChannel(), this); - HALReport(HALUsageReporting::kResourceType_Victor, GetChannel(), GetModuleNumber() - 1); + LiveWindow::GetInstance()->AddActuator("Victor", GetChannel(), this); + HALReport(HALUsageReporting::kResourceType_Victor, GetChannel()); } /** - * Constructor that assumes the default digital module. - * - * @param channel The PWM channel on the digital module that the Victor is attached to. + * @param channel The PWM channel that the Victor is attached to. */ Victor::Victor(uint32_t channel) : SafePWM(channel) { InitVictor(); } -/** - * Constructor that specifies the digital module. - * - * @param moduleNumber The digital module (1 or 2). - * @param channel The PWM channel on the digital module that the Victor is attached to (1..10). - */ -Victor::Victor(uint8_t moduleNumber, uint32_t channel) : SafePWM(moduleNumber, channel) -{ - InitVictor(); -} - Victor::~Victor() { } /** - * Set the PWM value. - * + * Set the PWM value. + * * The PWM value is set using a range of -1.0 to 1.0, appropriately * scaling the value for the FPGA. - * + * * @param speed The speed value between -1.0 and 1.0 to set. * @param syncGroup Unused interface. */ @@ -76,7 +62,7 @@ void Victor::Set(float speed, uint8_t syncGroup) /** * Get the recently set value of the PWM. - * + * * @return The most recently set value for the PWM between -1.0 and 1.0. */ float Victor::Get() @@ -94,11 +80,10 @@ void Victor::Disable() /** * Write out the PID value as seen in the PIDOutput base object. - * + * * @param output Write out the PWM value as was found in the PIDController */ -void Victor::PIDWrite(float output) +void Victor::PIDWrite(float output) { Set(output); } - diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java index 6f76468e0f..c25089ffc8 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java @@ -74,11 +74,10 @@ public class ADXL345_I2C extends SensorBase { /** * Constructor. * - * @param module The slot of the digital module that the sensor is plugged into. * @param range The range (+ or -) that the accelerometer will measure. */ - public ADXL345_I2C(int moduleNumber, DataFormat_Range range) { - DigitalModule module = DigitalModule.getInstance(moduleNumber); + public ADXL345_I2C(DataFormat_Range range) { + DigitalModule module = DigitalModule.getInstance(1); m_i2c = module.getI2C(kAddress); // Turn on the measurements @@ -86,7 +85,7 @@ public class ADXL345_I2C extends SensorBase { // Specify the data format to read m_i2c.write(kDataFormatRegister, kDataFormat_FullRes | range.value); - UsageReporting.report(tResourceType.kResourceType_ADXL345, tInstances.kADXL345_I2C, moduleNumber-1); + UsageReporting.report(tResourceType.kResourceType_ADXL345, tInstances.kADXL345_I2C); } /** diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Accelerometer.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Accelerometer.java index 39a5afb963..846a1b8cd1 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Accelerometer.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Accelerometer.java @@ -32,16 +32,15 @@ public class Accelerometer extends SensorBase implements PIDSource, ISensor, Liv * Common initialization */ private void initAccelerometer() { - UsageReporting.report(tResourceType.kResourceType_Accelerometer, m_analogChannel.getChannel(), m_analogChannel.getModuleNumber()-1); - LiveWindow.addSensor("Accelerometer", m_analogChannel.getModuleNumber(), m_analogChannel.getChannel(), this); + UsageReporting.report(tResourceType.kResourceType_Accelerometer, m_analogChannel.getChannel()); + LiveWindow.addSensor("Accelerometer", m_analogChannel.getChannel(), this); } /** * Create a new instance of an accelerometer. * - * The accelerometer is assumed to be in the first analog module in the given analog channel. The - * constructor allocates desired analog channel. - * @param channel the port that the accelerometer is on on the default module + * The constructor allocates desired analog channel. + * @param channel the port that the accelerometer is on */ public Accelerometer(final int channel) { m_allocatedChannel = true; @@ -49,20 +48,6 @@ public class Accelerometer extends SensorBase implements PIDSource, ISensor, Liv initAccelerometer(); } - /** - * Create new instance of accelerometer. - * - * Make a new instance of the accelerometer given a module and channel. The constructor allocates - * the desired analog channel from the specified module - * @param slot the slot that the module is in - * @param channel the port that the Accelerometer is on on the module - */ - public Accelerometer(final int slot, final int channel) { - m_allocatedChannel = true; - m_analogChannel = new AnalogInput(slot, channel); - initAccelerometer(); - } - /** * Create a new instance of Accelerometer from an existing AnalogChannel. * Make a new instance of accelerometer given an AnalogChannel. This is particularly diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java index e1515cbc98..1b58e6bc11 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java @@ -43,53 +43,33 @@ public class AnalogInput extends SensorBase implements PIDSource, LiveWindowSendable { private static final int kAccumulatorSlot = 1; - private static Resource channels = new Resource(kAnalogModules - * kAnalogInputChannels); + private static Resource channels = new Resource(kAnalogInputChannels); private ByteBuffer m_port; - private int m_moduleNumber, m_channel; + private int m_channel; private static final int[] kAccumulatorChannels = { 0, 1 }; private long m_accumulatorOffset; /** - * Construct an analog channel on the default module. + * Construct an analog channel. * * @param channel * The channel number to represent. */ public AnalogInput(final int channel) { - this(getDefaultAnalogModule(), channel); - } - - /** - * Construct an analog channel on a specified module. - * - * @param moduleNumber - * The digital module to use (1 or 2). - * @param channel - * The channel number to represent. - */ - public AnalogInput(final int moduleNumber, final int channel) { m_channel = channel; - m_moduleNumber = moduleNumber; - if (AnalogJNI.checkAnalogModule((byte)moduleNumber) == 0) { - throw new AllocationException("Analog input channel " + m_channel - + " on module " + m_moduleNumber - + " cannot be allocated. Module is not present."); - } + if (AnalogJNI.checkAnalogInputChannel(channel) == 0) { throw new AllocationException("Analog input channel " + m_channel - + " on module " + m_moduleNumber + " cannot be allocated. Channel is not present."); } try { - channels.allocate((moduleNumber - 1) * kAnalogInputChannels + channel); + channels.allocate(channel); } catch (CheckedAllocationException e) { throw new AllocationException("Analog input channel " + m_channel - + " on module " + m_moduleNumber + " is already allocated"); + + " is already allocated"); } - ByteBuffer port_pointer = AnalogJNI.getPortWithModule( - (byte) moduleNumber, (byte) channel); + ByteBuffer port_pointer = AnalogJNI.getPortWithModule((byte) 1, (byte) channel); ByteBuffer status = ByteBuffer.allocateDirect(4); // set the byte order status.order(ByteOrder.LITTLE_ENDIAN); @@ -97,28 +77,26 @@ public class AnalogInput extends SensorBase implements PIDSource, m_port = AnalogJNI.initializeAnalogInputPort(port_pointer, status.asIntBuffer()); HALUtil.checkStatus(status.asIntBuffer()); - LiveWindow.addSensor("AnalogInput", moduleNumber, channel, this); - UsageReporting.report(tResourceType.kResourceType_AnalogChannel, - channel, moduleNumber - 1); + LiveWindow.addSensor("AnalogInput", channel, this); + UsageReporting.report(tResourceType.kResourceType_AnalogChannel, channel); } /** * Channel destructor. */ public void free() { - channels.free(((m_moduleNumber - 1) * kAnalogInputChannels + m_channel)); + channels.free(m_channel); m_channel = 0; - m_moduleNumber = 0; m_accumulatorOffset = 0; } /** - * Get the analog module that this channel is on. + * Get the analog module. * - * @return The AnalogModule that this channel is on. + * @return The AnalogModule. */ public AnalogModule getModule() { - return AnalogModule.getInstance(m_moduleNumber); + return AnalogModule.getInstance(1); } /** @@ -239,15 +217,6 @@ public class AnalogInput extends SensorBase implements PIDSource, return m_channel; } - /** - * Gets the number of the analog module this channel is on. - * - * @return The module number of the analog module this channel is on. - */ - public int getModuleNumber() { - return m_moduleNumber; - } - /** * Set the number of averaging bits. This sets the number of averaging bits. * The actual number of averaged samples is 2**bits. The averaging is done @@ -435,7 +404,6 @@ public class AnalogInput extends SensorBase implements PIDSource, } if (!isAccumulatorChannel()) { throw new IllegalArgumentException("Channel " + m_channel - + " on module " + m_moduleNumber + " is not an accumulator channel."); } ByteBuffer value = ByteBuffer.allocateDirect(8); @@ -459,9 +427,6 @@ public class AnalogInput extends SensorBase implements PIDSource, * @return The analog channel is attached to an accumulator. */ public boolean isAccumulatorChannel() { - if (m_moduleNumber != kAccumulatorSlot) { - return false; - } for (int i = 0; i < kAccumulatorChannels.length; i++) { if (m_channel == kAccumulatorChannels[i]) { return true; diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java index a548adf052..787b904c73 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java @@ -59,7 +59,7 @@ public class AnalogOutput extends SensorBase implements LiveWindowSendable { m_port = AnalogJNI.initializeAnalogOutputPort(port_pointer, status.asIntBuffer()); HALUtil.checkStatus(status.asIntBuffer()); - LiveWindow.addSensor("AnalogOutput", 1, channel, this); + LiveWindow.addSensor("AnalogOutput", channel, this); UsageReporting.report(tResourceType.kResourceType_AnalogChannel, channel, 1); } diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java index e49900f345..db242189df 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java @@ -12,40 +12,20 @@ import edu.wpi.first.wpilibj.tables.ITable; * @author Alex Henning */ public class AnalogPotentiometer implements Potentiometer, LiveWindowSendable { - private int m_module, m_channel; + private int m_channel; private double m_scale, m_offset; private AnalogInput m_analog_input; - + /** * Common initialization code called by all constructors. */ - private void initPot(final int slot, final int channel, double scale, double offset) { - this.m_module = slot; + private void initPot(final int channel, double scale, double offset) { this.m_channel = channel; this.m_scale = scale; this.m_offset = offset; - m_analog_input = new AnalogInput(slot, channel); + m_analog_input = new AnalogInput(channel); } - - /** - * AnalogPotentiometer constructor. - * - * Use the scaling and offset values so that the output produces - * meaningful values. I.E: you have a 270 degree potentiometer and - * you want the output to be degrees with the halfway point as 0 - * degrees. The scale value is 270.0(degrees)/5.0(volts) and the - * offset is -135.0 since the halfway point after scaling is 135 - * degrees. - * - * @param slot The analog module this potentiometer is plugged into. - * @param channel The analog channel this potentiometer is plugged into. - * @param scale The scaling to multiply the voltage by to get a meaningful unit. - * @param offset The offset to add to the scaled value for controlling the zero value - */ - public AnalogPotentiometer(final int slot, final int channel, double scale, double offset) { - initPot(slot, channel, scale, offset); - } - + /** * AnalogPotentiometer constructor. * @@ -61,9 +41,9 @@ public class AnalogPotentiometer implements Potentiometer, LiveWindowSendable { * @param offset The offset to add to the scaled value for controlling the zero value */ public AnalogPotentiometer(final int channel, double scale, double offset) { - initPot(1, channel, scale, offset); + initPot(channel, scale, offset); } - + /** * AnalogPotentiometer constructor. * @@ -78,18 +58,18 @@ public class AnalogPotentiometer implements Potentiometer, LiveWindowSendable { * @param scale The scaling to multiply the voltage by to get a meaningful unit. */ public AnalogPotentiometer(final int channel, double scale) { - initPot(1, channel, scale, 0); + initPot(channel, scale, 0); } - + /** * AnalogPotentiometer constructor. * * @param channel The analog channel this potentiometer is plugged into. */ public AnalogPotentiometer(final int channel) { - initPot(1, channel, 1, 0); + initPot(channel, 1, 0); } - + /** * Get the current reading of the potentiomere. * @@ -98,8 +78,8 @@ public class AnalogPotentiometer implements Potentiometer, LiveWindowSendable { public double get() { return m_analog_input.getVoltage() * m_scale + m_offset; } - - + + /** * Implement the PIDSource interface. * @@ -108,7 +88,7 @@ public class AnalogPotentiometer implements Potentiometer, LiveWindowSendable { public double pidGet() { return get(); } - + /* * Live Window code, only does anything if live window is activated. */ @@ -116,7 +96,7 @@ public class AnalogPotentiometer implements Potentiometer, LiveWindowSendable { return "Analog Input"; } private ITable m_table; - + /** * {@inheritDoc} */ @@ -124,7 +104,7 @@ public class AnalogPotentiometer implements Potentiometer, LiveWindowSendable { m_table = subtable; updateTable(); } - + /** * {@inheritDoc} */ @@ -133,20 +113,20 @@ public class AnalogPotentiometer implements Potentiometer, LiveWindowSendable { m_table.putNumber("Value", get()); } } - + /** * {@inheritDoc} */ public ITable getTable(){ return m_table; } - + /** * Analog Channels don't have to do anything special when entering the LiveWindow. * {@inheritDoc} */ public void startLiveWindowMode() {} - + /** * Analog Channels don't have to do anything special when exiting the LiveWindow. * {@inheritDoc} diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java index 8380fbdcf5..558ada811e 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java @@ -21,7 +21,7 @@ import edu.wpi.first.wpilibj.util.BoundaryException; /** * Class for creating and configuring Analog Triggers - * + * * @author dtjones */ public class AnalogTrigger implements IInputOutput { @@ -33,7 +33,7 @@ public class AnalogTrigger implements IInputOutput { /** * Create a new exception with the given message - * + * * @param message * the message to pass with the exception */ @@ -50,18 +50,13 @@ public class AnalogTrigger implements IInputOutput { protected int m_index; /** - * Initialize an analog trigger from a module number and channel. This is - * the common code for the two constructors that use a module number and - * channel. - * - * @param moduleNumber - * The number of the analog module to create this trigger on. + * Initialize an analog trigger from a channel. + * * @param channel * the port to use for the analog trigger */ - protected void initTrigger(final int moduleNumber, final int channel) { - ByteBuffer port_pointer = AnalogJNI.getPortWithModule( - (byte) moduleNumber, (byte) channel); + protected void initTrigger(final int channel) { + ByteBuffer port_pointer = AnalogJNI.getPortWithModule((byte) 1, (byte) channel); IntBuffer status = IntBuffer.allocate(1); IntBuffer index = IntBuffer.allocate(1); // XXX: Uncomment when analog has been fixed @@ -70,44 +65,29 @@ public class AnalogTrigger implements IInputOutput { //HALUtil.checkStatus(status); //m_index = index.get(0); - UsageReporting.report(tResourceType.kResourceType_AnalogTrigger, - channel, moduleNumber-1); + UsageReporting.report(tResourceType.kResourceType_AnalogTrigger, channel); } /** - * Constructor for an analog trigger given a channel number. The default - * module is used in this case. - * + * Constructor for an analog trigger given a channel number. + * * @param channel * the port to use for the analog trigger */ public AnalogTrigger(final int channel) { - initTrigger(AnalogModule.getDefaultAnalogModule(), channel); - } - - /** - * Constructor for an analog trigger given both the module number and - * channel. - * - * @param moduleNumber - * The number of the analog module to create this trigger on. - * @param channel - * the port to use for the analog trigger - */ - public AnalogTrigger(final int moduleNumber, final int channel) { - initTrigger(moduleNumber, channel); + initTrigger(channel); } /** * Construct an analog trigger given an analog channel. This should be used * in the case of sharing an analog channel between the trigger and an * analog input object. - * + * * @param channel - * the AnalogChannel to use for the analog trigger + * the AnalogInput to use for the analog trigger */ public AnalogTrigger(AnalogInput channel) { - initTrigger(channel.getModuleNumber(), channel.getChannel()); + initTrigger(channel.getChannel()); } /** @@ -124,7 +104,7 @@ public class AnalogTrigger implements IInputOutput { * Set the upper and lower limits of the analog trigger. The limits are * given in ADC codes. If oversampling is used, the units must be scaled * appropriately. - * + * * @param lower * the lower raw limit * @param upper @@ -142,7 +122,7 @@ public class AnalogTrigger implements IInputOutput { /** * Set the upper and lower limits of the analog trigger. The limits are * given as floating point voltage values. - * + * * @param lower * the lower voltage limit * @param upper @@ -165,7 +145,7 @@ public class AnalogTrigger implements IInputOutput { * Configure the analog trigger to use the averaged vs. raw values. If the * value is true, then the averaged value is selected for the analog * trigger, otherwise the immediate value is used. - * + * * @param useAveragedValue * true to use an averaged value, false otherwise */ @@ -181,7 +161,7 @@ public class AnalogTrigger implements IInputOutput { * will operate with a 3 point average rejection filter. This is designed to * help with 360 degree pot applications for the period where the pot * crosses through zero. - * + * * @param useFilteredValue * true to use a filterd value, false otherwise */ @@ -195,7 +175,7 @@ public class AnalogTrigger implements IInputOutput { /** * Return the index of the analog trigger. This is the FPGA index of this * analog trigger instance. - * + * * @return The index of the analog trigger. */ public int getIndex() { @@ -205,7 +185,7 @@ public class AnalogTrigger implements IInputOutput { /** * Return the InWindow output of the analog trigger. True if the analog * input is between the upper and lower limits. - * + * * @return The InWindow output of the analog trigger. */ public boolean getInWindow() { @@ -219,7 +199,7 @@ public class AnalogTrigger implements IInputOutput { * Return the TriggerState output of the analog trigger. True if above upper * limit. False if below lower limit. If in Hysteresis, maintain previous * state. - * + * * @return The TriggerState output of the analog trigger. */ public boolean getTriggerState() { @@ -233,7 +213,7 @@ public class AnalogTrigger implements IInputOutput { * Creates an AnalogTriggerOutput object. Gets an output object that can be * used for routing. Caller is responsible for deleting the * AnalogTriggerOutput object. - * + * * @param type * An enum of the type of output object to create. * @return A pointer to a new AnalogTriggerOutput object. diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Compressor.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Compressor.java index cac7f19a27..089e8d9110 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Compressor.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Compressor.java @@ -12,74 +12,74 @@ import edu.wpi.first.wpilibj.tables.ITable; public class Compressor extends SensorBase implements IDevice, LiveWindowSendable { private ByteBuffer m_pcm; - - public Compressor(int module) { - initCompressor(module); + + public Compressor(int pcmId) { + initCompressor(pcmId); } - + public Compressor() { initCompressor(getDefaultSolenoidModule()); } - + private void initCompressor(int module) { m_table = null; - + m_pcm = CompressorJNI.initializeCompressor((byte)module); } - + public void start() { setClosedLoopControl(true); } - + public void stop() { setClosedLoopControl(false); } - + public boolean enabled() { ByteBuffer status = ByteBuffer.allocateDirect(4); status.order(ByteOrder.LITTLE_ENDIAN); - + boolean on = CompressorJNI.getCompressor(m_pcm, status.asIntBuffer()); HALUtil.checkStatus(status.asIntBuffer()); - + return on; } - + public boolean getPressureSwitchValue() { ByteBuffer status = ByteBuffer.allocateDirect(4); status.order(ByteOrder.LITTLE_ENDIAN); - + boolean on = CompressorJNI.getPressureSwitch(m_pcm, status.asIntBuffer()); HALUtil.checkStatus(status.asIntBuffer()); - + return on; } - + public float getCompressorCurrent() { ByteBuffer status = ByteBuffer.allocateDirect(4); status.order(ByteOrder.LITTLE_ENDIAN); - + float current = CompressorJNI.getCompressorCurrent(m_pcm, status.asIntBuffer()); HALUtil.checkStatus(status.asIntBuffer()); - + return current; } - + public void setClosedLoopControl(boolean on) { ByteBuffer status = ByteBuffer.allocateDirect(4); status.order(ByteOrder.LITTLE_ENDIAN); - + CompressorJNI.setClosedLoopControl(m_pcm, on, status.asIntBuffer()); HALUtil.checkStatus(status.asIntBuffer()); } - + public boolean getClosedLoopControl() { ByteBuffer status = ByteBuffer.allocateDirect(4); status.order(ByteOrder.LITTLE_ENDIAN); - + boolean on = CompressorJNI.getClosedLoopControl(m_pcm, status.asIntBuffer()); HALUtil.checkStatus(status.asIntBuffer()); - + return on; } @@ -90,7 +90,7 @@ public class Compressor extends SensorBase implements IDevice, LiveWindowSendabl @Override public void stopLiveWindowMode() { } - + @Override public String getSmartDashboardType() { return "Compressor"; @@ -103,7 +103,7 @@ public class Compressor extends SensorBase implements IDevice, LiveWindowSendabl m_table = subtable; updateTable(); } - + @Override public ITable getTable() { return m_table; diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Counter.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Counter.java index 368aa0c95a..4ddee76574 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Counter.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Counter.java @@ -106,7 +106,7 @@ public class Counter extends SensorBase implements CounterBase, * Create an instance of a counter from a Digital Input. This is used if an * existing digital input is to be shared by multiple other objects such as * encoders. - * + * * @param source * the digital source to count */ @@ -119,8 +119,8 @@ public class Counter extends SensorBase implements CounterBase, /** * Create an instance of a Counter object. Create an up-Counter instance - * given a channel. The default digital module is assumed. - * + * given a channel. + * * @param channel * the digital input channel to count */ @@ -129,25 +129,11 @@ public class Counter extends SensorBase implements CounterBase, setUpSource(channel); } - /** - * Create an instance of a Counter object. Create an instance of an - * up-Counter given a digital module and a channel. - * - * @param slot - * The cRIO chassis slot for the digital module used - * @param channel - * The channel in the digital module - */ - public Counter(int slot, int channel) { - initCounter(Mode.kTwoPulse); - setUpSource(slot, channel); - } - /** * Create an instance of a Counter object. Create an instance of a simple * up-Counter given an analog trigger. Use the trigger state output from the * analog trigger. - * + * * @param encodingType * which edges to count * @param upSource @@ -188,7 +174,7 @@ public class Counter extends SensorBase implements CounterBase, * Create an instance of a Counter object. Create an instance of a simple * up-Counter given an analog trigger. Use the trigger state output from the * analog trigger. - * + * * @param trigger * the analog trigger to count */ @@ -214,22 +200,8 @@ public class Counter extends SensorBase implements CounterBase, } /** - * Set the up source for the counter as digital input channel and slot. - * - * @param slot - * the location of the digital module to use - * @param channel - * the digital port to count - */ - public void setUpSource(int slot, int channel) { - setUpSource(new DigitalInput(slot, channel)); - m_allocatedUpSource = true; - } - - /** - * Set the upsource for the counter as a digital input channel. The slot - * will be the default digital module slot. - * + * Set the upsource for the counter as a digital input channel. + * * @param channel * the digital port to count */ @@ -241,7 +213,7 @@ public class Counter extends SensorBase implements CounterBase, /** * Set the source object that causes the counter to count up. Set the up * counting DigitalSource. - * + * * @param source * the digital source to count */ @@ -262,7 +234,7 @@ public class Counter extends SensorBase implements CounterBase, /** * Set the up counting source to be an analog trigger. - * + * * @param analogTrigger * The analog trigger object that is used for the Up Source * @param triggerType @@ -276,7 +248,7 @@ public class Counter extends SensorBase implements CounterBase, /** * Set the edge sensitivity on an up counting source. Set the up source to * either detect rising edges or falling edges. - * + * * @param risingEdge * true to count rising edge * @param fallingEdge @@ -311,9 +283,8 @@ public class Counter extends SensorBase implements CounterBase, } /** - * Set the down counting source to be a digital input channel. The slot will - * be set to the default digital module slot. - * + * Set the down counting source to be a digital input channel. + * * @param channel * the digital port to count */ @@ -322,23 +293,10 @@ public class Counter extends SensorBase implements CounterBase, m_allocatedDownSource = true; } - /** - * Set the down counting source to be a digital input slot and channel. - * - * @param slot - * the location of the digital module to use - * @param channel - * the digital port to count - */ - public void setDownSource(int slot, int channel) { - setDownSource(new DigitalInput(slot, channel)); - m_allocatedDownSource = true; - } - /** * Set the source object that causes the counter to count down. Set the down * counting DigitalSource. - * + * * @param source * the digital source to count */ @@ -363,7 +321,7 @@ public class Counter extends SensorBase implements CounterBase, /** * Set the down counting source to be an analog trigger. - * + * * @param analogTrigger * The analog trigger object that is used for the Down Source * @param triggerType @@ -377,7 +335,7 @@ public class Counter extends SensorBase implements CounterBase, /** * Set the edge sensitivity on a down counting source. Set the down source * to either detect rising edges or falling edges. - * + * * @param risingEdge * true to count the rising edge * @param fallingEdge @@ -435,7 +393,7 @@ public class Counter extends SensorBase implements CounterBase, /** * Set Semi-period mode on this counter. Counts up on both rising and * falling edges. - * + * * @param highSemiPeriod * true to count up on both rising and falling */ @@ -451,7 +409,7 @@ public class Counter extends SensorBase implements CounterBase, * Configure the counter to count in up or down based on the length of the * input pulse. This mode is most useful for direction sensitive gear tooth * sensors. - * + * * @param threshold * The pulse length beyond which the counter counts the opposite * direction. Units are seconds. @@ -492,7 +450,7 @@ public class Counter extends SensorBase implements CounterBase, /** * Read the current scaled counter value. Read the value at this instant, * scaled by the distance per pulse (defaults to 1). - * + * * @return */ public double getDistance() { @@ -527,7 +485,7 @@ public class Counter extends SensorBase implements CounterBase, * Sets the maximum period where the device is considered moving. This value * is used to determine the "stopped" state of the counter using the * GetStopped method. - * + * * @param maxPeriod * The maximum period where the counted device is considered * moving in seconds. @@ -552,7 +510,7 @@ public class Counter extends SensorBase implements CounterBase, * been no events since an FPGA reset) and you will likely not see the * stopped bit become true (since it is updated at the end of an average and * there are no samples to average). - * + * * @param enabled * true to continue updating */ @@ -569,7 +527,7 @@ public class Counter extends SensorBase implements CounterBase, * stopped based on the MaxPeriod value set using the SetMaxPeriod method. * If the clock exceeds the MaxPeriod, then the device (and counter) are * assumed to be stopped and it returns true. - * + * * @return Returns true if the most recent counter period exceeds the * MaxPeriod value set by SetMaxPeriod. */ @@ -583,7 +541,7 @@ public class Counter extends SensorBase implements CounterBase, /** * The last direction the counter value changed. - * + * * @return The last direction the counter value changed. */ public boolean getDirection() { @@ -598,7 +556,7 @@ public class Counter extends SensorBase implements CounterBase, * Set the Counter to return reversed sensing on the direction. This allows * counters to change the direction they are counting in the case of 1X and * 2X quadrature encoding only. Any other counter mode isn't supported. - * + * * @param reverseDirection * true if the value counted should be negated. */ @@ -614,7 +572,7 @@ public class Counter extends SensorBase implements CounterBase, * Get the Period of the most recent count. Returns the time interval of the * most recent count. This can be used for velocity calculations to * determine shaft speed. - * + * * @returns The period of the last two pulses in units of seconds. */ public double getPeriod() { @@ -629,7 +587,7 @@ public class Counter extends SensorBase implements CounterBase, * Get the current rate of the Counter. Read the current rate of the counter * accounting for the distance per pulse value. The default value for * distance per pulse (1) yields units of pulses per second. - * + * * @return The rate in units/sec */ public double getRate() { @@ -641,7 +599,7 @@ public class Counter extends SensorBase implements CounterBase, * timer to average when calculating the period. Perform averaging to * account for mechanical imperfections or as oversampling to increase * resolution. - * + * * @param samplesToAverage * The number of samples to average from 1 to 127. */ @@ -662,7 +620,7 @@ public class Counter extends SensorBase implements CounterBase, * timer to average when calculating the period. Perform averaging to * account for mechanical imperfections or as oversampling to increase * resolution. - * + * * @return SamplesToAverage The number of samples being averaged (from 1 to * 127) */ @@ -680,7 +638,7 @@ public class Counter extends SensorBase implements CounterBase, * encoder. Set this value based on the Pulses per Revolution and factor in * any gearing reductions. This distance can be in any units you like, * linear or angular. - * + * * @param distancePerPulse * The scale factor that will be used to convert pulses to useful * units. @@ -692,7 +650,7 @@ public class Counter extends SensorBase implements CounterBase, /** * Set which parameter of the encoder you are using as a process control * variable. The counter class supports the rate and distance parameters. - * + * * @param pidSource * An enum to select the parameter. */ diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java index 1fbc605e64..f6bf75944e 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java @@ -34,35 +34,21 @@ public class DigitalInput extends DigitalSource implements IInputOutput, /** * Create an instance of a Digital Input class. Creates a digital input - * given a channel and uses the default module. - * + * given a channel. + * * @param channel * the port for the digital input */ public DigitalInput(int channel) { - this(getDefaultDigitalModule(), channel); - } + initDigitalPort(channel, true); - /** - * Create an instance of a Digital Input class. Creates a digital input - * given an channel and module. - * - * @param moduleNumber - * The number of the digital module to use for this input - * @param channel - * the port for the digital input - */ - public DigitalInput(int moduleNumber, int channel) { - initDigitalPort(moduleNumber, channel, true); - - UsageReporting.report(tResourceType.kResourceType_DigitalInput, - channel, moduleNumber - 1); + UsageReporting.report(tResourceType.kResourceType_DigitalInput, channel); } /** * Get the value from a digital input channel. Retrieve the value of a * single digital input channel from the FPGA. - * + * * @return the stats of the digital input */ public boolean get() { @@ -76,7 +62,7 @@ public class DigitalInput extends DigitalSource implements IInputOutput, /** * Get the channel of the digital input - * + * * @return The GPIO channel number that this object represents. */ public int getChannel() { @@ -89,7 +75,7 @@ public class DigitalInput extends DigitalSource implements IInputOutput, /** * Request interrupts asynchronously on this digital input. - * + * * @param handler * The address of the interrupt handler function of type * tInterruptHandler that will be called whenever there is an @@ -150,7 +136,7 @@ public class DigitalInput extends DigitalSource implements IInputOutput, /** * Set which edge to trigger interrupts on - * + * * @param risingEdge * true to interrupt on rising edge * @param fallingEdge diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java index ebb140bd97..9cb42d7363 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java @@ -36,29 +36,15 @@ public class DigitalOutput extends DigitalSource implements IInputOutput, /** * Create an instance of a digital output. Create an instance of a digital - * output given a module number and channel. - * - * @param moduleNumber - * The number of the digital module to use - * @param channel - * the port to use for the digital output - */ - public DigitalOutput(int moduleNumber, int channel) { - initDigitalPort(moduleNumber, channel, false); - - UsageReporting.report(tResourceType.kResourceType_DigitalOutput, - channel, moduleNumber - 1); - } - - /** - * Create an instance of a digital output. Create a digital output given a - * channel. The default module is used. - * + * output given a channel. + * * @param channel * the port to use for the digital output */ public DigitalOutput(int channel) { - this(getDefaultDigitalModule(), channel); + initDigitalPort(channel, false); + + UsageReporting.report(tResourceType.kResourceType_DigitalOutput, channel); } /** @@ -74,7 +60,7 @@ public class DigitalOutput extends DigitalSource implements IInputOutput, /** * Set the value of a digital output. - * + * * @param value * true is on, off is false */ @@ -96,7 +82,7 @@ public class DigitalOutput extends DigitalSource implements IInputOutput, /** * Generate a single pulse. Write a pulse to the specified digital output * channel. There can only be a single pulse going at any time. - * + * * @param channel * The channel to pulse. * @param pulseLength @@ -114,7 +100,7 @@ public class DigitalOutput extends DigitalSource implements IInputOutput, * @deprecated Generate a single pulse. Write a pulse to the specified * digital output channel. There can only be a single pulse * going at any time. - * + * * @param channel * The channel to pulse. * @param pulseLength @@ -134,7 +120,7 @@ public class DigitalOutput extends DigitalSource implements IInputOutput, /** * Determine if the pulse is still going. Determine if a previously started * pulse is still going. - * + * * @return true if pulsing */ public boolean isPulsing() { @@ -148,12 +134,12 @@ public class DigitalOutput extends DigitalSource implements IInputOutput, /** * Change the PWM frequency of the PWM output on a Digital Output line. - * + * * The valid range is from 0.6 Hz to 19 kHz. The frequency resolution is * logarithmic. - * + * * There is only one PWM frequency per digital module. - * + * * @param rate * The frequency to output all digital output PWM signals on this * module. @@ -162,22 +148,22 @@ public class DigitalOutput extends DigitalSource implements IInputOutput, ByteBuffer status = ByteBuffer.allocateDirect(4); // set the byte order status.order(ByteOrder.LITTLE_ENDIAN); - PWMJNI.setPWMRateWithModule((byte) m_moduleNumber, rate, + PWMJNI.setPWMRateWithModule((byte) 1, rate, status.asIntBuffer()); HALUtil.checkStatus(status.asIntBuffer()); } /** * Enable a PWM Output on this line. - * + * * Allocate one of the 4 DO PWM generator resources from this module. - * + * * Supply the initial duty-cycle to output so as to avoid a glitch when * first starting. - * + * * The resolution of the duty cycle is 8-bit for low frequencies (1kHz or * less) but is reduced the higher the frequency of the PWM signal is. - * + * * @param initialDutyCycle * The duty-cycle to start generating. [0..1] */ @@ -187,19 +173,17 @@ public class DigitalOutput extends DigitalSource implements IInputOutput, ByteBuffer status = ByteBuffer.allocateDirect(4); // set the byte order status.order(ByteOrder.LITTLE_ENDIAN); - m_pwmGenerator = PWMJNI.allocatePWMWithModule( - (byte) m_moduleNumber, status.asIntBuffer()); + m_pwmGenerator = PWMJNI.allocatePWMWithModule((byte) 1, status.asIntBuffer()); HALUtil.checkStatus(status.asIntBuffer()); PWMJNI.setPWMDutyCycle(m_pwmGenerator, initialDutyCycle, - status.asIntBuffer()); + status.asIntBuffer()); HALUtil.checkStatus(status.asIntBuffer()); - PWMJNI.setPWMOutputChannelWithModule((byte) m_moduleNumber, - m_pwmGenerator, m_channel, status.asIntBuffer()); + PWMJNI.setPWMOutputChannelWithModule((byte) 1, m_pwmGenerator, m_channel, status.asIntBuffer()); } /** * Change this line from a PWM output back to a static Digital Output line. - * + * * Free up one of the 4 DO PWM generator resources that were in use. */ public void disablePWM() { @@ -209,17 +193,16 @@ public class DigitalOutput extends DigitalSource implements IInputOutput, status.order(ByteOrder.LITTLE_ENDIAN); PWMJNI.setPWMOutputChannel(m_pwmGenerator, kDigitalChannels, status.asIntBuffer()); HALUtil.checkStatus(status.asIntBuffer()); - PWMJNI.freePWMWithModule((byte) m_moduleNumber, m_pwmGenerator, - status.asIntBuffer()); + PWMJNI.freePWMWithModule((byte) 1, m_pwmGenerator, status.asIntBuffer()); m_pwmGenerator = null; } /** * Change the duty-cycle that is being generated on the line. - * + * * The resolution of the duty cycle is 8-bit for low frequencies (1kHz or * less) but is reduced the higher the frequency of the PWM signal is. - * + * * @param dutyCycle * The duty-cycle to change to. [0..1] */ @@ -227,8 +210,7 @@ public class DigitalOutput extends DigitalSource implements IInputOutput, ByteBuffer status = ByteBuffer.allocateDirect(4); // set the byte order status.order(ByteOrder.LITTLE_ENDIAN); - PWMJNI.setPWMDutyCycleWithModule((byte) m_moduleNumber, - m_pwmGenerator, dutyCycle, status.asIntBuffer()); + PWMJNI.setPWMDutyCycleWithModule((byte) 1, m_pwmGenerator, dutyCycle, status.asIntBuffer()); HALUtil.checkStatus(status.asIntBuffer()); } diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/DigitalSource.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/DigitalSource.java index 515248b13d..b681ba4f86 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/DigitalSource.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/DigitalSource.java @@ -25,34 +25,26 @@ import edu.wpi.first.wpilibj.util.CheckedAllocationException; */ public abstract class DigitalSource extends InterruptableSensorBase { - protected static Resource channels = new Resource(kDigitalChannels - * kDigitalModules); + protected static Resource channels = new Resource(kDigitalChannels); protected ByteBuffer m_port; - protected int m_moduleNumber, m_channel; + protected int m_channel; - protected void initDigitalPort(int moduleNumber, int channel, boolean input) { + protected void initDigitalPort(int channel, boolean input) { m_channel = channel; - m_moduleNumber = moduleNumber; - if (DIOJNI.checkDigitalModule((byte) m_moduleNumber) != 1) { - throw new AllocationException("Digital input " + m_channel - + " on module " + m_moduleNumber - + " cannot be allocated. Module is not present."); - } + checkDigitalChannel(m_channel); // XXX: Replace with // HALLibrary.checkDigitalChannel when // implemented try { - channels.allocate((m_moduleNumber - 1) * kDigitalChannels - + m_channel); + channels.allocate(m_channel); } catch (CheckedAllocationException ex) { throw new AllocationException("Digital input " + m_channel - + " on module " + m_moduleNumber + " is already allocated"); + + " is already allocated"); } - ByteBuffer port_pointer = DIOJNI.getPortWithModule( - (byte) moduleNumber, (byte) channel); + ByteBuffer port_pointer = DIOJNI.getPortWithModule((byte) 1, (byte) channel); ByteBuffer status = ByteBuffer.allocateDirect(4); // set the byte order status.order(ByteOrder.LITTLE_ENDIAN); @@ -63,19 +55,18 @@ public abstract class DigitalSource extends InterruptableSensorBase { } public void free() { - channels.free(((m_moduleNumber - 1) * kDigitalChannels + m_channel)); + channels.free(m_channel); ByteBuffer status = ByteBuffer.allocateDirect(4); // set the byte order status.order(ByteOrder.LITTLE_ENDIAN); DIOJNI.freeDIO(m_port, status.asIntBuffer()); HALUtil.checkStatus(status.asIntBuffer()); m_channel = 0; - m_moduleNumber = 0; } /** * Get the channel routing number - * + * * @return channel routing number */ public int getChannelForRouting() { @@ -84,16 +75,16 @@ public abstract class DigitalSource extends InterruptableSensorBase { /** * Get the module routing number - * - * @return module routing number + * + * @return 0 */ public int getModuleForRouting() { - return m_moduleNumber - 1; + return 0; } /** * Is this an analog trigger - * + * * @return true if this is an analog trigger */ public boolean getAnalogTriggerForRouting() { diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Encoder.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Encoder.java index 433a4dda1f..253d32ec8f 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Encoder.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Encoder.java @@ -103,152 +103,11 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource, UsageReporting.report(tResourceType.kResourceType_Encoder, m_index, m_encodingType.value); - LiveWindow.addSensor("Encoder", m_aSource.getModuleForRouting(), - m_aSource.getChannelForRouting(), this); + LiveWindow.addSensor("Encoder", m_aSource.getChannelForRouting(), this); } /** - * Encoder constructor. Construct a Encoder given a and b modules and - * channels fully specified. - * - * @param aSlot - * The a channel digital input module. - * @param aChannel - * The a channel digital input channel. - * @param bSlot - * The b channel digital input module. - * @param bChannel - * The b channel digital input channel. - * @param reverseDirection - * represents the orientation of the encoder and inverts the - * output values if necessary so forward represents positive - * values. - */ - public Encoder(final int aSlot, final int aChannel, final int bSlot, - final int bChannel, boolean reverseDirection) { - m_allocatedA = true; - m_allocatedB = true; - m_allocatedI = false; - m_aSource = new DigitalInput(aSlot, aChannel); - m_bSource = new DigitalInput(bSlot, bChannel); - initEncoder(reverseDirection); - } - - /** - * Encoder constructor. Construct a Encoder given a and b modules and - * channels fully specified. - * - * @param aSlot - * The a channel digital input module. - * @param aChannel - * The a channel digital input channel. - * @param bSlot - * The b channel digital input module. - * @param bChannel - * The b channel digital input channel. - */ - public Encoder(final int aSlot, final int aChannel, final int bSlot, - final int bChannel) { - this(aSlot, aChannel, bSlot, bChannel, false); - } - - /** - * Encoder constructor. Construct a Encoder given a and b modules and - * channels fully specified. - * - * @param aSlot - * The a channel digital input module. - * @param aChannel - * The a channel digital input channel. - * @param bSlot - * The b channel digital input module. - * @param bChannel - * The b channel digital input channel. - * @param reverseDirection - * represents the orientation of the encoder and inverts the - * output values if necessary so forward represents positive - * values. - * @param encodingType - * either k1X, k2X, or k4X to indicate 1X, 2X or 4X decoding. If - * 4X is selected, then an encoder FPGA object is used and the - * returned counts will be 4x the encoder spec'd value since all - * rising and falling edges are counted. If 1X or 2X are selected - * then a counter object will be used and the returned value will - * either exactly match the spec'd count or be double (2x) the - * spec'd count. - */ - public Encoder(final int aSlot, final int aChannel, final int bSlot, - final int bChannel, boolean reverseDirection, - final EncodingType encodingType) { - m_allocatedA = true; - m_allocatedB = true; - m_allocatedI = false; - m_aSource = new DigitalInput(aSlot, aChannel); - m_bSource = new DigitalInput(bSlot, bChannel); - if (encodingType == null) - throw new NullPointerException("Given encoding type was null"); - m_encodingType = encodingType; - initEncoder(reverseDirection); - } - - /** - * Encoder constructor. Construct a Encoder given a and b modules and - * channels fully specified. Using the index pulse forces 4x encoding. - * - * @param aSlot - * The a channel digital input module. - * @param aChannel - * The a channel digital input channel. - * @param bSlot - * The b channel digital input module. - * @param bChannel - * The b channel digital input channel. - * @param indexSlot - * The index channel digital input module. - * @param indexChannel - * The index channel digital input channel. - * @param reverseDirection - * represents the orientation of the encoder and inverts the - * output values if necessary so forward represents positive - * values. - */ - public Encoder(final int aSlot, final int aChannel, final int bSlot, - final int bChannel, final int indexSlot, final int indexChannel, - boolean reverseDirection) { - m_allocatedA = true; - m_allocatedB = true; - m_allocatedI = true; - m_aSource = new DigitalInput(aSlot, aChannel); - m_bSource = new DigitalInput(bSlot, bChannel); - m_indexSource = new DigitalInput(indexSlot, indexChannel); - initEncoder(reverseDirection); - } - - /** - * Encoder constructor. Construct a Encoder given a and b modules and - * channels fully specified. Using the index pulse forces 4x encoding. - * - * @param aSlot - * The a channel digital input module. - * @param aChannel - * The a channel digital input channel. - * @param bSlot - * The b channel digital input module. - * @param bChannel - * The b channel digital input channel. - * @param indexSlot - * The index channel digital input module. - * @param indexChannel - * The index channel digital input channel. - */ - public Encoder(final int aSlot, final int aChannel, final int bSlot, - final int bChannel, final int indexSlot, final int indexChannel) { - this(aSlot, aChannel, bSlot, bChannel, indexSlot, indexChannel, false); - } - - /** - * Encoder constructor. Construct a Encoder given a and b channels assuming - * the default module. + * Encoder constructor. Construct a Encoder given a and b channels. * * @param aChannel * The a channel digital input channel. @@ -270,8 +129,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource, } /** - * Encoder constructor. Construct a Encoder given a and b channels assuming - * the default module. + * Encoder constructor. Construct a Encoder given a and b channels. * * @param aChannel * The a channel digital input channel. @@ -283,8 +141,7 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource, } /** - * Encoder constructor. Construct a Encoder given a and b channels assuming - * the default module. + * Encoder constructor. Construct a Encoder given a and b channels. * * @param aChannel * The a channel digital input channel. @@ -317,8 +174,8 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource, } /** - * Encoder constructor. Construct a Encoder given a and b channels assuming - * the default module. Using an index pulse forces 4x encoding + * Encoder constructor. Construct a Encoder given a and b channels. + * Using an index pulse forces 4x encoding * * @param aChannel * The a channel digital input channel. @@ -343,8 +200,8 @@ public class Encoder extends SensorBase implements CounterBase, PIDSource, } /** - * Encoder constructor. Construct a Encoder given a and b channels assuming - * the default module. Using an index pulse forces 4x encoding + * Encoder constructor. Construct a Encoder given a and b channels. + * Using an index pulse forces 4x encoding * * @param aChannel * The a channel digital input channel. diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/GearTooth.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/GearTooth.java index 6561c1a105..e35b04f099 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/GearTooth.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/GearTooth.java @@ -34,9 +34,18 @@ public class GearTooth extends Counter implements ISensor { /** * Construct a GearTooth sensor given a channel. * - * The default module is assumed. + * No direction sensing is assumed. * - * @param channel The GPIO channel on the digital module that the sensor is connected to. + * @param channel The GPIO channel that the sensor is connected to. + */ + public GearTooth(final int channel) { + this(channel,false); + } + + /** + * Construct a GearTooth sensor given a channel. + * + * @param channel The GPIO channel that the sensor is connected to. * @param directionSensitive Enable the pulse length decoding in hardware to specify count direction. */ public GearTooth(final int channel, boolean directionSensitive) { @@ -47,48 +56,7 @@ public class GearTooth extends Counter implements ISensor { } else { UsageReporting.report(tResourceType.kResourceType_GearTooth, channel, DigitalModule.getDefaultDigitalModule()-1); } - } - - /** - * Construct a GearTooth sensor given a channel. - * - * The default module is assumed. - * No direction sensing is assumed. - * - * @param channel The GPIO channel on the digital module that the sensor is connected to. - */ - public GearTooth(final int channel) { - this(channel,false); - } - - /** - * Construct a GearTooth sensor given a channel and module. - * - * @param slot The slot in the chassis that the digital module is plugged in to. - * @param channel The GPIO channel on the digital module that the sensor is connected to. - * @param directionSensitive Enable the pulse length decoding in hardware to specify count direction. - */ - public GearTooth(final int slot, final int channel, boolean directionSensitive) { - super(slot, channel); - enableDirectionSensing(directionSensitive); - if(directionSensitive) { - UsageReporting.report(tResourceType.kResourceType_GearTooth, channel, DigitalModule.getDefaultDigitalModule()-1, "D"); - } else { - UsageReporting.report(tResourceType.kResourceType_GearTooth, channel, DigitalModule.getDefaultDigitalModule()-1); - } - LiveWindow.addSensor("GearTooth", slot, channel, this); - } - - /** - * Construct a GearTooth sensor given a channel and module. - * - * No direction sensing is assumed. - * - * @param slot The slot in the chassis that the digital module is plugged in to. - * @param channel The GPIO channel on the digital module that the sensor is connected to. - */ - public GearTooth(final int slot, final int channel) { - this(slot, channel,false); + LiveWindow.addSensor("GearTooth", channel, this); } /** diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Gyro.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Gyro.java index 09146da366..87c6243150 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Gyro.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Gyro.java @@ -79,31 +79,13 @@ public class Gyro extends SensorBase implements PIDSource, ISensor, setPIDSourceParameter(PIDSourceParameter.kAngle); - UsageReporting.report(tResourceType.kResourceType_Gyro, - m_analog.getChannel(), m_analog.getModuleNumber() - 1); - LiveWindow.addSensor("Gyro", m_analog.getModuleNumber(), - m_analog.getChannel(), this); - } - - /** - * Gyro constructor given a slot and a channel. . - * - * @param slot - * The cRIO slot for the analog module the gyro is connected to. - * @param channel - * The analog channel the gyro is connected to. - */ - public Gyro(int slot, int channel) { - m_analog = new AnalogInput(slot, channel); - m_channelAllocated = true; - initGyro(); + UsageReporting.report(tResourceType.kResourceType_Gyro, m_analog.getChannel()); + LiveWindow.addSensor("Gyro", m_analog.getChannel(), this); } /** * Gyro constructor with only a channel. - * - * Use the default analog module slot. - * + * * @param channel * The analog channel the gyro is connected to. */ @@ -117,7 +99,7 @@ public class Gyro extends SensorBase implements PIDSource, ISensor, * Gyro constructor with a precreated analog channel object. Use this * constructor when the analog channel needs to be shared. There is no * reference counting when an AnalogChannel is passed to the gyro. - * + * * @param channel * The AnalogChannel object that the gyro is connected to. */ @@ -156,13 +138,13 @@ public class Gyro extends SensorBase implements PIDSource, ISensor, /** * Return the actual angle in degrees that the robot is currently facing. - * + * * The angle is based on the current accumulator value corrected by the * oversampling rate, the gyro type and the A/D calibration values. The * angle is continuous, that is can go beyond 360 degrees. This make * algorithms that wouldn't want to see a discontinuity in the gyro output * as it sweeps past 0 on the second time around. - * + * * @return the current heading of the robot in degrees. This heading is * based on integration of the returned rate from the gyro. */ @@ -186,9 +168,9 @@ public class Gyro extends SensorBase implements PIDSource, ISensor, /** * Return the rate of rotation of the gyro - * + * * The rate is based on the most recent reading of the gyro analog value - * + * * @return the current rate in degrees per second */ public double getRate() { @@ -206,7 +188,7 @@ public class Gyro extends SensorBase implements PIDSource, ISensor, * Set the gyro type based on the sensitivity. This takes the number of * volts/degree/second sensitivity of the gyro and uses it in subsequent * calculations to allow the code to work with multiple gyros. - * + * * @param voltsPerDegreePerSecond * The type of gyro specified as the voltage that represents one * degree/second. @@ -218,7 +200,7 @@ public class Gyro extends SensorBase implements PIDSource, ISensor, /** * Set which parameter of the encoder you are using as a process control * variable. The Gyro class supports the rate and angle parameters - * + * * @param pidSource * An enum to select the parameter. */ @@ -229,7 +211,7 @@ public class Gyro extends SensorBase implements PIDSource, ISensor, /** * Get the angle of the gyro for use with PIDControllers - * + * * @return the current angle according to the gyro */ public double pidGet() { diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/HiTechnicColorSensor.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/HiTechnicColorSensor.java index 27ddf8896e..57e9f271ff 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/HiTechnicColorSensor.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/HiTechnicColorSensor.java @@ -109,7 +109,7 @@ public class HiTechnicColorSensor extends SensorBase implements ISensor, LiveWin throw new ColorSensorException("Invalid Sensor type"); } - LiveWindow.addSensor("HiTechnicColorSensor", slot, 0, this); + LiveWindow.addSensor("HiTechnicColorSensor", slot, this); UsageReporting.report(tResourceType.kResourceType_HiTechnicColorSensor, module.getModuleNumber()-1); } diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/HiTechnicCompass.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/HiTechnicCompass.java index 9dcf636400..6fb4583f38 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/HiTechnicCompass.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/HiTechnicCompass.java @@ -53,11 +53,9 @@ public class HiTechnicCompass extends SensorBase implements ISensor, LiveWindowS /** * Constructor. - * - * @param slot The slot of the digital module that the sensor is plugged into. */ - public HiTechnicCompass(int slot) { - DigitalModule module = DigitalModule.getInstance(slot); + public HiTechnicCompass() { + DigitalModule module = DigitalModule.getInstance(1); m_i2c = module.getI2C(kAddress); // Verify Sensor @@ -70,8 +68,8 @@ public class HiTechnicCompass extends SensorBase implements ISensor, LiveWindowS throw new CompassException("Invalid Sensor type"); } - UsageReporting.report(tResourceType.kResourceType_HiTechnicCompass, module.getModuleNumber()-1); - LiveWindow.addSensor("HiTechnicCompass", slot, 0, this); + UsageReporting.report(tResourceType.kResourceType_HiTechnicCompass, 1); + LiveWindow.addSensor("HiTechnicCompass", 1, this); } /** diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/I2C.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/I2C.java index 31899fdbf5..6f93062851 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/I2C.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/I2C.java @@ -18,10 +18,10 @@ import edu.wpi.first.wpilibj.util.BoundaryException; /** * I2C bus interface class. - * + * * This class is intended to be used by sensor (and other I2C device) drivers. * It probably should not be used directly. - * + * * It is constructed by calling DigitalModule::GetI2C() on a DigitalModule * object. */ @@ -31,25 +31,24 @@ public class I2C extends SensorBase { private int m_deviceAddress; private boolean m_compatibilityMode; - /** - * Constructor. - * - * @param module - * The Digital Module to which the device is connected. - * @param deviceAddress - * The address of the device on the I2C bus. - */ - public I2C(DigitalModule module, int deviceAddress) { - if (module == null) { - throw new NullPointerException("Digital Module given was null"); - } - m_module = module; - m_deviceAddress = deviceAddress; - m_compatibilityMode = true; + /** + * Constructor. + * + * @param module + * The Digital Module to which the device is connected. + * @param deviceAddress + * The address of the device on the I2C bus. + */ + public I2C(DigitalModule module, int deviceAddress) { + if (module == null) { + throw new NullPointerException("Digital Module given was null"); + } + m_module = module; + m_deviceAddress = deviceAddress; + m_compatibilityMode = true; - UsageReporting.report(tResourceType.kResourceType_I2C, deviceAddress, - module.getModuleNumber()-1); - } + UsageReporting.report(tResourceType.kResourceType_I2C, deviceAddress); + } /** * Destructor. @@ -59,10 +58,10 @@ public class I2C extends SensorBase { /** * Generic transaction. - * + * * This is a lower-level interface to the I2C hardware giving you more * control over each transaction. - * + * * @param dataToSend * Buffer of data to send as part of the transaction. * @param sendSize @@ -105,10 +104,10 @@ public class I2C extends SensorBase { /** * Attempt to address a device on the I2C bus. - * + * * This allows you to figure out if there is a device on the I2C bus that * responds to the address specified in the constructor. - * + * * @return Transfer Aborted... false for success, true for aborted. */ public boolean addressOnly() { @@ -117,10 +116,10 @@ public class I2C extends SensorBase { /** * Execute a write transaction with the device. - * + * * Write a single byte to a register on a device and wait until the * transaction is complete. - * + * * @param registerAddress * The address of the register on the device to be written. * @param data @@ -135,11 +134,11 @@ public class I2C extends SensorBase { /** * Execute a read transaction with the device. - * + * * Read 1 to 7 bytes from a device. Most I2C devices will auto-increment the * register pointer internally allowing you to read up to 7 consecutive * registers on a device in a single transaction. - * + * * @param registerAddress * The register to read first in the transaction. * @param count @@ -163,9 +162,9 @@ public class I2C extends SensorBase { /** * Send a broadcast write to all devices on the I2C bus. - * + * * This is not currently implemented! - * + * * @param registerAddress * The register to write on all devices on the bus. * @param data @@ -176,30 +175,30 @@ public class I2C extends SensorBase { /** * SetCompatabilityMode - * + * * Enables bitwise clock skewing detection. This will reduce the I2C * interface speed, but will allow you to communicate with devices that skew * the clock at abnormal times. Compatability mode is enabled by default. - * + * * @param enable * Enable compatability mode for this sensor or not. */ public void setCompatabilityMode(boolean enable) { m_compatibilityMode = enable; UsageReporting.report(tResourceType.kResourceType_I2C, - m_deviceAddress, m_module.getModuleNumber() - 1, "C"); + m_deviceAddress, 1, "C"); } /** * Verify that a device's registers contain expected values. - * + * * Most devices will have a set of registers that contain a known value that * can be used to identify them. This allows an I2C device driver to easily * verify that the device contains the expected value. - * + * * @pre The device must support and be configured to use register * auto-increment. - * + * * @param registerAddress * The base register to start reading from the device. * @param count diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Jaguar.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Jaguar.java index adc616e5f5..de56ced645 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Jaguar.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Jaguar.java @@ -34,31 +34,20 @@ public class Jaguar extends SafePWM implements SpeedController, IDeviceControlle setPeriodMultiplier(PeriodMultiplier.k1X); setRaw(m_centerPwm); - UsageReporting.report(tResourceType.kResourceType_Jaguar, getChannel(), getModuleNumber()-1); - LiveWindow.addActuator("Jaguar", getModuleNumber(), getChannel(), this); + UsageReporting.report(tResourceType.kResourceType_Jaguar, getChannel()); + LiveWindow.addActuator("Jaguar", getChannel(), this); } /** - * Constructor that assumes the default digital module. + * Constructor. * - * @param channel The PWM channel on the digital module that the Jaguar is attached to. + * @param channel The PWM channel that the Jaguar is attached to. */ public Jaguar(final int channel) { super(channel); initJaguar(); } - /** - * Constructor that specifies the digital module. - * - * @param slot The slot in the chassis that the digital module is plugged into. - * @param channel The PWM channel on the digital module that the Jaguar is attached to. - */ - public Jaguar(final int slot, final int channel) { - super(slot, channel); - initJaguar(); - } - /** * Set the PWM value. * diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/PWM.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/PWM.java index 84e9fce0dc..44539f13fc 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/PWM.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/PWM.java @@ -38,7 +38,7 @@ public class PWM extends SensorBase implements LiveWindowSendable { * resource tracking into the HAL. This will wait until we get the unit * tests running for the first time. */ - + private static Resource allocated = new Resource( kPwmChannels); /** @@ -106,49 +106,35 @@ public class PWM extends SensorBase implements LiveWindowSendable { int m_minPwm; /** - * Initialize PWMs given an module and channel. + * Initialize PWMs given a channel. * * This method is private and is the common path for all the constructors for creating PWM * instances. Checks module and channel value ranges and allocates the appropriate channel. * The allocation is only done to help users ensure that they don't double assign channels. */ - private void initPWM(final int moduleNumber, final int channel) { - checkPWMModule(moduleNumber); + private void initPWM(final int channel) { checkPWMChannel(channel); try { - allocated.allocate((moduleNumber - 1) * kPwmChannels + channel); + allocated.allocate(channel); } catch (CheckedAllocationException e) { throw new AllocationException( - "PWM channel " + channel + " on module " + moduleNumber + " is already allocated"); + "PWM channel " + channel + " is already allocated"); } m_channel = channel; - m_module = DigitalModule.getInstance(moduleNumber); + m_module = DigitalModule.getInstance(1); m_module.setPWM(m_channel, kPwmDisabled); m_eliminateDeadband = false; - UsageReporting.report(tResourceType.kResourceType_PWM, channel, moduleNumber-1); + UsageReporting.report(tResourceType.kResourceType_PWM, channel); } /** - * Allocate a PWM given a module and channel. - * Allocate a PWM using a module and channel number. + * Allocate a PWM given a channel. * - * @param moduleNumber The module number of the digital module to use. - * @param channel The PWM channel on the digital module. - */ - public PWM(final int moduleNumber, final int channel) { - initPWM(moduleNumber, channel); - } - - /** - * Allocate a PWM in the default module given a channel. - * - * Using a default module allocate a PWM given the channel number. - * - * @param channel The PWM channel on the digital module. + * @param channel The PWM channel. */ public PWM(final int channel) { - initPWM(getDefaultDigitalModule(), channel); + initPWM(channel); } /** @@ -159,7 +145,7 @@ public class PWM extends SensorBase implements LiveWindowSendable { public void free() { m_module.setPWM(m_channel, kPwmDisabled); m_module.freeDIO(m_channel); - allocated.free((m_module.getModuleNumber() - 1) * kPwmChannels + m_channel); + allocated.free(m_channel); } /** @@ -211,15 +197,6 @@ public class PWM extends SensorBase implements LiveWindowSendable { m_minPwm = (int)((min-kDefaultPwmCenter)/loopTime+kDefaultPwmStepsDown-1); } - /** - * Gets the module number associated with the PWM Object. - * - * @return The module's number. - */ - public int getModuleNumber() { - return m_module.getModuleNumber(); - } - /** * Gets the channel number associated with the PWM Object. * diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Relay.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Relay.java index 880bc05ce8..fa8d0fd652 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Relay.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Relay.java @@ -30,13 +30,6 @@ import edu.wpi.first.wpilibj.util.CheckedAllocationException; */ public class Relay extends SensorBase implements IDeviceController, LiveWindowSendable { - - /* - * XXX: Refactor to no longer depend on the DigitalModule, and move all - * resource tracking into the HAL. This will wait until we get the unit - * tests running for the first time. - */ - /** * This class represents errors in trying to set relay values contradictory * to the direction to which the relay is set. @@ -45,7 +38,7 @@ public class Relay extends SensorBase implements IDeviceController, /** * Create a new exception with the given message - * + * * @param message * the message to pass with the exception */ @@ -128,62 +121,34 @@ public class Relay extends SensorBase implements IDeviceController, * Common relay initialization method. This code is common to all Relay * constructors and initializes the relay and reserves all resources that * need to be locked. Initially the relay is set to both lines at 0v. - * - * @param moduleNumber - * The number of the digital module to use. */ - private void initRelay(final int moduleNumber) { - SensorBase.checkRelayModule(moduleNumber); + private void initRelay() { SensorBase.checkRelayChannel(m_channel); try { if (m_direction == Direction.kBoth || m_direction == Direction.kForward) { - relayChannels.allocate(((moduleNumber - 1) * kRelayChannels - + m_channel) * 2); - UsageReporting.report(tResourceType.kResourceType_Relay, - m_channel, moduleNumber - 1); + relayChannels.allocate(m_channel * 2); + UsageReporting.report(tResourceType.kResourceType_Relay, m_channel); } if (m_direction == Direction.kBoth || m_direction == Direction.kReverse) { - relayChannels.allocate(((moduleNumber - 1) * kRelayChannels - + m_channel) * 2 + 1); - UsageReporting.report(tResourceType.kResourceType_Relay, - m_channel + 128, moduleNumber - 1); + relayChannels.allocate(m_channel * 2 + 1); + UsageReporting.report(tResourceType.kResourceType_Relay, m_channel + 128); } } catch (CheckedAllocationException e) { - throw new AllocationException("Relay channel " + m_channel - + " on module " + moduleNumber + " is already allocated"); + throw new AllocationException("Relay channel " + m_channel + " is already allocated"); } - m_module = DigitalModule.getInstance(moduleNumber); + m_module = DigitalModule.getInstance(1); m_module.setRelayForward(m_channel, false); m_module.setRelayReverse(m_channel, false); - LiveWindow.addActuator("Relay", moduleNumber, m_channel, this); + LiveWindow.addActuator("Relay", m_channel, this); } /** - * Relay constructor given the module and the channel. - * - * @param moduleNumber - * The number of the digital module to use. + * Relay constructor given a channel. + * * @param channel - * The channel number within the module for this relay. - * @param direction - * The direction that the Relay object will control. - */ - public Relay(final int moduleNumber, final int channel, Direction direction) { - if (direction == null) - throw new NullPointerException("Null Direction was given"); - m_channel = channel; - m_direction = direction; - initRelay(moduleNumber); - } - - /** - * Relay constructor given a channel only where the default digital module - * is used. - * - * @param channel - * The channel number within the default module for this relay. + * The channel number for this relay. * @param direction * The direction that the Relay object will control. */ @@ -192,35 +157,19 @@ public class Relay extends SensorBase implements IDeviceController, throw new NullPointerException("Null Direction was given"); m_channel = channel; m_direction = direction; - initRelay(getDefaultDigitalModule()); + initRelay(); } /** - * Relay constructor given the module and the channel, allowing both - * directions. - * - * @param moduleNumber - * The number of the digital module to use. + * Relay constructor given a channel, allowing both directions. + * * @param channel - * The channel number within the module for this relay. - */ - public Relay(final int moduleNumber, final int channel) { - m_channel = channel; - m_direction = Direction.kBoth; - initRelay(moduleNumber); - } - - /** - * Relay constructor given a channel only where the default digital module - * is used, allowing both directions. - * - * @param channel - * The channel number within the default module for this relay. + * The channel number for this relay. */ public Relay(final int channel) { m_channel = channel; m_direction = Direction.kBoth; - initRelay(getDefaultDigitalModule()); + initRelay(); } public void free() { @@ -243,17 +192,17 @@ public class Relay extends SensorBase implements IDeviceController, /** * Set the relay state. - * + * * Valid values depend on which directions of the relay are controlled by * the object. - * + * * When set to kBothDirections, the relay can be set to any of the four * states: 0v-0v, 12v-0v, 0v-12v, 12v-12v - * + * * When set to kForwardOnly or kReverseOnly, you can specify the constant * for the direction or you can simply specify kOff_val and kOn_val. Using * only kOff_val and kOn_val is recommended. - * + * * @param value * The state to set the relay. */ @@ -310,12 +259,12 @@ public class Relay extends SensorBase implements IDeviceController, /** * Get the Relay State - * + * * Gets the current state of the relay. - * + * * When set to kForwardOnly or kReverseOnly, value is returned as kOn/kOff * not kForward/kReverse (per the recommendation in Set) - * + * * @return The current state of the relay as a Relay::Value */ public Value get() { @@ -344,12 +293,12 @@ public class Relay extends SensorBase implements IDeviceController, /** * Set the Relay Direction - * + * * Changes which values the relay can be set to depending on which direction * is used - * + * * Valid inputs are kBothDirections, kForwardOnly, and kReverseOnly - * + * * @param direction * The direction for the relay to operate in */ @@ -364,7 +313,7 @@ public class Relay extends SensorBase implements IDeviceController, m_direction = direction; - initRelay(m_module.getModuleNumber()); + initRelay(); } /* diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/RobotDrive.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/RobotDrive.java index 9da30419ce..f12343cc36 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/RobotDrive.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/RobotDrive.java @@ -82,8 +82,8 @@ public class RobotDrive implements MotorSafety, IUtility { * Set up parameters for a two wheel drive system where the * left and right motor pwm channels are specified in the call. * This call assumes Jaguars for controlling the motors. - * @param leftMotorChannel The PWM channel number on the default digital module that drives the left motor. - * @param rightMotorChannel The PWM channel number on the default digital module that drives the right motor. + * @param leftMotorChannel The PWM channel number that drives the left motor. + * @param rightMotorChannel The PWM channel number that drives the right motor. */ public RobotDrive(final int leftMotorChannel, final int rightMotorChannel) { m_sensitivity = kDefaultSensitivity; @@ -105,10 +105,10 @@ public class RobotDrive implements MotorSafety, IUtility { * Set up parameters for a four wheel drive system where all four motor * pwm channels are specified in the call. * This call assumes Jaguars for controlling the motors. - * @param frontLeftMotor Front left motor channel number on the default digital module - * @param rearLeftMotor Rear Left motor channel number on the default digital module - * @param frontRightMotor Front right motor channel number on the default digital module - * @param rearRightMotor Rear Right motor channel number on the default digital module + * @param frontLeftMotor Front left motor channel number + * @param rearLeftMotor Rear Left motor channel number + * @param frontRightMotor Front right motor channel number + * @param rearRightMotor Rear Right motor channel number */ public RobotDrive(final int frontLeftMotor, final int rearLeftMotor, final int frontRightMotor, final int rearRightMotor) { diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/SafePWM.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/SafePWM.java index 73573b6204..be0bebc050 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/SafePWM.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/SafePWM.java @@ -34,16 +34,6 @@ public class SafePWM extends PWM implements MotorSafety { initSafePWM(); } - /** - * Constructor for a SafePWM object taking channel and slot numbers. - * @param slot The slot number of the digital module for this PWM object - * @param channel The channel number in the module for this PWM object - */ - public SafePWM(final int slot, final int channel) { - super(slot, channel); - initSafePWM(); - } - /* * Set the expiration time for the PWM object * @param timeout The timeout (in seconds) for this motor object @@ -100,7 +90,7 @@ public class SafePWM extends PWM implements MotorSafety { } public String getDescription() { - return "PWM "+getChannel()+" on module "+getModuleNumber(); + return "PWM "+getChannel(); } public void disable() { diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Servo.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Servo.java index f3651b10d6..ed3b22ad41 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Servo.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Servo.java @@ -24,7 +24,7 @@ public class Servo extends PWM implements IDevice { private static final double kMaxServoAngle = 180.0; private static final double kMinServoAngle = 0.0; - + private static final double kDefaultMaxServoPWM = 2.4; private static final double kDefaultMinServoPWM = .6; @@ -33,43 +33,29 @@ public class Servo extends PWM implements IDevice { * * InitServo() assigns defaults for the period multiplier for the servo PWM control signal, as * well as the minimum and maximum PWM values supported by the servo. - * + * */ private void initServo() { setBounds(kDefaultMaxServoPWM, 0, 0, 0, kDefaultMinServoPWM); setPeriodMultiplier(PeriodMultiplier.k4X); - LiveWindow.addActuator("Servo", getModuleNumber(), getChannel(), this); - UsageReporting.report(tResourceType.kResourceType_Servo, getChannel(), getModuleNumber()-1); + LiveWindow.addActuator("Servo", getChannel(), this); + UsageReporting.report(tResourceType.kResourceType_Servo, getChannel()); } /** - * Constructor that assumes the default digital module.
- * + * Constructor.
+ * * By default {@value #kDefaultMaxServoPWM} ms is used as the maxPWM value
* By default {@value #kDefaultMinServoPWM} ms is used as the minPWM value
* - * @param channel The PWM channel on the digital module to which the servo is attached. + * @param channel The PWM channel to which the servo is attached. */ public Servo(final int channel) { super(channel); initServo(); } - /** - * Constructor that specifies the digital module.
- * - * By default {@value #kDefaultMaxServoPWM} ms is used as the maxPWM value
- * By default {@value #kDefaultMinServoPWM} ms is used as the minPWM value
- * - * @param slot The slot in the chassis that the digital module is plugged into. - * @param channel The PWM channel on the digital module to which the servo is attached. - */ - public Servo(final int slot, final int channel) { - super(slot, channel); - initServo(); - } - /** * Set the servo position. diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Talon.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Talon.java index 00c5e2953a..3538ac4945 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Talon.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Talon.java @@ -36,31 +36,20 @@ public class Talon extends SafePWM implements SpeedController, IDeviceController setPeriodMultiplier(PeriodMultiplier.k2X); setRaw(m_centerPwm); - LiveWindow.addActuator("Talon", getModuleNumber(), getChannel(), this); - UsageReporting.report(tResourceType.kResourceType_Talon, getChannel(), getModuleNumber()-1); + LiveWindow.addActuator("Talon", getChannel(), this); + UsageReporting.report(tResourceType.kResourceType_Talon, getChannel()); } /** - * Constructor that assumes the default digital module. + * Constructor. * - * @param channel The PWM channel on the digital module that the Victor is attached to. + * @param channel The PWM channel that the Victor is attached to. */ public Talon(final int channel) { super(channel); initTalon(); } - /** - * Constructor that specifies the digital module. - * - * @param slot The slot in the chassis that the digital module is plugged into. - * @param channel The PWM channel on the digital module that the Victor is attached to. - */ - public Talon(final int slot, final int channel) { - super(slot, channel); - initTalon(); - } - /** * Set the PWM value. * diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java index 632e6d26e3..110c261237 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java @@ -78,7 +78,7 @@ public class Ultrasonic extends SensorBase implements PIDSource, ISensor, * Background task that goes through the list of ultrasonic sensors and * pings each one in turn. The counter is configured to read the timing of * the returned echo pulse. - * + * * DANGER WILL ROBINSON, DANGER WILL ROBINSON: This code runs as a task and * assumes that none of the ultrasonic sensors will change while it's * running. If one does, then this will certainly break. Make sure to @@ -133,16 +133,14 @@ public class Ultrasonic extends SensorBase implements PIDSource, ISensor, m_instances++; UsageReporting.report(tResourceType.kResourceType_Ultrasonic, m_instances); - LiveWindow.addSensor("Ultrasonic", m_echoChannel.getModuleForRouting(), - m_echoChannel.getChannel(), this); + LiveWindow.addSensor("Ultrasonic", m_echoChannel.getChannel(), this); } /** - * Create an instance of the Ultrasonic Sensor using the default module. + * Create an instance of the Ultrasonic Sensor. * This is designed to supchannel the Daventech SRF04 and Vex ultrasonic - * sensors. This constructor assumes that both digital I/O channels are in - * the default digital module. - * + * sensors. + * * @param pingChannel * The digital output channel that sends the pulse to initiate * the sensor sending the ping. @@ -162,11 +160,11 @@ public class Ultrasonic extends SensorBase implements PIDSource, ISensor, } /** - * Create an instance of the Ultrasonic Sensor using the default module. + * Create an instance of the Ultrasonic Sensor. * This is designed to supchannel the Daventech SRF04 and Vex ultrasonic * sensors. This constructor assumes that both digital I/O channels are in * the default digital module. Default unit is inches. - * + * * @param pingChannel * The digital output channel that sends the pulse to initiate * the sensor sending the ping. @@ -182,7 +180,7 @@ public class Ultrasonic extends SensorBase implements PIDSource, ISensor, /** * Create an instance of an Ultrasonic Sensor from a DigitalInput for the * echo channel and a DigitalOutput for the ping channel. - * + * * @param pingChannel * The digital output object that starts the sensor doing a ping. * Requires a 10uS pulse to start. @@ -208,7 +206,7 @@ public class Ultrasonic extends SensorBase implements PIDSource, ISensor, * Create an instance of an Ultrasonic Sensor from a DigitalInput for the * echo channel and a DigitalOutput for the ping channel. Default unit is * inches. - * + * * @param pingChannel * The digital output object that starts the sensor doing a ping. * Requires a 10uS pulse to start. @@ -220,58 +218,6 @@ public class Ultrasonic extends SensorBase implements PIDSource, ISensor, this(pingChannel, echoChannel, Unit.kInches); } - /** - * Create an instance of the Ultrasonic sensor using specified modules. This - * is designed to supchannel the Daventech SRF04 and Vex ultrasonic sensors. - * This constructors takes the channel and module slot for each of the - * required digital I/O channels. - * - * @param pingSlot - * The digital module that the pingChannel is in. - * @param pingChannel - * The digital output channel that sends the pulse to initiate - * the sensor sending the ping. - * @param echoSlot - * The digital module that the echoChannel is in. - * @param echoChannel - * The digital input channel that receives the echo. The length - * of time that the echo is high represents the round trip time - * of the ping, and the distance. - * @param units - * The units returned in either kInches or kMilliMeters - */ - public Ultrasonic(final int pingSlot, final int pingChannel, - final int echoSlot, final int echoChannel, Unit units) { - m_pingChannel = new DigitalOutput(pingSlot, pingChannel); - m_echoChannel = new DigitalInput(echoSlot, echoChannel); - m_allocatedChannels = true; - m_units = units; - initialize(); - } - - /** - * Create an instance of the Ultrasonic sensor using specified modules. This - * is designed to supchannel the Daventech SRF04 and Vex ultrasonic sensors. - * This constructors takes the channel and module slot for each of the - * required digital I/O channels. Defualt unit is inches. - * - * @param pingSlot - * The digital module that the pingChannel is in. - * @param pingChannel - * The digital output channel that sends the pulse to initiate - * the sensor sending the ping. - * @param echoSlot - * The digital module that the echoChannel is in. - * @param echoChannel - * The digital input channel that receives the echo. The length - * of time that the echo is high represents the round trip time - * of the ping, and the distance. - */ - public Ultrasonic(final int pingSlot, final int pingChannel, - final int echoSlot, final int echoChannel) { - this(pingSlot, pingChannel, echoSlot, echoChannel, Unit.kInches); - } - /** * Destructor for the ultrasonic sensor. Delete the instance of the * ultrasonic sensor by freeing the allocated digital channels. If the @@ -320,7 +266,7 @@ public class Ultrasonic extends SensorBase implements PIDSource, ISensor, /** * Turn Automatic mode on/off. When in Automatic mode, all sensors will fire * in round robin, waiting a set time between each sensor. - * + * * @param enabling * Set to true if round robin scheduling should start for all the * ultrasonic sensors. This scheduling method assures that the @@ -385,7 +331,7 @@ public class Ultrasonic extends SensorBase implements PIDSource, ISensor, * in a counter that will increment on each edge of the echo (return) * signal. If the count is not at least 2, then the range has not yet been * measured, and is invalid. - * + * * @return true if the range is valid */ public boolean isRangeValid() { @@ -394,7 +340,7 @@ public class Ultrasonic extends SensorBase implements PIDSource, ISensor, /** * Get the range in inches from the ultrasonic sensor. - * + * * @return double Range in inches of the target returned from the ultrasonic * sensor. If there is no valid value yet, i.e. at least one * measurement hasn't completed, then return 0. @@ -409,7 +355,7 @@ public class Ultrasonic extends SensorBase implements PIDSource, ISensor, /** * Get the range in millimeters from the ultrasonic sensor. - * + * * @return double Range in millimeters of the target returned by the * ultrasonic sensor. If there is no valid value yet, i.e. at least * one measurement hasn't complted, then return 0. @@ -420,7 +366,7 @@ public class Ultrasonic extends SensorBase implements PIDSource, ISensor, /** * Get the range in the current DistanceUnit for the PIDSource base object. - * + * * @return The range in DistanceUnit */ public double pidGet() { @@ -437,7 +383,7 @@ public class Ultrasonic extends SensorBase implements PIDSource, ISensor, /** * Set the current DistanceUnit that should be used for the PIDSource base * object. - * + * * @param units * The DistanceUnit that should be used. */ @@ -447,7 +393,7 @@ public class Ultrasonic extends SensorBase implements PIDSource, ISensor, /** * Get the current DistanceUnit that is used for the PIDSource base object. - * + * * @return The type of DistanceUnit that is being used. */ public Unit getDistanceUnits() { @@ -456,7 +402,7 @@ public class Ultrasonic extends SensorBase implements PIDSource, ISensor, /** * Is the ultrasonic enabled - * + * * @return true if the ultrasonic is enabled */ public boolean isEnabled() { @@ -465,7 +411,7 @@ public class Ultrasonic extends SensorBase implements PIDSource, ISensor, /** * Set if the ultrasonic is enabled - * + * * @param enable * set to true to enable the ultrasonic */ diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Victor.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Victor.java index 04b3f6a8e3..9d3fcc51e7 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Victor.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/Victor.java @@ -38,31 +38,20 @@ public class Victor extends SafePWM implements SpeedController, IDeviceControlle setPeriodMultiplier(PeriodMultiplier.k2X); setRaw(m_centerPwm); - LiveWindow.addActuator("Victor", getModuleNumber(), getChannel(), this); - UsageReporting.report(tResourceType.kResourceType_Victor, getChannel(), getModuleNumber()-1); + LiveWindow.addActuator("Victor", getChannel(), this); + UsageReporting.report(tResourceType.kResourceType_Victor, getChannel()); } /** - * Constructor that assumes the default digital module. + * Constructor. * - * @param channel The PWM channel on the digital module that the Victor is attached to. + * @param channel The PWM channel that the Victor is attached to. */ public Victor(final int channel) { super(channel); initVictor(); } - /** - * Constructor that specifies the digital module. - * - * @param slot The slot in the chassis that the digital module is plugged into. - * @param channel The PWM channel on the digital module that the Victor is attached to. - */ - public Victor(final int slot, final int channel) { - super(slot, channel); - initVictor(); - } - /** * Set the PWM value. * diff --git a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java index 47e5b2dbea..90ed3a8a14 100644 --- a/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java +++ b/wpilibj/wpilibJava/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java @@ -169,24 +169,38 @@ public class LiveWindow { } /** - * Add Sensor to LiveWindow. The components are shown with the module type, - * slot and channel like this: Gyro[1, 2] for a gyro object connected to the - * first analog module in channel 2 + * Add Sensor to LiveWindow. The components are shown with the type and + * channel like this: Gyro[1] for a gyro object connected to the first + * analog channel. * * @param moduleType A string indicating the type of the module used in the * naming (above) - * @param moduleNumber The number of the particular module type * @param channel The channel number the device is connected to * @param component A reference to the object being added */ - public static void addSensor(String moduleType, int moduleNumber, int channel, LiveWindowSendable component) { - addSensor("Ungrouped", moduleType + "[" + moduleNumber + "," + channel + "]", component); + public static void addSensor(String moduleType, int channel, LiveWindowSendable component) { + addSensor("Ungrouped", moduleType + "[" + channel + "]", component); if (sensors.contains(component)) { sensors.removeElement(component); } sensors.addElement(component); } + /** + * Add Actuator to LiveWindow. The components are shown with the module + * type, slot and channel like this: Servo[1,2] for a servo object connected + * to the first digital module and PWM port 2. + * + * @param moduleType A string that defines the module name in the label for + * the value + * @param channel The channel number the device is plugged into (usually + * PWM) + * @param component The reference to the object being added + */ + public static void addActuator(String moduleType, int channel, LiveWindowSendable component) { + addActuator("Ungrouped", moduleType + "[" + channel + "]", component); + } + /** * Add Actuator to LiveWindow. The components are shown with the module * type, slot and channel like this: Servo[1,2] for a servo object connected diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java index 1f375d84f6..fe2120fee1 100644 --- a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java +++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java @@ -19,7 +19,7 @@ import edu.wpi.first.wpilibj.test.TestBench; * Designed to allow the user to easily setup and tear down the fixture to allow for reuse. * This class should be explicitly instantiated in the TestBed class to allow any test to access this fixture. * This allows tests to be mailable so that you can easily reconfigure the physical testbed without breaking the tests. - * + * * @author Jonathan Leitschuh * */ @@ -31,7 +31,7 @@ public abstract class MotorEncoderFixture implements ITestFixture { private Counter counters[] = new Counter[2]; protected DigitalInput aSource; //Stored so it can be freed at tear down protected DigitalInput bSource; - + /** * Default constructor for a MotorEncoderFixture * @param motor The SpeedControler for this MotorEncoder pair @@ -40,10 +40,10 @@ public abstract class MotorEncoderFixture implements ITestFixture { */ public MotorEncoderFixture(){ } - + /** * Where the implementer of this class should pass the speed controller - * Constructor should only be called from outside this class if the Speed controller + * Constructor should only be called from outside this class if the Speed controller * is not also an implementation of PWM interface * @return */ @@ -60,14 +60,14 @@ public abstract class MotorEncoderFixture implements ITestFixture { * @return Input B to be used when this class is instantiated */ abstract protected DigitalInput giveDigitalInputB(); - + final private void initialize(){ if(!initialized){ aSource = giveDigitalInputA(); bSource = giveDigitalInputB(); - + motor = giveSpeedController(); - + encoder = new Encoder(aSource, bSource); counters[0] = new Counter(aSource); counters[1] = new Counter(bSource); @@ -77,14 +77,14 @@ public abstract class MotorEncoderFixture implements ITestFixture { initialized = true; } } - + @Override public boolean setup() { initialize(); encoder.start(); return true; } - + /** * Gets the motor for this Object * @return the motor this object refers too @@ -93,7 +93,7 @@ public abstract class MotorEncoderFixture implements ITestFixture { initialize(); return motor; } - + /** * Gets the encoder for this object * @return the encoder that this object refers too @@ -102,12 +102,12 @@ public abstract class MotorEncoderFixture implements ITestFixture { initialize(); return encoder; } - + public Counter[] getCounters(){ initialize(); return counters; } - + /** * Retrieves the name of the motor that this object refers to * @return The simple name of the motor {@link Class#getSimpleName()} @@ -116,42 +116,42 @@ public abstract class MotorEncoderFixture implements ITestFixture { initialize(); return motor.getClass().getSimpleName(); } - + /** * Checks to see if the speed of the motor is within some range of a given value. * This is used instead of equals() because doubles can have inaccuracies. * @param value The value to compare against * @param acuracy The accuracy range to check against to see if the - * @return true if the range of values between motors speed ± accuracy contains the 'value'
+ * @return true if the range of values between motors speed accuracy contains the 'value'
* {@code Math.abs((Math.abs(motor.get()) - Math.abs(value))) < Math.abs(accuracy)} */ public boolean isMotorSpeedWithinRange(double value, double accuracy){ initialize(); return Math.abs((Math.abs(motor.get()) - Math.abs(value))) < Math.abs(accuracy); } - + @Override public boolean reset(){ initialize(); boolean wasReset = true; - + motor.set(0); Timer.delay(TestBench.MOTOR_STOP_TIME); //DEFINED IN THE TestBench encoder.reset(); for(Counter c : counters){ c.reset(); } - + wasReset = wasReset && motor.get() == 0; wasReset = wasReset && encoder.get() == 0; for(Counter c : counters){ wasReset = wasReset && c.get() == 0; } - + return wasReset; } - + @Override public boolean teardown() { @@ -168,7 +168,7 @@ public abstract class MotorEncoderFixture implements ITestFixture { counters[0] = null; counters[1].free(); counters[1] = null; - + aSource.free(); aSource = null; bSource.free(); @@ -177,7 +177,7 @@ public abstract class MotorEncoderFixture implements ITestFixture { } else { throw new RuntimeException(type + " Motor Encoder torn down multiple times"); } - + return true; } diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java index 19311afa5c..1d82f1512b 100644 --- a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java +++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java @@ -53,7 +53,7 @@ public class FakeCounterSource } } } - + /** * Create a fake encoder on a given port * @param output the port to output the given signal to @@ -76,18 +76,6 @@ public class FakeCounterSource initEncoder(); } - /** - * Create a new fake encoder on the indicated slot and port - * @param slot Slot to create on - * @param port THe port that the encoder is supposably on - */ - public FakeCounterSource(int slot, int port) - { - m_output = new DigitalOutput(slot, port); - m_allocated = true; - initEncoder(); - } - /** * Destroy Object with minimum memory leak */ @@ -162,4 +150,3 @@ public class FakeCounterSource m_mSec = mSec; } } - diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java index 0ca000f791..409d33e72e 100644 --- a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java +++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java @@ -74,14 +74,6 @@ public class FakeEncoderSource } } - public FakeEncoderSource(int slotA, int portA, int slotB, int portB) - { - m_outputA = new DigitalOutput(slotA, portA); - m_outputB = new DigitalOutput(slotB, portB); - allocatedOutputs = true; - initQuadEncoder(); - } - public FakeEncoderSource(int portA, int portB) { m_outputA = new DigitalOutput(portA); diff --git a/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/AnalogChannel.java b/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/AnalogChannel.java index 44608bbed8..de019a30f3 100644 --- a/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/AnalogChannel.java +++ b/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/AnalogChannel.java @@ -22,17 +22,17 @@ public class AnalogChannel extends SensorBase implements PIDSource, /** * Construct an analog channel on the default module. - * + * * @param channel * The channel number to represent. */ public AnalogChannel(final int channel) { - this(getDefaultAnalogModule(), channel); + this(1, channel); } /** * Construct an analog channel on a specified module. - * + * * @param moduleNumber * The digital module to use (1 or 2). * @param channel @@ -58,7 +58,7 @@ public class AnalogChannel extends SensorBase implements PIDSource, * Get a scaled sample straight from this channel on the module. The value * is scaled to units of Volts using the calibrated scaling data from * getLSBWeight() and getOffset(). - * + * * @return A scaled sample straight from this channel on the module. */ public double getVoltage() { @@ -72,7 +72,7 @@ public class AnalogChannel extends SensorBase implements PIDSource, * oversampling will cause this value to be higher resolution, but it will * update more slowly. Using averaging will cause this value to be more * stable, but it will update more slowly. - * + * * @return A scaled sample from the output of the oversample and average * engine for this channel. */ @@ -82,7 +82,7 @@ public class AnalogChannel extends SensorBase implements PIDSource, /** * Get the channel number. - * + * * @return The channel number. */ public int getChannel() { @@ -91,7 +91,7 @@ public class AnalogChannel extends SensorBase implements PIDSource, /** * Gets the number of the analog module this channel is on. - * + * * @return The module number of the analog module this channel is on. */ public int getModuleNumber() { @@ -100,7 +100,7 @@ public class AnalogChannel extends SensorBase implements PIDSource, /* * Get the average value for use with PIDController - * + * * @return the average value */ public double pidGet() { diff --git a/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/SensorBase.java b/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/SensorBase.java index 27cd925dad..23909c0a53 100644 --- a/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/SensorBase.java +++ b/wpilibj/wpilibJavaSim/src/main/java/edu/wpi/first/wpilibj/SensorBase.java @@ -11,13 +11,13 @@ package edu.wpi.first.wpilibj; * Base class for all sensors. * Stores most recent status information as well as containing utility functions for checking * channels and error processing. - * + * * XXX: Wait, there's no exception thrown if we try to allocate a non-existent module? It that behavior correct? */ public abstract class SensorBase { // TODO: Refactor // TODO: Move this to the HAL - + /** * Ticks per microsecond */ @@ -26,25 +26,16 @@ public abstract class SensorBase { // TODO: Refactor * Number of digital channels per digital sidecar */ public static final int kDigitalChannels = 14; - /** - * Number of digital modules - * XXX: This number is incorrect. We need to find the correct number. - */ - public static final int kDigitalModules = 2; /** * Number of analog channels per module */ public static final int kAnalogChannels = 8; - /** - * Number of analog modules - */ - public static final int kAnalogModules = 2; /** * Number of solenoid channels per module */ public static final int kSolenoidChannels = 8; /** - * Number of analog modules + * Number of solenoid modules */ public static final int kSolenoidModules = 2; /** @@ -56,8 +47,6 @@ public abstract class SensorBase { // TODO: Refactor */ public static final int kRelayChannels = 8; - private static int m_defaultAnalogModule = 1; - private static int m_defaultDigitalModule = 1; private static int m_defaultSolenoidModule = 1; /** @@ -66,32 +55,6 @@ public abstract class SensorBase { // TODO: Refactor public SensorBase() { } - /** - * Sets the default Digital Module. - * This sets the default digital module to use for objects that are created without - * specifying the digital module in the constructor. The default module is initialized - * to the first module in the chassis. - * - * @param moduleNumber The number of the digital module to use. - */ - public static void setDefaultDigitalModule(final int moduleNumber) { - checkDigitalModule(moduleNumber); - SensorBase.m_defaultDigitalModule = moduleNumber; - } - - /** - * Sets the default Analog module. - * This sets the default analog module to use for objects that are created without - * specifying the analog module in the constructor. The default module is initialized - * to the first module in the chassis. - * - * @param moduleNumber The number of the analog module to use. - */ - public static void setDefaultAnalogModule(final int moduleNumber) { - checkAnalogModule(moduleNumber); - SensorBase.m_defaultAnalogModule = moduleNumber; - } - /** * Set the default location for the Solenoid (9472) module. * @@ -102,51 +65,6 @@ public abstract class SensorBase { // TODO: Refactor SensorBase.m_defaultSolenoidModule = moduleNumber; } - /** - * Check that the digital module number is valid. - * Module numbers are 1 or 2 (they are no longer real cRIO slots). - * - * @param moduleNumber The digital module module number to check. - */ - protected static void checkDigitalModule(final int moduleNumber) { - // TODO: fix - if(moduleNumber == 1 || moduleNumber == 2) - System.err.println("Digital module " + moduleNumber + " is not present."); - } - - /** - * Check that the digital module number is valid. - * Module numbers are 1 or 2 (they are no longer real cRIO slots). - * - * @param moduleNumber The digital module module number to check. - */ - protected static void checkRelayModule(final int moduleNumber) { - checkDigitalModule(moduleNumber); - } - - /** - * Check that the digital module number is valid. - * Module numbers are 1 or 2 (they are no longer real cRIO slots). - * - * @param moduleNumber The digital module module number to check. - */ - protected static void checkPWMModule(final int moduleNumber) { - checkDigitalModule(moduleNumber); - } - - /** - * Check that the analog module number is valid. - * Module numbers are 1 or 2 (they are no longer real cRIO slots). - * - * @param moduleNumber The analog module module number to check. - */ - protected static void checkAnalogModule(final int moduleNumber) { - // TODO: fix - if(moduleNumber == 1 || moduleNumber == 2) { - System.err.println("Analog module " + moduleNumber + " is not present."); - } - } - /** * Verify that the solenoid module is correct. * Module numbers are 1 or 2 (they are no longer real cRIO slots). @@ -226,24 +144,6 @@ public abstract class SensorBase { // TODO: Refactor } } - /** - * Get the number of the default analog module. - * - * @return The number of the default analog module. - */ - public static int getDefaultAnalogModule() { - return SensorBase.m_defaultAnalogModule; - } - - /** - * Get the number of the default analog module. - * - * @return The number of the default analog module. - */ - public static int getDefaultDigitalModule() { - return SensorBase.m_defaultDigitalModule; - } - /** * Get the number of the default analog module. *