![]() |
DUNE: Uniform Navigational Environment
2024.09.0
|
Device driver for the Water Linked DVL-A50 and DVL-A125.
Public Member Functions | |
| Task (const std::string &name, Tasks::Context &ctx) | |
| void | onUpdateParameters (void) |
| void | onEntityReservation (void) |
| void | onIdle (void) override |
| bool | onConnect () override |
| void | onDisconnect () override |
| void | onInitializeDevice () override |
| void | consume (const IMC::VehicleMedium *msg) |
| void | checkStatus () |
| void | onSoundSpeed (const double sound_speed) override |
| bool | onReadData () override |
| void | displayConfig (void) |
Public Attributes | |
| std::unique_ptr< Driver > | m_driver |
| std::unique_ptr< IO::Handle > | m_io |
| IMC::Distance | m_alt_dvl |
| IMC::Distance | m_alt_flt |
| Navigation::BeamFilter * | m_filter |
| std::vector< unsigned > | m_entities |
| DUNE::Monitors::MediumHandler | m_hand |
| Counter< double > | m_wdog |
| Counter< double > | m_out_water_wdog |
| double | m_last_sspeed |
| Arguments | m_args |
|
inline |
Constructor.
| [in] | name | task name. |
| [in] | ctx | context. |
References Sensors::WaterLinkedDVL::Arguments::beam_angle, Sensors::WaterLinkedDVL::Arguments::beam_width, Sensors::WaterLinkedDVL::Arguments::dvl_model, Sensors::WaterLinkedDVL::Arguments::io_dev, Sensors::WaterLinkedDVL::Arguments::orientation, Sensors::WaterLinkedDVL::Arguments::position, Sensors::WaterLinkedDVL::Arguments::pwr_channel, and Sensors::WaterLinkedDVL::Arguments::type_activation.
|
inline |
Check for device faults.
| [in] | status | device status (0 -> OK; 1 -> fault). |
|
inline |
|
inline |
Set entity state description.
References Sensors::WaterLinkedDVL::Configuration::acoustic_enabled, and Sensors::WaterLinkedDVL::Configuration::speed_of_sound.
|
inlineoverride |
Try to connect to the device.
References Sensors::WaterLinkedDVL::Arguments::io_dev.
|
inlineoverride |
Disconnect from device.
|
inline |
Reserve entity identifiers.
|
inlineoverride |
Restart device when idle.
References DUNE::Monitors::MediumHandler::inWater().
|
inlineoverride |
Initialize device.
References Sensors::WaterLinkedDVL::Arguments::beam_angle, Sensors::WaterLinkedDVL::Arguments::beam_width, Sensors::WaterLinkedDVL::Arguments::dvl_model, Sensors::WaterLinkedDVL::Arguments::orientation, Sensors::WaterLinkedDVL::Arguments::position, and Sensors::WaterLinkedDVL::Arguments::type_activation.
|
inlineoverride |
Get data from device.
|
inlineoverride |
|
inline |
Update internal state with new parameter values.
References Sensors::WaterLinkedDVL::Arguments::beam_width, Sensors::WaterLinkedDVL::Arguments::orientation, Sensors::WaterLinkedDVL::Arguments::position, and Sensors::WaterLinkedDVL::Arguments::pwr_channel.
| IMC::Distance Sensors::WaterLinkedDVL::Task::m_alt_dvl |
DVL altitude estimate.
| IMC::Distance Sensors::WaterLinkedDVL::Task::m_alt_flt |
Filtered Altitude.
| std::vector<unsigned> Sensors::WaterLinkedDVL::Task::m_entities |
List of entities.
| Navigation::BeamFilter* Sensors::WaterLinkedDVL::Task::m_filter |
Beam Filter.
| DUNE::Monitors::MediumHandler Sensors::WaterLinkedDVL::Task::m_hand |
Medium handler.
| std::unique_ptr<IO::Handle> Sensors::WaterLinkedDVL::Task::m_io |
IO Handle.
| double Sensors::WaterLinkedDVL::Task::m_last_sspeed |
Last sound speed.
| Counter<double> Sensors::WaterLinkedDVL::Task::m_out_water_wdog |
Out of water watchdog.
| Counter<double> Sensors::WaterLinkedDVL::Task::m_wdog |
Communication watchdog.
