diff --git a/src/comms/config_layer.hpp b/src/comms/config_layer.hpp index d4e92594..0a8f7b68 100644 --- a/src/comms/config_layer.hpp +++ b/src/comms/config_layer.hpp @@ -209,4 +209,4 @@ class ConfigLayer { extern Config config; -#endif \ No newline at end of file +#endif diff --git a/src/comms/data/comms_data.hpp b/src/comms/data/comms_data.hpp index e3a5097e..9e1f43d4 100644 --- a/src/comms/data/comms_data.hpp +++ b/src/comms/data/comms_data.hpp @@ -16,7 +16,7 @@ enum class TypeLabel : uint8_t { RevEncoderData, TOFSensorData, LidarDataPacketSI, - DR16Data, + TransmitterData, TempRobotState, TargetState, EstimatedState, @@ -48,8 +48,8 @@ inline std::string to_string(TypeLabel type_label) { return "TOFSensorData"; case TypeLabel::LidarDataPacketSI: return "LidarDataPacketSI"; - case TypeLabel::DR16Data: - return "DR16Data"; + case TypeLabel::TransmitterData: + return "TransmitterData"; case TypeLabel::TempRobotState: return "TempRobotState"; case TypeLabel::TargetState: diff --git a/src/comms/data/data_structs.hpp b/src/comms/data/data_structs.hpp index f197858c..a5eec876 100644 --- a/src/comms/data/data_structs.hpp +++ b/src/comms/data/data_structs.hpp @@ -7,7 +7,7 @@ #include "modules/comms/data/comms_data.hpp" // for CommsData #endif -#include // uintN_t +#include // uintN_t #include "test_data.hpp" @@ -21,7 +21,7 @@ #include "lidar_data_packet_si.hpp" -#include "dr16_data.hpp" +#include "transmitter_data.hpp" #include "robot_state_data.hpp" @@ -29,4 +29,4 @@ #include "comms_ref_data.hpp" -#endif // DATA_STRUCTS_HPP \ No newline at end of file +#endif // DATA_STRUCTS_HPP diff --git a/src/comms/data/dr16_data.hpp b/src/comms/data/dr16_data.hpp deleted file mode 100644 index 1384f128..00000000 --- a/src/comms/data/dr16_data.hpp +++ /dev/null @@ -1,71 +0,0 @@ -#pragma once - -#if defined(FIRMWARE) -#include "comms/data/comms_data.hpp" // for CommsData -#elif defined(HIVE) -#include "modules/comms/data/comms_data.hpp" // for CommsData -#endif - -#include // uintN_t - -/// @brief Structure for the DR16 -struct DR16Data : Comms::CommsData { - DR16Data() : CommsData(Comms::TypeLabel::DR16Data, Comms::PhysicalMedium::Ethernet, Comms::Priority::High, sizeof(DR16Data)) { } - /// Sensor ID. - uint8_t id; - /// mouse x velocity - int16_t mouse_x = 0; - /// mouse y velocity - int16_t mouse_y = 0; - /// mouse z velocity - int16_t mouse_z = 0; - /// left mouse button status - bool l_mouse_button = 0; - /// right mouse button status - bool r_mouse_button = 0; - /// left switch status - float l_switch = 0; - /// right switch status - float r_switch = 0; - /// left stick x axis - float l_stick_x = 0; - /// left stick y axis - float l_stick_y = 0; - /// right stick x axis - float r_stick_x = 0; - /// right stick y axis - float r_stick_y = 0; - /// wheel - float wheel = 0; - - /** - * Usage example of how to acces the keys bitfield: - DR16Data data; - data.w = 1; // Mark key 'w' as pressed - if (data.s) { // Check if key 's' is pressed - // do something - } - * - */ - union { - uint16_t raw = 0; - struct { - bool w : 1; - bool s : 1; - bool a : 1; - bool d : 1; - bool shift : 1; - bool ctrl : 1; - bool q : 1; - bool e : 1; - bool r : 1; - bool f : 1; - bool g : 1; - bool z : 1; - bool x : 1; - bool c : 1; - bool v : 1; - bool b : 1; - } key; - } keys; -}; diff --git a/src/comms/data/firmware_data.cpp b/src/comms/data/firmware_data.cpp index 7d04907c..1b6488ba 100644 --- a/src/comms/data/firmware_data.cpp +++ b/src/comms/data/firmware_data.cpp @@ -49,9 +49,9 @@ void FirmwareData::set_data(CommsData* data) { break; } - case TypeLabel::DR16Data: { + case TypeLabel::TransmitterData: { // place the data in the mega struct - dr16_data = *static_cast(data); + transmitter_data = *static_cast(data); break; } case TypeLabel::BuffEncoderData: { @@ -124,7 +124,7 @@ void FirmwareData::set_data(CommsData* data) { } } // namespace Comms - + #if defined(HIVE) TEST_CASE("setting firmware data structs") { @@ -195,10 +195,10 @@ TEST_CASE("setting firmware data structs") { firmware_data.set_data(&lidar_sensor_data); CHECK(firmware_data.lidars[1].back().lidar_speed == 55); - DR16Data dr16_data; - dr16_data.mouse_x = 55; - firmware_data.set_data(&dr16_data); - CHECK(firmware_data.dr16_data.mouse_x == 55); + TransmitterData transmitter_data; + transmitter_data.mouse_x = 55; + firmware_data.set_data(&transmitter_data); + CHECK(firmware_data.transmitter_data.mouse_x == 55); ConfigSection config_section; config_section.section_id = 55; @@ -211,4 +211,4 @@ TEST_CASE("setting firmware data structs") { CHECK(firmware_data.ref_data.game_status.raw[0] == 55); } -#endif // defined(HIVE) \ No newline at end of file +#endif // defined(HIVE) diff --git a/src/comms/data/firmware_data.hpp b/src/comms/data/firmware_data.hpp index e2d1d3d1..785d9056 100644 --- a/src/comms/data/firmware_data.hpp +++ b/src/comms/data/firmware_data.hpp @@ -64,8 +64,8 @@ struct FirmwareData { /// @brief lidar vector std::vector lidars[2]; - /// @brief DR16 data - DR16Data dr16_data; + /// @brief Transmitter data + TransmitterData transmitter_data; /// @brief Config section ConfigSection config_section; diff --git a/src/comms/data/transmitter_data.hpp b/src/comms/data/transmitter_data.hpp new file mode 100644 index 00000000..9bc40afe --- /dev/null +++ b/src/comms/data/transmitter_data.hpp @@ -0,0 +1,107 @@ +#pragma once + +#if defined(FIRMWARE) +#include "comms/data/comms_data.hpp" // for CommsData +#elif defined(HIVE) +#include "modules/comms/data/comms_data.hpp" // for CommsData +#endif + +#include // uintN_t +#include // std::optional + +/// @brief Switch Position Enum +enum class SwitchPos{ + INVALID = 0, + FORWARD, + BACKWARD, + MIDDLE +}; + +/// @brief Structure for the Transmitter +struct TransmitterData : Comms::CommsData { + TransmitterData() : CommsData(Comms::TypeLabel::TransmitterData, Comms::PhysicalMedium::Ethernet, Comms::Priority::High, sizeof(TransmitterData)) { } + + /// mouse x velocity + std::optional mouse_x = {}; + /// mouse y velocity + std::optional mouse_y = {}; + /// mouse z velocity + std::optional mouse_z = {}; + /// left mouse button status + std::optional l_mouse_button = {}; + /// right mouse button status + std::optional r_mouse_button = {}; + /// left switch status + SwitchPos l_switch = SwitchPos::INVALID; + /// right switch status + SwitchPos r_switch = SwitchPos::INVALID; + /// left stick x axis + float l_stick_x = 0; + /// left stick y axis + float l_stick_y = 0; + /// right stick x axis + float r_stick_x = 0; + /// right stick y axis + float r_stick_y = 0; + /// wheel + std::optional wheel = {}; + /// safety switch + std::optional safety_switch = {}; + /// switch b + std::optional switch_b = {}; + /// switch c + std::optional switch_c = {}; + /// switch d + std::optional switch_d = {}; + /// switch e + std::optional switch_e = {}; + /// switch f + std::optional switch_f = {}; + /// switch g + std::optional switch_g = {}; + /// switch h + std::optional switch_h = {}; + /// left dial + std::optional l_dial = {}; + /// right dial + std::optional r_dial = {}; + /// left slider + std::optional l_slider = {}; + /// right slider + std::optional r_slider = {}; + /// trim one + std::optional trim_one = {}; + /// trim two + std::optional trim_two = {}; + /// trim three + std::optional trim_three = {}; + /// trim four + std::optional trim_four = {}; + /// trim five + std::optional trim_five = {}; + /// trim six + std::optional trim_six = {}; + + /// @brief Keys + union { + uint16_t raw = 0; + struct { + bool w : 1; + bool s : 1; + bool a : 1; + bool d : 1; + bool shift : 1; + bool ctrl : 1; + bool q : 1; + bool e : 1; + bool r : 1; + bool f : 1; + bool g : 1; + bool z : 1; + bool x : 1; + bool c : 1; + bool v : 1; + bool b : 1; + } key; + } keys; +}; diff --git a/src/controls/controller_manager.cpp b/src/controls/controller_manager.cpp index 68961e32..68e9e370 100644 --- a/src/controls/controller_manager.cpp +++ b/src/controls/controller_manager.cpp @@ -60,6 +60,7 @@ void ControllerManager::step(float macro_reference[STATE_LEN][3], float macro_es for (size_t j = 0; j < CAN_MAX_MOTORS + 1; j++) { if (config_data->controller_info[i][j + 1] < 0) break; actuator_write(config_data->controller_info[i][j + 1], outputs[j]); + } } } diff --git a/src/controls/estimator_manager.cpp b/src/controls/estimator_manager.cpp index 62d88817..f2b67f00 100644 --- a/src/controls/estimator_manager.cpp +++ b/src/controls/estimator_manager.cpp @@ -13,7 +13,6 @@ EstimatorManager::~EstimatorManager() { } void EstimatorManager::init(CANManager* _can, const Config* _config_data, SensorManager* _sensor_manager) { - // set can and config data pointers can = _can; config_data = _config_data; @@ -106,4 +105,4 @@ void EstimatorManager::clear_outputs(float macro_outputs[STATE_LEN][3], float mi micro_outputs[i][j] = 0; } } -} \ No newline at end of file +} diff --git a/src/main.cpp b/src/main.cpp index 1afbce63..c29e3923 100644 --- a/src/main.cpp +++ b/src/main.cpp @@ -3,6 +3,13 @@ #include "comms/comms_layer.hpp" #include "git_info.h" +#include "sensors/buff_encoder.hpp" +#include "utils/profiler.hpp" + +#include "sensors/ET16S.hpp" +#include "sensors/Transmitter.hpp" +#include "sensors/d200.hpp" + #include "controls/controller_manager.hpp" #include "controls/estimator_manager.hpp" #include "sensors/ACS712.hpp" @@ -25,10 +32,12 @@ extern "C" void reset_teensy(void); // Declare global objects -DR16 dr16; + CANManager can; RefSystem *ref; ACS712 current_sensor; +Transmitter *transmitter = nullptr; + Comms::CommsLayer comms_layer; StereoCamTrigger stereoCamTrigger(60); @@ -103,11 +112,20 @@ int main() { // Execute setup functions pinMode(LED_BUILTIN, OUTPUT); + // Determine which transmitter is in use and instantiate its respective object. + // This allows for 'transmitter' to be used everywhere dr16 would be used + TransmitterType transmitter_type = transmitter->who_am_i(); + if (transmitter_type == TransmitterType::DR16) { + transmitter = new DR16; + } else if (transmitter_type == TransmitterType::ET16S) { + transmitter = new ET16S; + } // initialize objects can.init(); - dr16.init(); + transmitter->init(); comms_layer.init(); + ref = sensor_manager.get_ref(); // Config config @@ -147,8 +165,8 @@ int main() { // manual controls variables float vtm_pos_x = 0; float vtm_pos_y = 0; - float dr16_pos_x = 0; - float dr16_pos_y = 0; + float transmitter_pos_x = 0; + float transmitter_pos_y = 0; float pos_offset_x = 0; float pos_offset_y = 0; float feed = 0; @@ -196,10 +214,9 @@ int main() { // read sensors sensor_manager.read(); - // read CAN and DR16 -- These are kept out of sensor manager for safety - // reasons + // read CAN and Transmitter -- These are kept out of sensor manager for safety reasons can.read(); - dr16.read(); + transmitter->read(); sensor_manager.send_sensor_data_to_comms(); @@ -217,46 +234,69 @@ int main() { } // manual controls on firmware + std::optional transmitter_keys = transmitter->get_keys(); + std::optional mouse_x = transmitter->get_mouse_x(); + std::optional mouse_y = transmitter->get_mouse_y(); + std::optional l_mouse_button = transmitter->get_l_mouse_button(); + // std::optional r_mouse_button = transmitter->get_r_mouse_button(); + float delta = control_input_timer.delta(); - dr16_pos_x += dr16.get_mouse_x() * 0.05 * delta; - dr16_pos_y += dr16.get_mouse_y() * 0.05 * delta; + if (mouse_x.has_value() && mouse_y.has_value()) { + transmitter_pos_x += mouse_x.value() * 0.05 * delta; + transmitter_pos_y += mouse_y.value() * 0.05 * delta; + } vtm_pos_x += ref->ref_data.kbm_interaction.mouse_speed_x * 0.05 * delta; vtm_pos_y += ref->ref_data.kbm_interaction.mouse_speed_y * 0.05 * delta; // clamp to pitch limits - if (dr16_pos_y < pitch_min) { - dr16_pos_y = pitch_min; + if (transmitter_pos_y < pitch_min) { + transmitter_pos_y = pitch_min; } - if (dr16_pos_y > pitch_max) { - dr16_pos_y = pitch_max; + if (transmitter_pos_y > pitch_max) { + transmitter_pos_y = pitch_max; } float chassis_vel_x = 0; float chassis_vel_y = 0; float chassis_pos_x = 0; float chassis_pos_y = 0; + if (config->governor_types[0] == 2) { // if we should be controlling velocity - chassis_vel_x = dr16.get_l_stick_y() * 5.4 + - (-ref->ref_data.kbm_interaction.key_w + ref->ref_data.kbm_interaction.key_s) * 2.5 + - (-dr16.keys.w + dr16.keys.s) * 2.5; - chassis_vel_y = -dr16.get_l_stick_x() * 5.4 + - (ref->ref_data.kbm_interaction.key_d - ref->ref_data.kbm_interaction.key_a) * 2.5 + - (dr16.keys.d - dr16.keys.a) * 2.5; + + chassis_vel_x = transmitter->get_l_stick_y() * 5.4 + + (-ref->ref_data.kbm_interaction.key_w + ref->ref_data.kbm_interaction.key_s) * 2.5; + + if (transmitter_keys.has_value()) { + chassis_vel_x += (-transmitter_keys.value().w + transmitter_keys.value().s) * 2.5; + } + + chassis_vel_y = -transmitter->get_l_stick_x() * 5.4 + + (ref->ref_data.kbm_interaction.key_d - ref->ref_data.kbm_interaction.key_a) * 2.5; + + if (transmitter_keys.has_value()) { + chassis_vel_y += (transmitter_keys.value().d - transmitter_keys.value().a) * 2.5; + } } else if (config->governor_types[0] == 1) { // if we should be controlling position - chassis_pos_x = dr16.get_l_stick_x() * 2 + pos_offset_x; - chassis_pos_y = dr16.get_l_stick_y() * 2 + pos_offset_y; + chassis_pos_x = transmitter->get_l_stick_x() * 2 + pos_offset_x; + chassis_pos_y = transmitter->get_l_stick_y() * 2 + pos_offset_y; } - float chassis_spin = dr16.get_wheel() * 25; - float pitch_target = 1.57 + -dr16.get_r_stick_y() * 0.3 + dr16_pos_y + vtm_pos_y; - float yaw_target = -dr16.get_r_stick_x() * 1.5 - dr16_pos_x - vtm_pos_x; - float fly_wheel_target = (dr16.get_r_switch() == 1 || dr16.get_r_switch() == 3) ? 18 : 0; // m/s - float feeder_target = - (((dr16.get_l_mouse_button() || ref->ref_data.kbm_interaction.button_left) && dr16.get_r_switch() != 2) || - dr16.get_r_switch() == 1) - ? 10 - : 0; + float chassis_spin = transmitter->get_wheel() * 25; + float pitch_target = 1.57 + -transmitter->get_r_stick_y() * 0.3 + transmitter_pos_y + vtm_pos_y; + float yaw_target = -transmitter->get_r_stick_x() * 1.5 - transmitter_pos_x - vtm_pos_x; + + float fly_wheel_target = + (transmitter->get_r_switch() == SwitchPos::FORWARD || transmitter->get_r_switch() == SwitchPos::MIDDLE) + ? 18 + : 0; // m/s + // if the right switch is forward, and either the left mouse button is pressed or the right switch is not + // backward, set the feeder to something. Otherwise, set it to 0 + float feeder_target = (((l_mouse_button.has_value() || ref->ref_data.kbm_interaction.button_left) && + transmitter->get_r_switch() != SwitchPos::BACKWARD) || + transmitter->get_r_switch() == SwitchPos::FORWARD) + ? 10 + : 0; if (config->governor_types[6] == 1) { float dt2 = timer.delta(); if (dt2 > 0.1) @@ -268,10 +308,10 @@ int main() { } else { target_state[6][1] = feeder_target; } - // if (dr16.get_r_switch() == 1 && last_switch != 1) { + // if (transmitter->get_r_switch() == 1 && last_switch != 1) { // feed++; // } - // last_switch = dr16.get_r_switch(); + // last_switch = transmitter->get_r_switch(); // set manual controls target_state[0][0] = chassis_pos_x; target_state[0][1] = chassis_vel_x; @@ -286,7 +326,8 @@ int main() { target_state[7][0] = 1; // if the left switch is all the way down use Hive controls - if (dr16.get_l_switch() == 2) { + + if (transmitter->get_l_switch() == SwitchPos::BACKWARD) { // hid_incoming.get_target_state(target_state); memcpy(target_state, comms_layer.get_hive_data().target_state.state, sizeof(target_state)); last_feed = target_state[6][0]; @@ -299,7 +340,7 @@ int main() { } // when in teensy control mode reset hive toggle - if (dr16.get_l_switch() == 3) { + if (transmitter->get_l_switch() == SwitchPos::MIDDLE) { if (!hive_toggle || !safety_toggle) { pos_offset_x = temp_state[0][0]; pos_offset_y = temp_state[1][0]; @@ -310,9 +351,10 @@ int main() { safety_toggle = true; } - // print dr16 - // Serial.printf("DR16:\n\t"); - // dr16.print(); + // print transmitter + + // Serial.printf("transmitter:\n\t"); + // transmitter->print(); // Serial.printf("Target state:\n"); // for (int i = 0; i < 8; i++) { @@ -320,14 +362,14 @@ int main() { // target_state[i][1], target_state[i][2]); // } - // override temp state if needed. Dont override in teensy mode so the - // sentry doesnt move during inspection - if (comms_layer.get_hive_data().override_state.active && !(dr16.get_l_switch() == 3)) { + // override temp state if needed. Dont override in teensy mode so the sentry doesnt move during inspection + if (comms_layer.get_hive_data().override_state.active && !(transmitter->get_l_switch() == SwitchPos::MIDDLE)) { // clear the request comms_layer.get_hive_data().override_state.active = false; Serial.printf("Overriding state with hive state\n"); memcpy(hive_state_offset, comms_layer.get_hive_data().override_state.state, sizeof(hive_state_offset)); + memcpy(temp_state, hive_state_offset, sizeof(hive_state_offset)); override_request = true; } @@ -336,10 +378,10 @@ int main() { estimator_manager.step(temp_state, temp_micro_state, override_request); override_request = false; - if ((feed - temp_state[6][0] > 2 && dr16.get_l_switch() == 3) || - (comms_layer.get_hive_data().target_state.state[6][0] - temp_state[6][0] > 2 && dr16.get_l_switch() == 2)) { - Serial.printf("Feeder is lowkey jammed. current ball count: %f, " - "feed: %f, hive target: %f\n", + if ((feed - temp_state[6][0] > 2 && transmitter->get_l_switch() == SwitchPos::MIDDLE) || + (comms_layer.get_hive_data().target_state.state[6][0] - temp_state[6][0] > 2 && + transmitter->get_l_switch() == SwitchPos::BACKWARD)) { + Serial.printf("Feeder is lowkey jammed. current ball count: %f, feed: %f, hive target: %f\n", temp_state[6][0], feed, comms_layer.get_hive_data().target_state.state[6][0]); feed = temp_state[6][0] + 1; governor.set_reference_at_index(feed, 6, 0); @@ -390,26 +432,15 @@ int main() { estimated_state.data.time = millis() / 1000.0; estimated_state.send_to_comms(); - Comms::Sendable dr16_sendable; - dr16_sendable.data.l_mouse_button = dr16.get_l_mouse_button(); - dr16_sendable.data.r_mouse_button = dr16.get_r_mouse_button(); - dr16_sendable.data.l_switch = dr16.get_l_switch(); - dr16_sendable.data.r_switch = dr16.get_r_switch(); - dr16_sendable.data.l_stick_x = dr16.get_l_stick_x(); - dr16_sendable.data.l_stick_y = dr16.get_l_stick_y(); - dr16_sendable.data.r_stick_x = dr16.get_r_stick_x(); - dr16_sendable.data.r_stick_y = dr16.get_r_stick_y(); - dr16_sendable.data.wheel = dr16.get_wheel(); - dr16_sendable.data.mouse_x = dr16.get_mouse_x(); - dr16_sendable.data.mouse_y = dr16.get_mouse_y(); - dr16_sendable.data.keys.raw = *(uint16_t *)(dr16.get_raw() + 14); - dr16_sendable.send_to_comms(); + Comms::Sendable transmitter_sendable = transmitter->get_transmitter_data(); + transmitter_sendable.send_to_comms(); comms_layer.run(); bool is_slow_loop = false; // check whether this was a slow loop or not + float dt = stall_timer.delta(); if (dt > 0.002) { // zero the can bus just in case @@ -436,9 +467,11 @@ int main() { last_gimbal_power = ref->ref_data.robot_performance.gimbol_power_active; bool gimbal_power_recently_turned_on = gimbal_power_timer.get_elapsed_micros_no_restart() < 3000000; - not_safety_mode = (dr16.is_connected() && (dr16.get_l_switch() == 2 || dr16.get_l_switch() == 3) && - config_layer.is_configured() && !is_slow_loop && - ref->ref_data.robot_performance.gimbol_power_active && !gimbal_power_recently_turned_on); + not_safety_mode = + (transmitter->is_connected() && + (transmitter->get_l_switch() == SwitchPos::BACKWARD || transmitter->get_l_switch() == SwitchPos::MIDDLE) && + config_layer.is_configured() && !is_slow_loop && ref->ref_data.robot_performance.gimbol_power_active && + !gimbal_power_recently_turned_on); // SAFETY MODE if (not_safety_mode) { // SAFETY OFF @@ -471,6 +504,5 @@ int main() { // Keep the loop running at the desired rate loop_timer.delay_micros((int)(1E6 / (float)(LOOP_FREQ))); } - return 0; } diff --git a/src/sensors/ET16S.cpp b/src/sensors/ET16S.cpp index 85d9b233..69f4e2b5 100644 --- a/src/sensors/ET16S.cpp +++ b/src/sensors/ET16S.cpp @@ -2,20 +2,19 @@ ET16S::ET16S() { } - void ET16S::init() { Serial8.begin(100000, SERIAL_8E1_RXINV_TXINV); Serial8.flush(); Serial8.clear(); - //configure safety switch - //InputKind three_switch=THREE_SWITCH; + //configure safety switch; channel[4].kind = InputKind::THREE_SWITCH; + channel[4].id = ChannelId::SWITCH_A; //Turn safety on channel[4].data = static_cast(SwitchPos::FORWARD); //configure sticks //right stick horizontal - channel[0].kind = InputKind::STICK; + channel[r_stick_x_num.value()].kind = InputKind::STICK; //right stick vertical channel[1].kind = InputKind::STICK; //left stick vertical @@ -24,22 +23,41 @@ void ET16S::init() { channel[3].kind = InputKind::STICK; //configure remaining channels set_config(); + } void ET16S::read() { - // Raw data stored in array - uint8_t m_inputRaw[ET16S_PACKET_SIZE] = { 0 }; - // Store 2 packets (50 bytes) in the buffer to prevent incomplete packet reads - if (Serial8.available() < (2*ET16S_PACKET_SIZE)) { + static uint8_t last_byte = 0xAA; + + // if we have missed more than 4 packets (for example on startup), clear the buffer and start fresh + if (Serial8.available() > ET16S_PACKET_SIZE * 4) { + Serial8.clear(); + } + + // only start the "peeking" process if we have at least 2 packets worth of data, therefore we can afford to skip some bytes + if (Serial8.available() < ET16S_PACKET_SIZE * 2) { return; } - // We read until we find the start byte of the new packet (0x0f) - // this ensures we read one packet per loop + + // try to find the start of the frame. This is achieved by seeing if the current byte to read is 0x0f and the previous byte read was 0x00 + // if this is the case, we have found the start of the frame while (Serial8.peek() != 0x0f) { - Serial8.read(); + last_byte = Serial8.read(); } - // Fill raw input array - for (int i = 0; i < ET16S_PACKET_SIZE;i++) { + + // if the last byte was not 0x00, we have not found the start of the frame + if (last_byte != 0x00) { + return; + } + + // if we have less than a full packet available, we cannot read the full frame + // however we are "aligned" with the start of the frame, so we can wait for the next frame + if (Serial8.available() < ET16S_PACKET_SIZE) { + return; + } + + // read the full frame + for (int i = 0; i < ET16S_PACKET_SIZE; i++) { m_inputRaw[i] = Serial8.read(); } @@ -51,17 +69,11 @@ void ET16S::read() { set_channel_data(); //Check flag byte for disconnect test_connection(); - //if(channel[5].kind==InputKind::THREE_SWITCH){Serial.print("ITS TRUE");} - ///print_raw_bin(m_inputRaw); - //print_format_bin(16); - print(); - //print_raw(); } void ET16S::print() { for (int i = 0; i < ET16S_INPUT_VALUE_COUNT; i++) { - Serial.print(channel[i].data); - Serial.print(" "); + Serial.printf("%f ", channel[i].data); } Serial.println(); @@ -272,6 +284,7 @@ float ET16S::map_raw(InputChannel input) { return val; } + float ET16S::map_math(float val,float min_out, float max_out){ // maps input value from -1 to 1 val = min_out + (val - min_in) * (max_out - min_out) / (max_in - min_in); @@ -284,29 +297,51 @@ float ET16S::map_math(float val,float min_out, float max_out){ } return val; } + void ET16S::set_config() { //Valid channel types include STICK,TWO_SWITCH_THREE_SWITCH, //DIAL,SLIDER,TRIM,FLAG,INVALID //note (trim is not mapped) - channel[0].id = ChannelId::R_STICK_X; - channel[1].id = ChannelId::R_STICK_Y; - channel[2].id = ChannelId::L_STICK_Y; - channel[3].id = ChannelId::L_STICK_X; - channel[4].id = ChannelId::SWITCH_A; - channel[5].id = ChannelId::SWITCH_B; - channel[6].id = ChannelId::SWITCH_C; - channel[7].id = ChannelId::SWITCH_D; - channel[8].id = ChannelId::SWITCH_E; - channel[9].id = ChannelId::SWITCH_F; - channel[10].id = ChannelId::SWITCH_G; - channel[11].id = ChannelId::SWITCH_H; - channel[12].id = ChannelId::R_SLIDER; - channel[14].id = ChannelId::L_SLIDER; - channel[13].id = ChannelId::R_DIAL; - channel[15].id = ChannelId::UNMAPPED; //channel[15] is non-functional + channel[r_stick_x_num.value()].id = ChannelId::R_STICK_X; + channel[r_stick_y_num.value()].id = ChannelId::R_STICK_Y; + channel[l_stick_x_num.value()].id = ChannelId::L_STICK_X; + channel[l_stick_y_num.value()].id = ChannelId::L_STICK_Y; + if (switch_b_num.has_value()) { + channel[switch_b_num.value()].id = ChannelId::SWITCH_B; + } + if (switch_c_num.has_value()) { + channel[switch_c_num.value()].id = ChannelId::SWITCH_C; + } + if (switch_d_num.has_value()) { + channel[switch_d_num.value()].id = ChannelId::SWITCH_D; + } + if (switch_e_num.has_value()) { + channel[switch_e_num.value()].id = ChannelId::SWITCH_E; + } + if (switch_f_num.has_value()) { + channel[switch_f_num.value()].id = ChannelId::SWITCH_F; + } + if (switch_g_num.has_value()) { + channel[switch_g_num.value()].id = ChannelId::SWITCH_G; + } + if (switch_h_num.has_value()) { + channel[switch_h_num.value()].id = ChannelId::SWITCH_H; + } + if (r_slider_num.has_value()) { + channel[r_slider_num.value()].id = ChannelId::R_SLIDER; + } + if (l_slider_num.has_value()) { + channel[l_slider_num.value()].id = ChannelId::L_SLIDER; + } + if (r_dial_num.has_value()) { + channel[r_dial_num.value()].id = ChannelId::R_DIAL; + } + if(l_dial_num.has_value()){ + channel[l_dial_num.value()].id = ChannelId::L_DIAL; + } channel[16].id = ChannelId::FLAG; - for (int i=5; i (channel[4].data); } float ET16S::get_r_stick_x() { - return channel[0].data; + return channel[r_stick_x_num.value()].data; } float ET16S::get_r_stick_y() { - return channel[1].data; + return channel[r_stick_y_num.value()].data; } float ET16S::get_l_stick_x() { - return channel[2].data; + return channel[l_stick_x_num.value()].data; } float ET16S::get_l_stick_y() { - return channel[3].data; + return channel[l_stick_y_num.value()].data; } -std::optional ET16S::get_switch_b(){ + +std::optional ET16S::get_switch_b(){ if (!switch_b_num.has_value()){ return {}; } - return channel[switch_b_num.value()].data; + return static_cast (channel[switch_b_num.value()].data); } -std::optional ET16S::get_switch_c(){ + +std::optional ET16S::get_switch_c(){ if (!switch_c_num.has_value()){ return {}; } - return channel[switch_c_num.value()].data; + return static_cast (channel[switch_c_num.value()].data); } -std::optional ET16S::get_switch_d(){ + +std::optional ET16S::get_switch_d(){ if (!switch_d_num.has_value()){ return {}; } - return channel[switch_d_num.value()].data; + return static_cast (channel[switch_d_num.value()].data); } -std::optional ET16S::get_switch_e(){ + +std::optional ET16S::get_switch_e(){ if (!switch_e_num.has_value()){ return {}; } - return channel[switch_e_num.value()].data; + return static_cast (channel[switch_e_num.value()].data); } -std::optional ET16S::get_switch_f(){ + +std::optional ET16S::get_switch_f(){ if (!switch_f_num.has_value()){ return {}; } - return channel[switch_f_num.value()].data; + return static_cast (channel[switch_f_num.value()].data); } -std::optional ET16S::get_switch_g(){ + +std::optional ET16S::get_switch_g(){ if (!switch_g_num.has_value()){ return {}; } - return channel[switch_g_num.value()].data; + return static_cast (channel[switch_g_num.value()].data); } -std::optional ET16S::get_switch_h(){ + +std::optional ET16S::get_switch_h(){ if (!switch_h_num.has_value()){ return {}; } - return channel[switch_h_num.value()].data; + return static_cast (channel[switch_h_num.value()].data); } + std::optional ET16S::get_l_slider(){ if (!l_slider_num.has_value()){ return {}; } return channel[l_slider_num.value()].data; } + std::optional ET16S::get_r_slider(){ if (!r_slider_num.has_value()){ return {}; } return channel[r_slider_num.value()].data; } + std::optional ET16S::get_trim_one(){ if (!trim_one_num.has_value()){ return {}; } return channel[trim_one_num.value()].data; } + std::optional ET16S::get_trim_two(){ if (!trim_two_num.has_value()){ return {}; } return channel[trim_two_num.value()].data; } + std::optional ET16S::get_trim_three(){ if (!trim_three_num.has_value()){ return {}; } return channel[trim_three_num.value()].data; } + std::optional ET16S::get_trim_four(){ if (!trim_four_num.has_value()){ return {}; } return channel[trim_four_num.value()].data; } + std::optional ET16S::get_trim_five(){ if (!trim_five_num.has_value()){ return {}; } return channel[trim_five_num.value()].data; } + std::optional ET16S::get_trim_six(){ if (!trim_six_num.has_value()){ return {}; } return channel[trim_six_num.value()].data; } + std::optional ET16S::get_l_dial(){ if (!l_dial_num.has_value()){ return {}; } return channel[l_dial_num.value()].data; } + std::optional ET16S::get_r_dial(){ if (!r_dial_num.has_value()){ return {}; } return channel[r_dial_num.value()].data; } std::optional ET16S::get_channel_data(int chan_num){ - // Will return nothing if an incorrect channel number is given - if ((chan_num < 0) || (chan_num > 16)){ + // Will return nothing if an incorrect channel number is given + if ((chan_num < 0) || (chan_num > 16)){ return {}; } return channel[chan_num].data; } -bool ET16S::get_connection_status() { - return is_connected; +bool ET16S::is_connected() { + return is_connect; } +SwitchPos ET16S::get_l_switch(){ + return static_cast (get_safety_switch()); +} + +SwitchPos ET16S::get_r_switch(){ + return static_cast (channel[switch_d_num.value()].data); +} + +float ET16S::get_wheel(){ + // index will need to be changed to use a different control for wheel + return channel[l_slider_num.value()].data; +} +TransmitterData ET16S::get_transmitter_data(){ + TransmitterData transmitter_data; + transmitter_data.l_mouse_button = get_l_mouse_button(); + transmitter_data.r_mouse_button = get_r_mouse_button(); + transmitter_data.l_switch = get_l_switch(); + transmitter_data.r_switch = get_r_switch(); + transmitter_data.l_stick_x = get_l_stick_x(); + transmitter_data.l_stick_y = get_l_stick_y(); + transmitter_data.r_stick_x = get_r_stick_x(); + transmitter_data.r_stick_y = get_r_stick_y(); + transmitter_data.wheel = get_wheel(); + transmitter_data.l_dial = get_l_dial(); + transmitter_data.r_dial = get_r_dial(); + transmitter_data.safety_switch = get_safety_switch(); + transmitter_data.switch_b = get_switch_b(); + transmitter_data.switch_c = get_switch_c(); + transmitter_data.switch_d = get_switch_d(); + transmitter_data.switch_e = get_switch_e(); + transmitter_data.switch_f = get_switch_f(); + transmitter_data.switch_g = get_switch_g(); + transmitter_data.switch_h = get_switch_h(); + transmitter_data.l_slider = get_l_slider(); + transmitter_data.r_slider = get_r_slider(); + transmitter_data.trim_one = get_trim_one(); + transmitter_data.trim_two = get_trim_two(); + transmitter_data.trim_three = get_trim_three(); + transmitter_data.trim_four = get_trim_four(); + transmitter_data.trim_five = get_trim_five(); + transmitter_data.trim_six = get_trim_six(); + return transmitter_data; +} diff --git a/src/sensors/ET16S.hpp b/src/sensors/ET16S.hpp index 35908084..2e2cab20 100644 --- a/src/sensors/ET16S.hpp +++ b/src/sensors/ET16S.hpp @@ -2,9 +2,9 @@ #include #include +#include "./Transmitter.hpp" //http://www.wflysz.com/wflyftp/ET16S/ET16SENV1.00.pdf -//channel[15] is broken /// @brief The size of an SBUS packet is 25 bits constexpr uint16_t ET16S_PACKET_SIZE = 25; @@ -13,13 +13,13 @@ constexpr uint16_t ET16S_INPUT_VALUE_COUNT = 17; /// @brief maximum raw input value for stick,dial,wheel constexpr float max_in = 1695; /// @brief minimum raw input value for stick,dial,wheel -constexpr float min_in = 352; +constexpr float min_in = 353; // this is 352 if Port9 is set to w.bus2 /// @brief flag byte displaying disconnect (found through testing) -constexpr uint16_t ERROR = 0b0000000000001100; +constexpr uint16_t DISCONNECT = 0b0000000000001100; /// @brief organizes the kinds of inputs the transmitter has enum class InputKind { - INVALID, + INVALID = 0, STICK, TWO_SWITCH, THREE_SWITCH, @@ -30,7 +30,7 @@ enum class InputKind { }; /// @brief enum for all possible inputs on transmitter enum class ChannelId{ - UNMAPPED, + UNMAPPED = 0, L_STICK_X, L_STICK_Y, R_STICK_X, @@ -55,14 +55,6 @@ enum class ChannelId{ TRIM_6, FLAG }; -/// @brief three switch possible positions -/// @note for switch on the front plate forward is up -enum class SwitchPos{ - INVALID, - FORWARD, - MIDDLE, - BACKWARD -}; /// @brief stores data and kind of data for the 15 data channels and 1 flag channel /// for the W-fly Transmitter @@ -81,7 +73,7 @@ struct InputChannel { }; /// @brief Class for W-Fly transmitter and reciever to gather and map control data -class ET16S { +class ET16S : public Transmitter { public: /// @brief Constructor, left empty ET16S(); @@ -101,7 +93,7 @@ class ET16S { /// @brief get safety values /// @return safety value(1-3) 1 is safe - uint8_t get_safety_switch(); + SwitchPos get_safety_switch(); /// @brief get right stick x axis value /// @return (-1 to 1) @@ -121,31 +113,31 @@ class ET16S { /// @brief get switch b value /// @return switch b value if it exists otherwise return nothing - std::optional get_switch_b(); + std::optional get_switch_b(); /// @brief get switch c value /// @return switch c value if it exists otherwise return nothing - std::optional get_switch_c(); + std::optional get_switch_c(); /// @brief get switch d value /// @return switch d value if it exists otherwise return nothing - std::optional get_switch_d(); + std::optional get_switch_d(); /// @brief get switch e value /// @return switch e value if it exists otherwise return nothing - std::optional get_switch_e(); + std::optional get_switch_e(); /// @brief get switch f value /// @return switch f value if it exists otherwise return nothing - std::optional get_switch_f(); + std::optional get_switch_f(); /// @brief get switch g value /// @return switch g value if it exists otherwise return nothing - std::optional get_switch_g(); + std::optional get_switch_g(); /// @brief get switch h value /// @return switch h value if it exists otherwise return nothing - std::optional get_switch_h(); + std::optional get_switch_h(); /// @brief get left slider value /// @return left slider value if it exists otherwise return nothing @@ -187,16 +179,34 @@ class ET16S { /// @return trim six value if it exists otherwise return nothing std::optional get_trim_six(); - /// @brief get channel data - /// @param chan_num is the channel number from 5-16 + /// @param chan_num is the channel number from 0-16 /// @return channel data std::optional get_channel_data(int chan_num); /// @brief getter for connection status /// @return false if disconnected - bool get_connection_status(); - + bool is_connected(); + + /// @brief returns switch A + /// @note exists for DR16 Backwards Compatability + /// @return left most front face switch value + SwitchPos get_l_switch(); + + /// @brief returns switch D + /// @note exists for DR16 Backwards Compatability + /// @return right most front face switch value + SwitchPos get_r_switch(); + + /// @brief returns left slider + /// @note exists for DR16 Backwards Compatability + /// @return back left spin wheel value + float get_wheel(); + + /// @brief getter for raw data + /// @return raw data + uint8_t* get_raw() { return m_inputRaw; } + private: /// @brief prints the entire raw binary data packet exactly as it is recieved /// @param m_inputRaw raw bit array @@ -218,6 +228,12 @@ class ET16S { /// @param m_inputRaw takes in 8 bit chunks of the total data packet void format_raw(uint8_t m_inputRaw[ET16S_PACKET_SIZE]); + /// @brief averages the last 5 samples of a channel + /// @param sample is the current sample + /// @param channel_index is the index of the channel + /// @return the average of the last 5 samples + float average_channel(float sample, int channel_index); + /// @brief assigns the mapped input values to their respective channels void set_channel_data(); @@ -231,30 +247,40 @@ class ET16S { InputChannel channel[ET16S_INPUT_VALUE_COUNT]; /// @brief signifies whether a disconnect flag has been read - bool is_connected=false; - //switch a (safety switch) and joysticks are not configurable - /// @brief switch b index - std::optional switch_b_num=5; + bool is_connect = false; + // switch a (safety switch / index 4) is not configurable + // Following index system denotes which channel each input is configured through + // if the controls are changed the number below must be changed to match the number displayed on the ET16S + /// @brief r stick x index + std::optional r_stick_x_num = 0; + /// @brief right y stick index + std::optional r_stick_y_num = 1; + /// @brief left y stick index + std::optional l_stick_y_num = 2; + /// @brief left x stick index + std::optional l_stick_x_num = 3; + /// @brief stich b index + std::optional switch_b_num = 5; /// @brief switch c index - std::optional switch_c_num=6; + std::optional switch_c_num = 6; /// @brief switch d index - std::optional switch_d_num=7; + std::optional switch_d_num = 7; /// @brief switch e index - std::optional switch_e_num=8; + std::optional switch_e_num = 8; /// @brief switch f index - std::optional switch_f_num=9; + std::optional switch_f_num = 9; /// @brief switch g index - std::optional switch_g_num=10; + std::optional switch_g_num = 10; /// @brief switch h index - std::optional switch_h_num=11; + std::optional switch_h_num = 11; /// @brief right slider index - std::optional r_slider_num=12; + std::optional r_slider_num = 12; /// @brief left slider index - std::optional l_slider_num=14; + std::optional l_slider_num = 14; /// @brief right dial index - std::optional r_dial_num=13; + std::optional r_dial_num = 13; /// @brief left dial index - std::optional l_dial_num; + std::optional l_dial_num=15; /// @brief trim one index std::optional trim_one_num; /// @brief trim two index @@ -267,4 +293,19 @@ class ET16S { std::optional trim_five_num; /// @brief trim six index std::optional trim_six_num; + + /// @brief the number of samples to average + const static int AVERAGE_SAMPLE_COUNT = 2; + + /// @brief circular buffer for storing the last few samples of each channel + float channel_values_circular_buf[ET16S_INPUT_VALUE_COUNT][AVERAGE_SAMPLE_COUNT] = { 0 }; + /// @brief the index of the next sample to be stored in the circular buffer + int value_indices[ET16S_INPUT_VALUE_COUNT] = { 0 }; + + /// @brief raw data packet + uint8_t m_inputRaw[ET16S_PACKET_SIZE] = { 0 }; + + /// @brief getter for transmitter data + /// @return Filled Transmitter data struct + TransmitterData get_transmitter_data(); }; diff --git a/src/sensors/Transmitter.cpp b/src/sensors/Transmitter.cpp new file mode 100644 index 00000000..ca4fe13d --- /dev/null +++ b/src/sensors/Transmitter.cpp @@ -0,0 +1,47 @@ +#include "Transmitter.hpp" +#include "ET16S.hpp" + +TransmitterType Transmitter::who_am_i() { + uint8_t raw_input[ET16S_PACKET_SIZE] = { 0 }; + + //Serial Initilization + Serial8.begin(100000, SERIAL_8E1_RXINV_TXINV); + Serial8.flush(); + Serial8.clear(); + + int counter = 0; //How many sequential elements have been found + + uint32_t start_time = millis(); + uint32_t timeout = 500; // Times out after 100 milliseconds + while(counter != 5){ + start_time = millis(); + raw_input[24] = 0; + + while (Serial8.available() < (2*ET16S_PACKET_SIZE)) { + if ((millis() - start_time) > timeout) { + Serial.println("Transmitter: DR16 by timeout"); + return TransmitterType::DR16; + } + } + // We read until we find the start byte of the new packet (0x0f) + // this ensures we read one packet per loop + + while ((Serial8.peek() != 0x0f) && ((millis() - start_time) < timeout)) { + Serial8.read(); + } + // Fill raw input array + for (int i = 0; i < ET16S_PACKET_SIZE+1;i++) { + raw_input[i] = Serial8.read(); + } + + if (raw_input[0] == 0x0f) { + counter += 1; + } else { + Serial.println("Transmitter: DR16"); + return TransmitterType::DR16; + } + } + + Serial.println("Transmitter: ET16S"); + return TransmitterType::ET16S; +} diff --git a/src/sensors/Transmitter.hpp b/src/sensors/Transmitter.hpp new file mode 100644 index 00000000..5026035a --- /dev/null +++ b/src/sensors/Transmitter.hpp @@ -0,0 +1,235 @@ +#pragma once + +#include +#include +#include "../comms/data/data_structs.hpp" + +/// @brief The enum of what type of transmitter is being used +enum class TransmitterType { + INVALID = 0, + DR16, + ET16S +}; + + + +/// @brief A unifying interface for all transmitters +class Transmitter { +public: + /// @brief checks the incoming data stream to determine the transmitter type + /// @note who_am_i assumes transmitter is ET16S, on fail it returns dr16. utilizes the packet size of each transmitter to comfirm + /// @return Corrosponding TransmitterType object + static TransmitterType who_am_i(); + + /// @brief standard destructor + virtual ~Transmitter() {} + + /// @brief Reads raw input + virtual void read() {} + + /// @brief initalizes serial connection + virtual void init() {} + + /// @brief prints all output values + + virtual void print() {} + + /// @brief zeros all buffers + virtual void zero() {} + + /// @brief Prints raw input + virtual void print_raw() {} + + /// @brief get right stick x axis value + /// @return (-1 to 1) + virtual float get_r_stick_x() { return 0; } + + /// @brief get right stick y axis value + /// @return (-1 to 1) + virtual float get_r_stick_y() { return 0; } + + /// @brief get left stick x axis value + /// @return (-1 to 1) + virtual float get_l_stick_x() { return 0; } + + /// @brief get left stick y axis value + /// @return (-1 to 1) + virtual float get_l_stick_y() { return 0; } + + /// @brief checks if data is valid + /// @return returns true if data is valid false otherwise + virtual bool is_data_valid() { return false; } + + /// @brief Returns the fail bit. Set only if invalid packets have been received for more then 250ms + /// @return Failure status + virtual uint8_t is_fail() { return 0; } + + /// @brief getter for connection status + /// @return false if disconnected + virtual bool is_connected() { return 0; } + + /// @brief Get mouse velocity x + /// @return Amount of points since last read + virtual std::optional get_mouse_x() { return {}; } + + /// @brief Get mouse velocity y + /// @return Amount of points since last read + virtual std::optional get_mouse_y() { return {}; } + + /// @brief status of left mouse button + /// @return Is left mouse button pressed + virtual std::optional get_l_mouse_button() { return {}; } + + /// @brief status of right mouse button + /// @return Is right mouse button pressed + virtual std::optional get_r_mouse_button() { return {};} + + /// @brief used for safety switch + /// @return left most front face switch value + virtual SwitchPos get_l_switch() { return SwitchPos::INVALID; } + + /// @brief used for flywheel trigger switch + /// @return left most front face switch value + virtual SwitchPos get_r_switch() { return SwitchPos::INVALID; } + + /// @brief used for spin wheel + /// @return wheel value + virtual float get_wheel() { return 0; } + + /// @brief used to get input + /// @return pointer to input array + virtual float* get_input() { return 0; } + + /// @brief used to get raw input + /// @return pointer to raw input array + virtual uint8_t* get_raw() { return nullptr; } + + /// @brief prints data in binary for a specific channel + /// @param channel_num channel number from 0-16 inclusive + virtual void print_format_bin(int channel_num) {} + + /// @brief getter for safety switch + /// @return safety switch value + virtual SwitchPos get_safety_switch() { return SwitchPos::INVALID; } + + /// @brief get switch b value on the ET16S + /// @return switch b value if it exists otherwise return nothing + virtual std::optional get_switch_b() { return {}; } + + /// @brief get switch c value on the ET16S + /// @return switch c value if it exists otherwise return nothing + virtual std::optional get_switch_c() { return {}; } + + /// @brief get switch d value on the ET16S + /// @return switch d value if it exists otherwise return nothing + virtual std::optional get_switch_d() { return {}; } + + /// @brief get switch e value on the ET16S + /// @return switch e value if it exists otherwise return nothing + virtual std::optional get_switch_e() { return {}; } + + /// @brief get switch f value on the ET16S + /// @return switch f value if it exists otherwise return nothing + virtual std::optional get_switch_f() { return {}; } + + /// @brief get switch g value on the ET16S + /// @return switch g value if it exists otherwise return nothing + virtual std::optional get_switch_g() { return {}; } + + /// @brief get switch h value on the ET16S + /// @return switch h value if it exists otherwise return nothing + virtual std::optional get_switch_h() { return {}; } + + /// @brief get left slider value on the ET16S + /// @return left slider value if it exists otherwise return nothing + virtual std::optional get_l_slider() { return {}; } + + /// @brief get right slider value on the ET16S + /// @return right slider value if it exists otherwise return nothing + virtual std::optional get_r_slider() { return {}; } + + /// @brief get left dial value on the ET16S + /// @return left dial value if it exists otherwise return nothing + virtual std::optional get_l_dial() { return {}; } + + /// @brief get right dial value on the ET16S + /// @return right dial value if it exists otherwise return nothing + virtual std::optional get_r_dial() { return {}; } + + /// @brief get trim one value on the ET16S + /// @return trim one value if it exists otherwise return nothing + virtual std::optional get_trim_one() { return {}; } + + /// @brief get trim two value on the ET16S + /// @return trim two value if it exists otherwise return nothing + virtual std::optional get_trim_two() { return {}; } + + /// @brief get trim three value on the ET16S + /// @return trim three value if it exists otherwise return nothing + virtual std::optional get_trim_three() { return {}; } + + /// @brief get trim four value on the ET16S + /// @return trim four value if it exists otherwise return nothing + virtual std::optional get_trim_four() { return {}; } + + /// @brief get trim five value on the ET16S + /// @return trim five value if it exists otherwise return nothing + virtual std::optional get_trim_five() { return {}; } + + /// @brief get trim six value on the ET16S + /// @return trim six value if it exists otherwise return nothing + virtual std::optional get_trim_six() { return {}; } + /// @brief get any channel on ET16S + /// @param chan_num is the channel number from 0-16 + /// @return value at given channel + virtual std::optional get_channel_data(int chan_num) { return {}; } + + /// @brief Various keys that can be pressed on the transmitter + struct Keys { + /// @brief If the key 'w' is pressed + bool w = 0; + /// @brief If the key 's' is pressed + bool s = 0; + /// @brief if the key 'a' is pressed + bool a = 0; + /// @brief if the key 'd' is pressed + bool d = 0; + /// @brief if the key 'shift' is pressed + bool shift = 0; + /// @brief if the key 'ctrl' is pressed + bool ctrl = 0; + /// @brief if the key 'q' is pressed + bool q = 0; + /// @brief if the key 'e' is pressed + bool e = 0; + /// @brief if the key 'r' is pressed + bool r = 0; + /// @brief if the key 'f' is pressed + bool f = 0; + /// @brief if the key 'g' is pressed + bool g = 0; + /// @brief if the key 'z' is pressed + bool z = 0; + /// @brief if the key 'x' is pressed + bool x = 0; + /// @brief if the key 'c' is pressed + bool c = 0; + /// @brief if the key 'v' is pressed + bool v = 0; + /// @brief if the key 'b' is pressed + bool b = 0; + }; + + /// @brief struct instance to keep track of the rm control data + Keys keys; + + /// @brief get keys + /// @return keys pressed + virtual std::optional get_keys() { return {}; } + + + /// @brief getter for transmitter data + /// @return Filled Transmitter data struct + virtual TransmitterData get_transmitter_data(){return TransmitterData();} + +}; diff --git a/src/sensors/dr16.cpp b/src/sensors/dr16.cpp index 32eb1900..03bc6553 100644 --- a/src/sensors/dr16.cpp +++ b/src/sensors/dr16.cpp @@ -243,19 +243,19 @@ float DR16::get_wheel() { return m_input[4]; } -float DR16::get_r_switch() { - return m_input[5]; +SwitchPos DR16::get_r_switch() { + return static_cast (m_input[5]); } -float DR16::get_l_switch() { - return m_input[6]; +SwitchPos DR16::get_l_switch() { + return static_cast (m_input[6]); } -int DR16::get_mouse_y() { +std::optional DR16::get_mouse_y() { return mouse_y; } -int DR16::get_mouse_x() { +std::optional DR16::get_mouse_x() { return mouse_x; } @@ -263,10 +263,27 @@ int DR16::get_mouse_z() { return mouse_z; } -bool DR16::get_l_mouse_button() { +std::optional DR16::get_l_mouse_button() { return l_mouse_button; } -bool DR16::get_r_mouse_button() { +std::optional DR16::get_r_mouse_button() { return r_mouse_button; } +TransmitterData DR16::get_transmitter_data(){ + TransmitterData transmitter_data; + transmitter_data.mouse_x = mouse_x; + transmitter_data.mouse_y = mouse_y; + transmitter_data.mouse_z = mouse_z; + transmitter_data.l_mouse_button = l_mouse_button; + transmitter_data.r_mouse_button = r_mouse_button; + transmitter_data.l_switch = get_l_switch(); + transmitter_data.r_switch = get_r_switch(); + transmitter_data.l_stick_x = get_l_stick_x(); + transmitter_data.l_stick_y = get_l_stick_y(); + transmitter_data.r_stick_x = get_r_stick_x(); + transmitter_data.r_stick_y = get_r_stick_y(); + transmitter_data.wheel = get_wheel(); + transmitter_data.safety_switch = get_safety_switch(); + return transmitter_data; +} diff --git a/src/sensors/dr16.hpp b/src/sensors/dr16.hpp index a095c152..ea4e798e 100644 --- a/src/sensors/dr16.hpp +++ b/src/sensors/dr16.hpp @@ -2,6 +2,8 @@ #define DR16_HPP #include // for access to fixed-width types +#include "Arduino.h" // for access to HardwareSerial defines +#include "Transmitter.hpp" constexpr uint16_t DR16_PACKET_SIZE = 18; // the size in bytes of a DR16-Receiver packet constexpr uint16_t DR16_INPUT_VALUE_COUNT = 7; // the size in floats of the normalized input @@ -62,74 +64,74 @@ constexpr uint32_t DR16_ALIGNMENT_LONG_INTERVAL_THRESHOLD = 1000; // time in us // wheel | Wheel Axis | [364 - 1024 - 1684] /// @brief Wrapper for reading and mapping input from the DR16-Receiver and associated controller -class DR16 { +class DR16 : public Transmitter { public: /// @brief Constructor, left empty DR16(); /// @brief Initializes DR16 receiver, starts the Serial interface, and zeros input buffers - void init(); + void init() override; /// @brief Attempts to read a full packet from the receiver. This function shouldn't be ran more than 100kHz - void read(); + void read() override; /// @brief Zeros the normalized input array - void zero(); + void zero() override; public: /// @brief Returns the fail bit. Set only if invalid packets have been received for more then 250ms /// @return Failure status - uint8_t is_fail() { return m_fail; } + uint8_t is_fail() override { return m_fail; } /// @brief Returns a the current connection status for the dr16 controller /// @return true for connected false for not connected - bool is_connected() { return m_connected; } + bool is_connected() override { return m_connected; } /// @brief Get the 7 float length input buffer. These values are normalized [-1, 1] /// @return float buffer - float* get_input(); + float* get_input() override; /// @brief Get right stick x value /// @return Right stick x value [-1.f, 1.f] - float get_r_stick_x(); + float get_r_stick_x() override; /// @brief Get right stick y value /// @return Right stick y value [-1.f, 1.f] - float get_r_stick_y(); + float get_r_stick_y() override; /// @brief Get left stick x value /// @return Left stick x value [-1.f, 1.f] - float get_l_stick_x(); + float get_l_stick_x() override; /// @brief Get left stick y value /// @return Left stick y value [-1.f, 1.f] - float get_l_stick_y(); + float get_l_stick_y() override; /// @brief Get wheel value /// @return Wheel value [-1.f, 1.f] - float get_wheel(); + float get_wheel() override; /// @brief Get left switch value /// @return Switch value [1, 2, 3] - float get_l_switch(); + SwitchPos get_l_switch() override; /// @brief Get right switch value /// @return Switch value [1, 2, 3] - float get_r_switch(); + SwitchPos get_r_switch() override; /// @brief Prints the normalized input buffer - void print(); + void print() override; /// @brief Prints the raw 18-byte packet from the receiver - void print_raw(); + void print_raw() override; /// @brief Get mouse velocity x /// @return Amount of points since last read - int get_mouse_x(); + std::optional get_mouse_x(); /// @brief Get mouse velocity y /// @return Amount of points since last read - int get_mouse_y(); + std::optional get_mouse_y(); /// @brief Get mouse velocity z (scroll wheel) /// @return Amount of points since last read @@ -137,19 +139,26 @@ class DR16 { /// @brief status of left mouse button /// @return Is left mouse button pressed - bool get_l_mouse_button(); + std::optional get_l_mouse_button(); /// @brief status of right mouse button /// @return Is right mouse button pressed - bool get_r_mouse_button(); + std::optional get_r_mouse_button(); /// @brief Get raw 18-byte packet /// @return 18-byte packet - uint8_t* get_raw() { return m_inputRaw; } + uint8_t* get_raw() override { return m_inputRaw; } + + std::optional get_keys() override { + return keys; + } + /// @brief getter for transmitter data + /// @return Filled Transmitter data struct + TransmitterData get_transmitter_data(); /// @brief A simple check to see if read data is within expected values /// @return True/false whether data is deemed valid or not - bool is_data_valid(); + bool is_data_valid() override; private: /// @brief Maps the input value to a specified value range /// @param value the input value @@ -160,65 +169,18 @@ class DR16 { /// @return Mapped input in the range of [out_low, out_high] float bounded_map(int value, int in_low, int in_high, int out_low, int out_high); - - /// @brief Keep track of mouse x velocity - int16_t mouse_x; + int16_t mouse_x = 0; /// @brief Keep track of mouse y velocity - int16_t mouse_y; + int16_t mouse_y = 0; /// @brief Keep track of mouse z velocity (scroll wheel) - int16_t mouse_z; - + int16_t mouse_z = 0; /// @brief Keep track of left mouse button status - bool l_mouse_button; + bool l_mouse_button = 0; /// @brief Keep track of right mouse button status - bool r_mouse_button; + bool r_mouse_button = 0; public: - - /// @brief keeps track of keys pressed on the rm client - struct Keys { - // just testing with keys at the moment - // but will eventually implement - // the mouse functionalities. - - /// @brief If the key 'w' is pressed - bool w; - /// @brief If the key 's' is pressed - bool s; - /// @brief if the key 'a' is pressed - bool a; - /// @brief if the key 'd' is pressed - bool d; - /// @brief if the key 'shift' is pressed - bool shift; - /// @brief if the key 'ctrl' is pressed - bool ctrl; - /// @brief if the key 'q' is pressed - bool q; - /// @brief if the key 'e' is pressed - bool e; - /// @brief if the key 'r' is pressed - bool r; - /// @brief if the key 'f' is pressed - bool f; - /// @brief if the key 'g' is pressed - bool g; - /// @brief if the key 'z' is pressed - bool z; - /// @brief if the key 'x' is pressed - bool x; - /// @brief if the key 'c' is pressed - bool c; - /// @brief if the key 'v' is pressed - bool v; - /// @brief if the key 'b' is pressed - bool b; - }; - - /// @brief struct instance to keep track of the rm control data - Keys keys; - /// @brief normalized input buffer float m_input[DR16_INPUT_VALUE_COUNT] = { 0 };