Convert y2018 over to use the new SensorReader class
Another step in converting to event loops.
Change-Id: Ia1d60e3495281c9735bf1c5f92958dbdd2822429
diff --git a/y2018/wpilib_interface.cc b/y2018/wpilib_interface.cc
index 6ddcd41..02aeeaa 100644
--- a/y2018/wpilib_interface.cc
+++ b/y2018/wpilib_interface.cc
@@ -7,7 +7,6 @@
#include <chrono>
#include <cmath>
#include <functional>
-#include <mutex>
#include <thread>
#include "frc971/wpilib/ahal/AnalogInput.h"
@@ -27,13 +26,11 @@
#include "aos/logging/queue_logging.h"
#include "aos/make_unique.h"
#include "aos/robot_state/robot_state.q.h"
-#include "aos/stl_mutex/stl_mutex.h"
#include "aos/time/time.h"
#include "aos/util/compiler_memory_barrier.h"
#include "aos/util/log_interval.h"
#include "aos/util/phased_loop.h"
#include "aos/util/wrapping_counter.h"
-
#include "frc971/autonomous/auto.q.h"
#include "frc971/control_loops/control_loops.q.h"
#include "frc971/control_loops/drivetrain/drivetrain.q.h"
@@ -43,12 +40,11 @@
#include "frc971/wpilib/dma.h"
#include "frc971/wpilib/dma_edge_counting.h"
#include "frc971/wpilib/encoder_and_potentiometer.h"
-#include "frc971/wpilib/interrupt_edge_counting.h"
#include "frc971/wpilib/joystick_sender.h"
#include "frc971/wpilib/logging.q.h"
#include "frc971/wpilib/loop_output_handler.h"
#include "frc971/wpilib/pdp_fetcher.h"
-#include "frc971/wpilib/wpilib_interface.h"
+#include "frc971/wpilib/sensor_reader.h"
#include "frc971/wpilib/wpilib_robot_base.h"
#include "y2018/constants.h"
#include "y2018/control_loops/superstructure/superstructure.q.h"
@@ -145,26 +141,13 @@
"medium encoders are too fast");
// Class to send position messages with sensor readings to our loops.
-class SensorReader {
+class SensorReader : public ::frc971::wpilib::SensorReader {
public:
SensorReader() {
// Set to filter out anything shorter than 1/4 of the minimum pulse width
// we should ever see.
- fast_encoder_filter_.SetPeriodNanoSeconds(
- static_cast<int>(1 / 4.0 /* built-in tolerance */ /
- kMaxFastEncoderPulsesPerSecond * 1e9 +
- 0.5));
- medium_encoder_filter_.SetPeriodNanoSeconds(
- static_cast<int>(1 / 4.0 /* built-in tolerance */ /
- kMaxMediumEncoderPulsesPerSecond * 1e9 +
- 0.5));
- hall_filter_.SetPeriodNanoSeconds(100000);
- }
-
- // Left drivetrain side.
- void set_drivetrain_left_encoder(::std::unique_ptr<frc::Encoder> encoder) {
- fast_encoder_filter_.Add(encoder.get());
- drivetrain_left_encoder_ = ::std::move(encoder);
+ UpdateFastEncoderFilterHz(kMaxFastEncoderPulsesPerSecond);
+ UpdateMediumEncoderFilterHz(kMaxMediumEncoderPulsesPerSecond);
}
void set_left_drivetrain_shifter_potentiometer(
@@ -172,12 +155,6 @@
left_drivetrain_shifter_ = ::std::move(potentiometer);
}
- // Right drivetrain side.
- void set_drivetrain_right_encoder(::std::unique_ptr<frc::Encoder> encoder) {
- fast_encoder_filter_.Add(encoder.get());
- drivetrain_right_encoder_ = ::std::move(encoder);
- }
-
void set_right_drivetrain_shifter_potentiometer(
::std::unique_ptr<frc::AnalogInput> potentiometer) {
right_drivetrain_shifter_ = ::std::move(potentiometer);
@@ -283,144 +260,14 @@
autonomous_modes_.at(i) = ::std::move(sensor);
}
- void set_pwm_trigger(::std::unique_ptr<frc::DigitalInput> pwm_trigger) {
- medium_encoder_filter_.Add(pwm_trigger.get());
- pwm_trigger_ = ::std::move(pwm_trigger);
- }
-
void set_lidar_lite_input(::std::unique_ptr<frc::DigitalInput> lidar_lite_input) {
lidar_lite_input_ = ::std::move(lidar_lite_input);
lidar_lite_.set_input(lidar_lite_input_.get());
}
- // All of the DMA-related set_* calls must be made before this, and it
- // doesn't hurt to do all of them.
- void set_dma(::std::unique_ptr<DMA> dma) {
- dma_synchronizer_.reset(
- new ::frc971::wpilib::DMASynchronizer(::std::move(dma)));
- dma_synchronizer_->Add(&lidar_lite_);
- }
-
- void RunPWMDetecter() {
- ::aos::SetCurrentThreadRealtimePriority(41);
-
- pwm_trigger_->RequestInterrupts();
- // Rising edge only.
- pwm_trigger_->SetUpSourceEdge(true, false);
-
- monotonic_clock::time_point last_posedge_monotonic =
- monotonic_clock::min_time;
-
- while (run_) {
- auto ret = pwm_trigger_->WaitForInterrupt(1.0, true);
- if (ret == frc::InterruptableSensorBase::WaitResult::kRisingEdge) {
- // Grab all the clocks.
- const double pwm_fpga_time = pwm_trigger_->ReadRisingTimestamp();
-
- aos_compiler_memory_barrier();
- const double fpga_time_before = frc::GetFPGATime() * 1e-6;
- aos_compiler_memory_barrier();
- const monotonic_clock::time_point monotonic_now =
- monotonic_clock::now();
- aos_compiler_memory_barrier();
- const double fpga_time_after = frc::GetFPGATime() * 1e-6;
- aos_compiler_memory_barrier();
-
- const double fpga_offset =
- (fpga_time_after + fpga_time_before) / 2.0 - pwm_fpga_time;
-
- // Compute when the edge was.
- const monotonic_clock::time_point monotonic_edge =
- monotonic_now - chrono::duration_cast<chrono::nanoseconds>(
- chrono::duration<double>(fpga_offset));
-
- LOG(DEBUG, "Got PWM pulse %f spread, %f offset, %lld trigger\n",
- fpga_time_after - fpga_time_before, fpga_offset,
- monotonic_edge.time_since_epoch().count());
-
- // Compute bounds on the timestep and sampling times.
- const double fpga_sample_length = fpga_time_after - fpga_time_before;
- const chrono::nanoseconds elapsed_time =
- monotonic_edge - last_posedge_monotonic;
-
- last_posedge_monotonic = monotonic_edge;
-
- // Verify that the values are sane.
- if (fpga_sample_length > 2e-5 || fpga_sample_length < 0) {
- continue;
- }
- if (fpga_offset < 0 || fpga_offset > 0.00015) {
- continue;
- }
- if (elapsed_time >
- chrono::microseconds(5050) + chrono::microseconds(4) ||
- elapsed_time <
- chrono::microseconds(5050) - chrono::microseconds(4)) {
- continue;
- }
- // Good edge!
- {
- ::std::unique_lock<::aos::stl_mutex> locker(tick_time_mutex_);
- last_tick_time_monotonic_timepoint_ = last_posedge_monotonic;
- last_period_ = elapsed_time;
- }
- } else {
- LOG(INFO, "PWM triggered %d\n", ret);
- }
- }
- pwm_trigger_->CancelInterrupts();
- }
-
- void operator()() {
- ::aos::SetCurrentThreadName("SensorReader");
-
- my_pid_ = getpid();
-
- dma_synchronizer_->Start();
-
- ::aos::time::PhasedLoop phased_loop(last_period_,
- ::std::chrono::milliseconds(3));
-
- ::std::thread pwm_detecter_thread(
- ::std::bind(&SensorReader::RunPWMDetecter, this));
-
- ::aos::SetCurrentThreadRealtimePriority(40);
- while (run_) {
- {
- const int iterations = phased_loop.SleepUntilNext();
- if (iterations != 1) {
- LOG(WARNING, "SensorReader skipped %d iterations\n", iterations - 1);
- }
- }
- RunIteration();
-
- monotonic_clock::time_point last_tick_timepoint;
- chrono::nanoseconds period;
- {
- ::std::unique_lock<::aos::stl_mutex> locker(tick_time_mutex_);
- last_tick_timepoint = last_tick_time_monotonic_timepoint_;
- period = last_period_;
- }
-
- if (last_tick_timepoint == monotonic_clock::min_time) {
- continue;
- }
- chrono::nanoseconds new_offset = phased_loop.OffsetFromIntervalAndTime(
- period, last_tick_timepoint + chrono::microseconds(2050));
-
- // TODO(austin): If this is the first edge in a while, skip to it (plus
- // an offset). Otherwise, slowly drift time to line up.
-
- phased_loop.set_interval_and_offset(period, new_offset);
- }
- pwm_detecter_thread.join();
- }
+ void Start() { AddToDMA(&lidar_lite_); }
void RunIteration() {
- ::frc971::wpilib::SendRobotState(my_pid_);
-
- const auto values = constants::GetValues();
-
{
auto drivetrain_message = drivetrain_queue.position.MakeMessage();
drivetrain_message->left_encoder =
@@ -441,8 +288,10 @@
drivetrain_message.Send();
}
+ }
- dma_synchronizer_->RunIteration();
+ void RunDmaIteration() {
+ const auto values = constants::GetValues();
{
auto superstructure_message = superstructure_queue.position.MakeMessage();
@@ -504,52 +353,7 @@
}
}
- void Quit() { run_ = false; }
-
private:
- double encoder_translate(int32_t value, double counts_per_revolution,
- double ratio) {
- return static_cast<double>(value) / counts_per_revolution * ratio *
- (2.0 * M_PI);
- }
-
- void CopyPosition(
- const ::frc971::wpilib::AbsoluteEncoderAndPotentiometer &encoder,
- ::frc971::PotAndAbsolutePosition *position,
- double encoder_counts_per_revolution, double encoder_ratio,
- ::std::function<double(double)> potentiometer_translate, bool reverse,
- double pot_offset) {
- const double multiplier = reverse ? -1.0 : 1.0;
- position->pot = multiplier * potentiometer_translate(
- encoder.ReadPotentiometerVoltage()) +
- pot_offset;
- position->encoder =
- multiplier * encoder_translate(encoder.ReadRelativeEncoder(),
- encoder_counts_per_revolution,
- encoder_ratio);
-
- position->absolute_encoder =
- (reverse ? (1.0 - encoder.ReadAbsoluteEncoder())
- : encoder.ReadAbsoluteEncoder()) *
- encoder_ratio * (2.0 * M_PI);
- }
-
- int32_t my_pid_;
-
- // Mutex to manage access to the period and tick time variables.
- ::aos::stl_mutex tick_time_mutex_;
- monotonic_clock::time_point last_tick_time_monotonic_timepoint_ =
- monotonic_clock::min_time;
- chrono::nanoseconds last_period_ = chrono::microseconds(5050);
-
- ::std::unique_ptr<::frc971::wpilib::DMASynchronizer> dma_synchronizer_;
-
- frc::DigitalGlitchFilter fast_encoder_filter_, medium_encoder_filter_,
- hall_filter_;
-
- ::std::unique_ptr<frc::Encoder> drivetrain_left_encoder_,
- drivetrain_right_encoder_;
-
::std::unique_ptr<frc::AnalogInput> left_drivetrain_shifter_,
right_drivetrain_shifter_;
@@ -567,14 +371,10 @@
::std::unique_ptr<frc::DigitalInput> claw_beambreak_;
::std::unique_ptr<frc::DigitalInput> box_back_beambreak_;
- ::std::unique_ptr<frc::DigitalInput> pwm_trigger_;
-
::std::array<::std::unique_ptr<frc::DigitalInput>, 4> autonomous_modes_;
::std::unique_ptr<frc::DigitalInput> lidar_lite_input_;
::frc971::wpilib::DMAPulseWidthReader lidar_lite_;
-
- ::std::atomic<bool> run_{true};
};
class SolenoidWriter {