![]() |
DUNE: Uniform Navigational Environment
2.4.0
|
Public Member Functions | |
| Task (const std::string &name, Tasks::Context &ctx) | |
| void | onUpdateParameters (void) |
| void | onResourceRelease (void) |
| void | onEntityResolution (void) |
| void | onResourceInitialization (void) |
| bool | setup (void) |
| void | reset (void) |
| void | runKalmanGPS (double x, double y) |
| void | runKalmanLBL (int beacon, float range, double dx, double dy, double exp_range) |
| void | getSpeedOutputStates (unsigned *u, unsigned *v) |
| unsigned | getNumberOutputs (void) |
| void | task (void) |
Public Member Functions inherited from DUNE::Navigation::BasicNavigation | |
| BasicNavigation (const std::string &name, Tasks::Context &ctx) | |
| virtual | ~BasicNavigation (void) |
| void | consume (const IMC::Acceleration *msg) |
| void | consume (const IMC::AngularVelocity *msg) |
| void | consume (const IMC::DataSanity *msg) |
| void | consume (const IMC::Distance *msg) |
| void | consume (const IMC::Depth *msg) |
| void | consume (const IMC::DepthOffset *msg) |
| void | consume (const IMC::EulerAngles *msg) |
| void | consume (const IMC::EulerAnglesDelta *msg) |
| void | consume (const IMC::GpsFix *msg) |
| void | consume (const IMC::GroundVelocity *msg) |
| void | consume (const IMC::LblConfig *msg) |
| void | consume (const IMC::LblRange *msg) |
| void | consume (const IMC::Rpm *msg) |
| void | consume (const IMC::WaterVelocity *msg) |
Public Member Functions inherited from DUNE::Tasks::Periodic | |
| Periodic (const std::string &name, Context &ctx) | |
| virtual | ~Periodic (void) |
| void | setFrequency (double freq) |
| double | getFrequency (void) const |
| double | getRunTime (void) const |
| unsigned | getRunCount (void) const |
Public Member Functions inherited from DUNE::Tasks::Task | |
| Task (const std::string &name, Context &context) | |
| virtual | ~Task (void) |
| const char * | getName (void) const |
| const char * | getSystemName (void) const |
| unsigned int | getSystemId (void) const |
| unsigned int | getEntityId (void) const |
| uint16_t | getActivationTime (void) const |
| uint16_t | getDeactivationTime (void) const |
| unsigned int | resolveSystemName (const std::string &name) const |
| const char * | resolveSystemId (unsigned int id) const |
| void | loadConfig (void) |
| void | setPriority (unsigned int value) |
| unsigned int | getPriority (void) const |
| void | inf (const char *format,...) DUNE_PRINTF_FORMAT(2 |
| void void | war (const char *format,...) DUNE_PRINTF_FORMAT(2 |
| void void void | err (const char *format,...) DUNE_PRINTF_FORMAT(2 |
| void void void void | cri (const char *format,...) DUNE_PRINTF_FORMAT(2 |
| void void void void void | debug (const char *format,...) DUNE_PRINTF_FORMAT(2 |
| void void void void void void | trace (const char *format,...) DUNE_PRINTF_FORMAT(2 |
| void void void void void void void | spew (const char *format,...) DUNE_PRINTF_FORMAT(2 |
| void void void void void void void void | dispatch (IMC::Message *msg, unsigned int flags=0) |
| void | dispatch (IMC::Message &msg, unsigned int flags=0) |
| void | dispatchReply (const IMC::Message &original, IMC::Message &msg, unsigned int flags=0) |
| void | receive (const IMC::Message *msg) |
| void | reserveEntities (void) |
| void | resolveEntities (void) |
| void | acquireResources (void) |
| void | releaseResources (void) |
| void | initializeResources (void) |
| void | updateParameters (bool act_deact=true) |
| void | writeParamsXML (std::ostream &os) const |
Public Member Functions inherited from DUNE::Tasks::AbstractTask | |
| AbstractTask (void) | |
| virtual | ~AbstractTask (void) |
Public Member Functions inherited from DUNE::Concurrency::Thread | |
| Thread (void) | |
| virtual | ~Thread (void) |
| int | getProcessorUsage (void) |
Public Member Functions inherited from DUNE::Concurrency::Runnable | |
| Runnable (void) | |
| virtual | ~Runnable (void) |
| void | start (void) |
| void | stop (void) |
| void | join (void) |
| void | stopAndJoin (void) |
| void | setPriority (Scheduler::Policy policy, unsigned priority) |
| State | getState (void) |
| bool | isCreated (void) |
| bool | isStopping (void) |
| bool | isRunning (void) |
| bool | isStarting (void) |
| bool | isDead (void) |
Public Attributes | |
| Arguments | m_args |
Additional Inherited Members | |
Public Types inherited from DUNE::Concurrency::Runnable | |
| enum | State { StateStarting, StateRunning, StateStopping, StateDead, StateUnknown } |
Protected Member Functions inherited from DUNE::Navigation::BasicNavigation | |
| double | getDepth (void) const |
| double | getAltitude (void) |
| double | getAcceleration (unsigned axis) const |
| double | getAngularVelocity (unsigned axis) const |
| double | getHeadingRate (void) |
| double | getEuler (unsigned axis) const |
| double | getEulerDelta (unsigned axis) const |
| float | getEulerDeltaTimestep (void) const |
| bool | gotDepthReadings (void) const |
| bool | gotEulerReadings (void) const |
| bool | gotAngularReadings (void) const |
| bool | gotAccelerationReadings (void) const |
| unsigned | getAhrsId (void) const |
| double | getLblRejectionValue (double exp_range) const |
| bool | rejectLbl (void) const |
| double | getTimeStep (void) |
| void | updateEuler (float filter) |
| void | updateEulerDelta (float filter) |
| void | updateAngularVelocities (float filter) |
| void | updateAcceleration (float filter) |
| void | updateDepth (float filter) |
| virtual void | onConsumeLblConfig (void) |
| virtual void | updateKalmanGpsParameters (double hacc) |
| virtual void | runKalmanDVL (void) |
| virtual void | correctAlignment (double psi) |
| void | onDispatchNavigation (void) |
| bool | isActive (void) |
| void | reportToBus (void) |
| void | updateBuffers (float filter) |
| void | resetAcceleration (void) |
| void | resetAngularVelocity (void) |
| void | resetDepth (void) |
| void | resetEulerAngles (void) |
| void | resetEulerAnglesDelta (void) |
| void | checkUncertainty (void) |
| void | checkDeclination (double lat, double lon, double height) |
Protected Member Functions inherited from DUNE::Tasks::Task | |
| const char * | getEntityLabel (void) const |
| void | setEntityLabel (const std::string &label) |
| void | setEntityState (IMC::EntityState::StateEnum state, Status::Code code) |
| void | setEntityState (IMC::EntityState::StateEnum state, const std::string &description) |
| IMC::EntityState::StateEnum | getEntityState (void) const |
| unsigned int | reserveEntity (const std::string &label) |
| unsigned int | resolveEntity (const std::string &label) const |
| std::string | resolveEntity (unsigned int id) const |
| bool | stopping (void) |
| bool | isActive (void) const |
| void | waitForMessages (double timeout) |
| void | consumeMessages (void) |
| template<typename T > | |
| Parameter & | param (const std::string &name, T &var) |
| template<typename Y , typename T > | |
| Parameter & | param (const std::string &name, T &var) |
| template<typename T > | |
| bool | paramChanged (T &var) |
| void | paramActive (Parameter::Scope def_scope, Parameter::Visibility def_visibility, bool def_value=false) |
| void | setParamSectionEditor (const std::string &name) |
| template<typename M , typename T > | |
| void | bind (T *task_obj, void(T::*consumer)(const M *)=&T::consume) |
| template<typename T > | |
| void | bind (T *task_obj, const std::vector< uint32_t > &list) |
| template<typename T > | |
| void | bind (T *task_obj, const std::vector< std::string > &list) |
| void | requestActivation (void) |
| void | requestDeactivation (void) |
| void | activate (void) |
| void | activationFailed (const std::string &reason) |
| void | deactivate (void) |
| void | deactivationFailed (const std::string &reason) |
| virtual void | onEntityReservation (void) |
| virtual void | onReportEntityState (void) |
| virtual void | onResourceAcquisition (void) |
| virtual void | onRequestActivation (void) |
| virtual void | onRequestDeactivation (void) |
| virtual void | onActivation (void) |
| virtual void | onDeactivation (void) |
Protected Member Functions inherited from DUNE::Concurrency::Thread | |
| void | startImpl (void) |
| void | stopImpl (void) |
| void | joinImpl (void) |
| void | setPriorityImpl (Scheduler::Policy policy, unsigned priority) |
Protected Attributes inherited from DUNE::Navigation::BasicNavigation | |
| Navigation::KalmanFilter | m_kal |
| Navigation::Ranging | m_ranging |
| int16_t | m_rpm |
| std::vector< double > | m_process_noise |
| std::vector< double > | m_measure_noise |
| std::vector< double > | m_state_cov |
| IMC::EstimatedState | m_estate |
| IMC::EstimatedStreamVelocity | m_ewvel |
| IMC::LblRangeAcceptance | m_lbl_ac |
| IMC::GpsFixRejection | m_gps_rej |
| IMC::DvlRejection | m_dvl_rej |
| IMC::NavigationUncertainty | m_uncertainty |
| IMC::NavigationData | m_navdata |
| IMC::GroundVelocity | m_gvel |
| IMC::WaterVelocity | m_wvel |
| Time::Counter< double > | m_time_without_gps |
| Time::Counter< double > | m_time_without_dvl |
| Time::Counter< double > | m_time_without_alt |
| Time::Counter< double > | m_dvl_sanity_timer |
| Time::Counter< double > | m_time_without_main_depth |
| Time::Counter< double > | m_time_without_depth |
| Time::Counter< double > | m_time_without_euler |
| double | m_gps_sog |
| double | m_last_z |
| bool | m_dead_reckoning |
| bool | m_sum_euler_inc |
| bool | m_aligned |
| unsigned | m_agvel_eid |
| unsigned | m_accel_eid |
| unsigned | m_imu_eid |
| unsigned | m_alignment_eid |
| float | m_lbl_threshold |
| double | m_heading |
| bool | m_valid_gv |
| bool | m_valid_wv |
| Math::Derivative< double > | m_deriv_heave |
Protected Attributes inherited from DUNE::Tasks::Task | |
| Context & | m_ctx |
|
inline |
References DUNE::Tasks::Parameter::defaultValue(), Navigation::AUV::Navigation::Arguments::initial_rpm_to_speed, m_args, DUNE::Navigation::BasicNavigation::m_kal, DUNE::Navigation::BasicNavigation::m_measure_noise, DUNE::Navigation::BasicNavigation::m_process_noise, DUNE::Navigation::BasicNavigation::m_state_cov, Navigation::AUV::Navigation::Arguments::max_current, Navigation::AUV::Navigation::NUM_OUT, Navigation::AUV::Navigation::NUM_STATE, DUNE::Tasks::Task::param(), DUNE::Navigation::KalmanFilter::reset(), and DUNE::Tasks::Parameter::units().
|
inlinevirtual |
Get number of EKF outputs.
Implements DUNE::Navigation::BasicNavigation.
References Navigation::AUV::Navigation::NUM_OUT.
|
inlinevirtual |
Get EKF output matrix speed indexes.
| [out] | u | forward speed state index. |
| [out] | v | transversal speed state index. |
Implements DUNE::Navigation::BasicNavigation.
|
inlinevirtual |
Resolve entities.
Reimplemented from DUNE::Navigation::BasicNavigation.
|
inlinevirtual |
Initialize resources.
Reimplemented from DUNE::Navigation::BasicNavigation.
|
inlinevirtual |
Release allocated resources.
Reimplemented from DUNE::Navigation::BasicNavigation.
|
inlinevirtual |
Update internal parameters.
Reimplemented from DUNE::Navigation::BasicNavigation.
References DUNE::Tasks::Periodic::getFrequency(), DUNE::Navigation::BasicNavigation::m_kal, DUNE::Navigation::BasicNavigation::m_measure_noise, DUNE::Navigation::BasicNavigation::m_process_noise, Navigation::AUV::Navigation::OUT_GPS_X, Navigation::AUV::Navigation::OUT_GPS_Y, Navigation::AUV::Navigation::OUT_LBL, DUNE::Navigation::KalmanFilter::setMeasurementNoise(), DUNE::Navigation::KalmanFilter::setProcessNoise(), Navigation::AUV::Navigation::STATE_WX, Navigation::AUV::Navigation::STATE_WY, Navigation::AUV::Navigation::STATE_X, and Navigation::AUV::Navigation::STATE_Y.
|
inlinevirtual |
Routine to reset navigation.
Reimplemented from DUNE::Navigation::BasicNavigation.
|
inlinevirtual |
Routine to assign EKF filter output variables when a GpsFix message is received.
| [in] | x | vehicle north displacement (m). |
| [in] | y | vehicle east displacement (m). |
Reimplemented from DUNE::Navigation::BasicNavigation.
References DUNE::Navigation::KalmanFilter::getState(), DUNE::Navigation::BasicNavigation::m_kal, DUNE::Navigation::BasicNavigation::m_time_without_gps, Navigation::AUV::Navigation::OUT_GPS_X, Navigation::AUV::Navigation::OUT_GPS_Y, DUNE::Time::Counter< T >::reset(), DUNE::Navigation::KalmanFilter::resetOutputs(), DUNE::Navigation::KalmanFilter::setInnovation(), DUNE::Navigation::KalmanFilter::setObservation(), Navigation::AUV::Navigation::STATE_X, Navigation::AUV::Navigation::STATE_Y, and DUNE::Navigation::KalmanFilter::update().
|
inlinevirtual |
Routine to assign EKF filter output variables when a GpsFix message is received.
| [in] | beacon | beacon id. |
| [in] | range | range to beacon. |
| [in] | dx | distance along x-axis. |
| [in] | dy | distance along y-axis. |
| [in] | exp_range | expected range. |
Reimplemented from DUNE::Navigation::BasicNavigation.
References DUNE::IMC::LblRangeAcceptance::acceptance, DUNE::Tasks::Task::dispatch(), DUNE::Navigation::KalmanFilter::getCovariance(), DUNE::Navigation::BasicNavigation::getLblRejectionValue(), DUNE::Navigation::KalmanFilter::getObservation(), DUNE::IMC::NavigationData::lbl_rej_level, DUNE::Navigation::BasicNavigation::m_kal, DUNE::Navigation::BasicNavigation::m_lbl_ac, DUNE::Navigation::BasicNavigation::m_lbl_threshold, DUNE::Navigation::BasicNavigation::m_navdata, Navigation::AUV::Navigation::OUT_LBL, DUNE::Navigation::KalmanFilter::resetOutputs(), DUNE::Navigation::KalmanFilter::setInnovation(), DUNE::Navigation::KalmanFilter::setMeasurementNoise(), DUNE::Navigation::KalmanFilter::setObservation(), Navigation::AUV::Navigation::STATE_X, Navigation::AUV::Navigation::STATE_Y, DUNE::Math::transpose(), and DUNE::Navigation::KalmanFilter::update().
|
inlinevirtual |
Routine to setup navigation.
Reimplemented from DUNE::Navigation::BasicNavigation.
References Navigation::AUV::Navigation::Arguments::initial_rpm_to_speed, m_args, DUNE::Navigation::BasicNavigation::m_kal, DUNE::Navigation::BasicNavigation::m_state_cov, DUNE::Navigation::KalmanFilter::setCovariance(), DUNE::Navigation::KalmanFilter::setState(), Navigation::AUV::Navigation::STATE_K, Navigation::AUV::Navigation::STATE_WX, Navigation::AUV::Navigation::STATE_WY, Navigation::AUV::Navigation::STATE_X, and Navigation::AUV::Navigation::STATE_Y.
|
inlinevirtual |
The task to be executed on each cycle.
Implements DUNE::Tasks::Periodic.
References DUNE::Navigation::BasicNavigation::checkUncertainty(), DUNE::IMC::NavigationData::cog, DUNE::IMC::NavigationData::custom_x, DUNE::IMC::NavigationData::custom_y, DUNE::IMC::NavigationData::custom_z, DUNE::Navigation::BasicNavigation::getAngularVelocity(), DUNE::Navigation::KalmanFilter::getCovariance(), DUNE::Navigation::BasicNavigation::getEuler(), DUNE::Navigation::KalmanFilter::getState(), DUNE::Navigation::BasicNavigation::getTimeStep(), m_args, DUNE::Navigation::BasicNavigation::m_estate, DUNE::Navigation::BasicNavigation::m_ewvel, DUNE::Navigation::BasicNavigation::m_heading, DUNE::Navigation::BasicNavigation::m_kal, DUNE::Navigation::BasicNavigation::m_navdata, DUNE::Navigation::BasicNavigation::m_process_noise, DUNE::Navigation::BasicNavigation::m_rpm, DUNE::Navigation::BasicNavigation::m_uncertainty, Navigation::AUV::Navigation::Arguments::max_current, Navigation::AUV::Navigation::NUM_STATE, DUNE::Navigation::BasicNavigation::onDispatchNavigation(), DUNE::Navigation::KalmanFilter::predict(), DUNE::IMC::EstimatedState::psi, DUNE::IMC::EstimatedState::r, DUNE::Navigation::BasicNavigation::reportToBus(), DUNE::Navigation::KalmanFilter::setProcessNoise(), DUNE::Navigation::KalmanFilter::setState(), DUNE::Navigation::KalmanFilter::setTransitions(), Navigation::AUV::Navigation::STATE_K, Navigation::AUV::Navigation::STATE_WX, Navigation::AUV::Navigation::STATE_WY, Navigation::AUV::Navigation::STATE_X, Navigation::AUV::Navigation::STATE_Y, DUNE::IMC::EstimatedState::theta, DUNE::IMC::EstimatedState::u, DUNE::IMC::NavigationUncertainty::u, DUNE::Navigation::BasicNavigation::updateBuffers(), DUNE::IMC::EstimatedState::vx, DUNE::IMC::EstimatedState::vy, DUNE::IMC::EstimatedStreamVelocity::x, DUNE::IMC::EstimatedStreamVelocity::y, and DUNE::IMC::EstimatedStreamVelocity::z.
| Arguments Navigation::AUV::Navigation::Task::m_args |
