WPILib  2014.0
WPIRoboticsLibraryforFRC
 All Classes Functions Variables Pages
Ultrasonic.h
1 /*----------------------------------------------------------------------------*/
2 /* Copyright (c) FIRST 2008. All Rights Reserved. */
3 /* Open Source Software - may be modified and shared by FRC teams. The code */
4 /* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
5 /*----------------------------------------------------------------------------*/
6 
7 #ifndef ULTRASONIC_H_
8 #define ULTRASONIC_H_
9 
10 #include "SensorBase.h"
11 #include "Task.h"
12 #include "PIDSource.h"
13 #include "LiveWindow/LiveWindowSendable.h"
14 
15 class Counter;
16 class DigitalInput;
17 class DigitalOutput;
18 
29 class Ultrasonic: public SensorBase, public PIDSource, public LiveWindowSendable
30 {
31 public:
32  typedef enum {
33  kInches = 0,
34  kMilliMeters = 1
35  } DistanceUnit;
36 
37  Ultrasonic(DigitalOutput *pingChannel, DigitalInput *echoChannel, DistanceUnit units = kInches);
38  Ultrasonic(DigitalOutput &pingChannel, DigitalInput &echoChannel, DistanceUnit units = kInches);
39  Ultrasonic(uint32_t pingChannel, uint32_t echoChannel, DistanceUnit units = kInches);
40  Ultrasonic(uint8_t pingModuleNumber, uint32_t pingChannel,
41  uint8_t echoModuleNumber, uint32_t echoChannel, DistanceUnit units = kInches);
42  virtual ~Ultrasonic();
43 
44  void Ping();
45  bool IsRangeValid();
46  static void SetAutomaticMode(bool enabling);
47  double GetRangeInches();
48  double GetRangeMM();
49  bool IsEnabled() { return m_enabled; }
50  void SetEnabled(bool enable) { m_enabled = enable; }
51 
52  double PIDGet();
53  void SetDistanceUnits(DistanceUnit units);
54  DistanceUnit GetDistanceUnits();
55 
56  void UpdateTable();
57  void StartLiveWindowMode();
58  void StopLiveWindowMode();
59  std::string GetSmartDashboardType();
60  void InitTable(ITable *subTable);
61  ITable * GetTable();
62 
63 private:
64  void Initialize();
65 
66  static void UltrasonicChecker();
67 
68  static constexpr double kPingTime = 10 * 1e-6;
69  static const uint32_t kPriority = 90;
70  static constexpr double kMaxUltrasonicTime = 0.1;
71  static constexpr double kSpeedOfSoundInchesPerSec = 1130.0 * 12.0;
72 
73  static Task m_task; // task doing the round-robin automatic sensing
74  static Ultrasonic *m_firstSensor; // head of the ultrasonic sensor list
75  static bool m_automaticEnabled; // automatic round robin mode
76  static SEM_ID m_semaphore; // synchronize access to the list of sensors
77 
78  DigitalInput *m_echoChannel;
79  DigitalOutput *m_pingChannel;
80  bool m_allocatedChannels;
81  bool m_enabled;
82  Counter *m_counter;
83  Ultrasonic *m_nextSensor;
84  DistanceUnit m_units;
85 
86  ITable *m_table;
87 };
88 
89 #endif
90 
Definition: DigitalInput.h:22
double GetRangeInches()
Definition: Ultrasonic.cpp:279
virtual ~Ultrasonic()
Definition: Ultrasonic.cpp:168
Definition: DigitalOutput.h:21
Ultrasonic(DigitalOutput *pingChannel, DigitalInput *echoChannel, DistanceUnit units=kInches)
Definition: Ultrasonic.cpp:110
static void SetAutomaticMode(bool enabling)
Definition: Ultrasonic.cpp:216
double PIDGet()
Definition: Ultrasonic.cpp:302
Definition: SensorBase.h:20
double GetRangeMM()
Definition: Ultrasonic.cpp:292
DistanceUnit GetDistanceUnits()
Definition: Ultrasonic.cpp:330
Definition: Counter.h:21
Definition: PIDSource.h:15
Definition: Ultrasonic.h:29
bool IsRangeValid()
Definition: Ultrasonic.cpp:269
void Ping()
Definition: Ultrasonic.cpp:255
void SetDistanceUnits(DistanceUnit units)
Definition: Ultrasonic.cpp:320
Definition: Task.h:17