From 2750961be67d03de092aae4f4a540182c33b3dc0 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sun, 5 Feb 2017 13:05:10 -0500 Subject: [PATCH] c++11 initialization cleanup (#237) --- EKF/ekf.cpp | 4 - EKF/ekf.h | 20 ++-- EKF/ekf_helper.cpp | 2 +- EKF/estimator_interface.cpp | 9 +- EKF/estimator_interface.h | 10 +- EKF/gps_checks.cpp | 2 - attitude_fw/ecl_controller.cpp | 10 +- attitude_fw/ecl_controller.h | 3 +- attitude_fw/ecl_pitch_controller.cpp | 10 +- attitude_fw/ecl_pitch_controller.h | 3 +- attitude_fw/ecl_roll_controller.cpp | 4 - attitude_fw/ecl_roll_controller.h | 3 +- attitude_fw/ecl_wheel_controller.cpp | 134 +++++++++++++-------------- attitude_fw/ecl_wheel_controller.h | 12 +-- attitude_fw/ecl_yaw_controller.cpp | 4 - attitude_fw/ecl_yaw_controller.h | 4 +- validation/data_validator.cpp | 5 - validation/data_validator.h | 2 +- 18 files changed, 102 insertions(+), 139 deletions(-) diff --git a/EKF/ekf.cpp b/EKF/ekf.cpp index f98e7a3a0b..5aa691f325 100644 --- a/EKF/ekf.cpp +++ b/EKF/ekf.cpp @@ -146,10 +146,6 @@ Ekf::Ekf(): _dt_ekf_avg = 0.001f * (float)(FILTER_UPDATE_PERIOD_MS); } -Ekf::~Ekf() -{ -} - bool Ekf::init(uint64_t timestamp) { bool ret = initialise_interface(timestamp); diff --git a/EKF/ekf.h b/EKF/ekf.h index 8c66d61834..8b53c20a04 100644 --- a/EKF/ekf.h +++ b/EKF/ekf.h @@ -48,7 +48,7 @@ class Ekf : public EstimatorInterface public: Ekf(); - ~Ekf(); + ~Ekf() = default; // initialise variables to sane values (also interface class) bool init(uint64_t timestamp); @@ -245,13 +245,13 @@ private: matrix::Dcm _R_to_earth; // transformation matrix from body frame to earth frame from last EKF predition - float P[_k_num_states][_k_num_states]; // state covariance matrix + float P[_k_num_states][_k_num_states]{}; // state covariance matrix - float _vel_pos_innov[6]; // innovations: 0-2 vel, 3-5 pos - float _vel_pos_innov_var[6]; // innovation variances: 0-2 vel, 3-5 pos + float _vel_pos_innov[6]{}; // innovations: 0-2 vel, 3-5 pos + float _vel_pos_innov_var[6]{}; // innovation variances: 0-2 vel, 3-5 pos - float _mag_innov[3]; // earth magnetic field innovations - float _mag_innov_var[3]; // earth magnetic field innovation variance + float _mag_innov[3]{}; // earth magnetic field innovations + float _mag_innov_var[3]{}; // earth magnetic field innovation variance float _airspeed_innov; // airspeed measurement innovation float _airspeed_innov_var; // airspeed measurement innovation variance @@ -263,8 +263,8 @@ private: float _heading_innov_var; // heading measurement innovation variance // optical flow processing - float _flow_innov[2]; // flow measurement innovation - float _flow_innov_var[2]; // flow innovation variance + float _flow_innov[2]{}; // flow measurement innovation + float _flow_innov_var[2]{}; // flow innovation variance Vector3f _flow_gyro_bias; // bias errors in optical flow sensor rate gyro outputs Vector3f _imu_del_ang_of; // bias corrected delta angle measurements accumulated across the same time frame as the optical flow rates float _delta_time_of; // time in sec that _imu_del_ang_of was accumulated over @@ -277,7 +277,7 @@ private: Quaternion _q_down_sampled; // down sampled quaternion (tracking delta angles between ekf update steps) Vector3f _vel_err_integ; // integral of velocity tracking error Vector3f _pos_err_integ; // integral of position tracking error - float _output_tracking_error[3];// contains the magnitude of the angle, velocity and position track errors (rad, m/s, m) + float _output_tracking_error[3]{};// contains the magnitude of the angle, velocity and position track errors (rad, m/s, m) // variables used for the GPS quality checks float _gpsDriftVelN; // GPS north position derivative (m/s) @@ -306,7 +306,7 @@ private: // Variables used to control activation of post takeoff functionality float _last_on_ground_posD; // last vertical position when the in_air status was false (m) - gps_check_fail_status_u _gps_check_fail_status; + gps_check_fail_status_u _gps_check_fail_status{}; // Terrain height state estimation float _terrain_vpos; // estimated vertical position of the terrain underneath the vehicle in local NED frame (m) diff --git a/EKF/ekf_helper.cpp b/EKF/ekf_helper.cpp index 33403a14b6..e011f36af3 100644 --- a/EKF/ekf_helper.cpp +++ b/EKF/ekf_helper.cpp @@ -774,7 +774,7 @@ void Ekf::get_innovation_test_status(uint16_t *status, float *mag, float *vel, f // return a bitmask integer that describes which state estimates are valid void Ekf::get_ekf_soln_status(uint16_t *status) { - ekf_solution_status soln_status; + ekf_solution_status soln_status{}; soln_status.flags.attitude = _control_status.flags.tilt_align && _control_status.flags.yaw_align && (_fault_status.value == 0); soln_status.flags.velocity_horiz = (_control_status.flags.gps || _control_status.flags.ev_pos || _control_status.flags.opt_flow) && (_fault_status.value == 0); soln_status.flags.velocity_vert = (_control_status.flags.baro_hgt || _control_status.flags.ev_hgt || _control_status.flags.gps_hgt || _control_status.flags.rng_hgt) && (_fault_status.value == 0); diff --git a/EKF/estimator_interface.cpp b/EKF/estimator_interface.cpp index 0d95fe8456..87aafae8fa 100644 --- a/EKF/estimator_interface.cpp +++ b/EKF/estimator_interface.cpp @@ -89,11 +89,6 @@ EstimatorInterface::EstimatorInterface(): _delta_vel_prev.setZero(); } -EstimatorInterface::~EstimatorInterface() -{ - -} - // Accumulate imu data and store to buffer at desired rate void EstimatorInterface::setIMUData(uint64_t time_usec, uint64_t delta_ang_dt, uint64_t delta_vel_dt, float (&delta_ang)[3], float (&delta_vel)[3]) @@ -227,7 +222,7 @@ void EstimatorInterface::setBaroData(uint64_t time_usec, float data) // limit data rate to prevent data being lost if (time_usec - _time_last_baro > _min_obs_interval_us) { - baroSample baro_sample_new; + baroSample baro_sample_new{}; baro_sample_new.hgt = data; baro_sample_new.time_us = time_usec - _params.baro_delay_ms * 1000; @@ -248,7 +243,7 @@ void EstimatorInterface::setAirspeedData(uint64_t time_usec, float true_airspeed // limit data rate to prevent data being lost if (time_usec - _time_last_airspeed > _min_obs_interval_us) { - airspeedSample airspeed_sample_new; + airspeedSample airspeed_sample_new{}; airspeed_sample_new.true_airspeed = true_airspeed; airspeed_sample_new.eas2tas = eas2tas; airspeed_sample_new.time_us = time_usec - _params.airspeed_delay_ms * 1000; diff --git a/EKF/estimator_interface.h b/EKF/estimator_interface.h index 31ed4b4332..fd9d983448 100644 --- a/EKF/estimator_interface.h +++ b/EKF/estimator_interface.h @@ -52,7 +52,7 @@ class EstimatorInterface public: EstimatorInterface(); - ~EstimatorInterface(); + ~EstimatorInterface() = default; virtual bool init(uint64_t timestamp) = 0; virtual bool update() = 0; @@ -328,7 +328,7 @@ protected: float _tas_test_ratio; // tas innovation consistency check ratio float _terr_test_ratio; // height above terrain measurement innovation consistency check ratio float _beta_test_ratio; // sideslip innovation consistency check ratio - innovation_fault_status_u _innov_check_fail_status; + innovation_fault_status_u _innov_check_fail_status{}; // IMU vibration monitoring Vector3f _delta_ang_prev; // delta angle from the previous IMU measurement @@ -358,7 +358,7 @@ protected: uint64_t _time_last_ext_vision; // timestamp of last external vision measurement in microseconds uint64_t _time_last_optflow; - fault_status_u _fault_status; + fault_status_u _fault_status{}; // allocate data buffers and intialise interface variables bool initialise_interface(uint64_t timestamp); @@ -370,10 +370,10 @@ protected: float _mag_declination_to_save_deg; // magnetic declination to save to EKF2_MAG_DECL (deg) // this is the current status of the filter control modes - filter_control_status_u _control_status; + filter_control_status_u _control_status{}; // this is the previous status of the filter control modes - used to detect mode transitions - filter_control_status_u _control_status_prev; + filter_control_status_u _control_status_prev{}; // perform a vector cross product Vector3f cross_product(const Vector3f &vecIn1, const Vector3f &vecIn2); diff --git a/EKF/gps_checks.cpp b/EKF/gps_checks.cpp index 29d83281f7..9a96a8af40 100644 --- a/EKF/gps_checks.cpp +++ b/EKF/gps_checks.cpp @@ -99,8 +99,6 @@ bool Ekf::collect_gps(uint64_t time_usec, struct gps_message *gps) // start collecting GPS if there is a 3D fix and the NED origin has been set return _NED_origin_initialised && (gps->fix_type >= 3); - - return false; } /* diff --git a/attitude_fw/ecl_controller.cpp b/attitude_fw/ecl_controller.cpp index bb313b22b1..213b601838 100644 --- a/attitude_fw/ecl_controller.cpp +++ b/attitude_fw/ecl_controller.cpp @@ -67,10 +67,6 @@ ECL_Controller::ECL_Controller(const char *name) : { } -ECL_Controller::~ECL_Controller() -{ -} - void ECL_Controller::reset_integrator() { _integrator = 0.0f; @@ -123,13 +119,17 @@ float ECL_Controller::get_desired_bodyrate() return _bodyrate_setpoint; } -float ECL_Controller::constrain_airspeed(float airspeed, float minspeed, float maxspeed) { +float ECL_Controller::constrain_airspeed(float airspeed, float minspeed, float maxspeed) +{ float airspeed_result = airspeed; + if (!PX4_ISFINITE(airspeed)) { /* airspeed is NaN, +- INF or not available, pick center of band */ airspeed_result = 0.5f * (minspeed + maxspeed); + } else if (airspeed < minspeed) { airspeed_result = minspeed; } + return airspeed_result; } diff --git a/attitude_fw/ecl_controller.h b/attitude_fw/ecl_controller.h index 9c41222da3..2b9d1b6761 100644 --- a/attitude_fw/ecl_controller.h +++ b/attitude_fw/ecl_controller.h @@ -84,8 +84,7 @@ class __EXPORT ECL_Controller { public: ECL_Controller(const char *name); - - ~ECL_Controller(); + ~ECL_Controller() = default; virtual float control_attitude(const struct ECL_ControlData &ctl_data) = 0; virtual float control_bodyrate(const struct ECL_ControlData &ctl_data) = 0; diff --git a/attitude_fw/ecl_pitch_controller.cpp b/attitude_fw/ecl_pitch_controller.cpp index 5c9f3150a6..30ab2b2e85 100644 --- a/attitude_fw/ecl_pitch_controller.cpp +++ b/attitude_fw/ecl_pitch_controller.cpp @@ -54,10 +54,6 @@ ECL_PitchController::ECL_PitchController() : { } -ECL_PitchController::~ECL_PitchController() -{ -} - float ECL_PitchController::control_attitude(const struct ECL_ControlData &ctl_data) { @@ -124,6 +120,7 @@ float ECL_PitchController::control_bodyrate(const struct ECL_ControlData &ctl_da /* flying inverted (wings upside down)*/ bool inverted = false; float constrained_roll; + /* roll is used as feedforward term and inverted flight needs to be considered */ if (fabsf(ctl_data.roll) < math::radians(90.0f)) { /* not inverted, but numerically still potentially close to infinity */ @@ -132,6 +129,7 @@ float ECL_PitchController::control_bodyrate(const struct ECL_ControlData &ctl_da } else { /* inverted flight, constrain on the two extremes of -pi..+pi to avoid infinity */ inverted = true; + /* note: the ranges are extended by 10 deg here to avoid numeric resolution effects */ if (ctl_data.roll > 0.0f) { /* right hemisphere */ @@ -148,10 +146,10 @@ float ECL_PitchController::control_bodyrate(const struct ECL_ControlData &ctl_da /* Calculate desired body fixed y-axis angular rate needed to compensate for roll angle. For reference see Automatic Control of Aircraft and Missiles by John H. Blakelock, pg. 175 - Availible on google books 8/11/2015: + Availible on google books 8/11/2015: https://books.google.com/books?id=ubcczZUDCsMC&pg=PA175#v=onepage&q&f=false*/ float body_fixed_turn_offset = (fabsf((CONSTANTS_ONE_G / airspeed) * - tanf(constrained_roll) * sinf(constrained_roll))); + tanf(constrained_roll) * sinf(constrained_roll))); if (inverted) { body_fixed_turn_offset = -body_fixed_turn_offset; diff --git a/attitude_fw/ecl_pitch_controller.h b/attitude_fw/ecl_pitch_controller.h index fa7612cb99..820dcdd3a4 100644 --- a/attitude_fw/ecl_pitch_controller.h +++ b/attitude_fw/ecl_pitch_controller.h @@ -59,8 +59,7 @@ class __EXPORT ECL_PitchController : { public: ECL_PitchController(); - - ~ECL_PitchController(); + ~ECL_PitchController() = default; float control_attitude(const struct ECL_ControlData &ctl_data); float control_bodyrate(const struct ECL_ControlData &ctl_data); diff --git a/attitude_fw/ecl_roll_controller.cpp b/attitude_fw/ecl_roll_controller.cpp index d1c9177c8d..26be7c19c7 100644 --- a/attitude_fw/ecl_roll_controller.cpp +++ b/attitude_fw/ecl_roll_controller.cpp @@ -52,10 +52,6 @@ ECL_RollController::ECL_RollController() : { } -ECL_RollController::~ECL_RollController() -{ -} - float ECL_RollController::control_attitude(const struct ECL_ControlData &ctl_data) { /* Do not calculate control signal with bad inputs */ diff --git a/attitude_fw/ecl_roll_controller.h b/attitude_fw/ecl_roll_controller.h index 6d07bab8ab..f8681010d9 100644 --- a/attitude_fw/ecl_roll_controller.h +++ b/attitude_fw/ecl_roll_controller.h @@ -59,8 +59,7 @@ class __EXPORT ECL_RollController : { public: ECL_RollController(); - - ~ECL_RollController(); + ~ECL_RollController() = default; float control_attitude(const struct ECL_ControlData &ctl_data); float control_bodyrate(const struct ECL_ControlData &ctl_data); diff --git a/attitude_fw/ecl_wheel_controller.cpp b/attitude_fw/ecl_wheel_controller.cpp index 7cae0316dd..1a04d39211 100644 --- a/attitude_fw/ecl_wheel_controller.cpp +++ b/attitude_fw/ecl_wheel_controller.cpp @@ -48,103 +48,99 @@ #include ECL_WheelController::ECL_WheelController() : - ECL_Controller("wheel") -{ -} - -ECL_WheelController::~ECL_WheelController() + ECL_Controller("wheel") { } float ECL_WheelController::control_bodyrate(const struct ECL_ControlData &ctl_data) { - /* Do not calculate control signal with bad inputs */ - if (!(PX4_ISFINITE(ctl_data.yaw_rate) && - PX4_ISFINITE(ctl_data.groundspeed) && - PX4_ISFINITE(ctl_data.groundspeed_scaler))) { - return math::constrain(_last_output, -1.0f, 1.0f); - } + /* Do not calculate control signal with bad inputs */ + if (!(PX4_ISFINITE(ctl_data.yaw_rate) && + PX4_ISFINITE(ctl_data.groundspeed) && + PX4_ISFINITE(ctl_data.groundspeed_scaler))) { + return math::constrain(_last_output, -1.0f, 1.0f); + } - /* get the usual dt estimate */ - uint64_t dt_micros = ecl_elapsed_time(&_last_run); - _last_run = ecl_absolute_time(); - float dt = (float)dt_micros * 1e-6f; + /* get the usual dt estimate */ + uint64_t dt_micros = ecl_elapsed_time(&_last_run); + _last_run = ecl_absolute_time(); + float dt = (float)dt_micros * 1e-6f; - /* lock integral for long intervals */ - bool lock_integrator = ctl_data.lock_integrator; + /* lock integral for long intervals */ + bool lock_integrator = ctl_data.lock_integrator; - if (dt_micros > 500000) { - lock_integrator = true; - } + if (dt_micros > 500000) { + lock_integrator = true; + } - /* input conditioning */ - float min_speed = 1.0f; + /* input conditioning */ + float min_speed = 1.0f; - /* Calculate body angular rate error */ - _rate_error = _rate_setpoint - ctl_data.yaw_rate; //body angular rate error + /* Calculate body angular rate error */ + _rate_error = _rate_setpoint - ctl_data.yaw_rate; //body angular rate error - if (!lock_integrator && _k_i > 0.0f && ctl_data.groundspeed > min_speed) { + if (!lock_integrator && _k_i > 0.0f && ctl_data.groundspeed > min_speed) { - float id = _rate_error * dt * ctl_data.groundspeed_scaler; + float id = _rate_error * dt * ctl_data.groundspeed_scaler; - /* - * anti-windup: do not allow integrator to increase if actuator is at limit - */ - if (_last_output < -1.0f) { - /* only allow motion to center: increase value */ - id = math::max(id, 0.0f); + /* + * anti-windup: do not allow integrator to increase if actuator is at limit + */ + if (_last_output < -1.0f) { + /* only allow motion to center: increase value */ + id = math::max(id, 0.0f); - } else if (_last_output > 1.0f) { - /* only allow motion to center: decrease value */ - id = math::min(id, 0.0f); - } + } else if (_last_output > 1.0f) { + /* only allow motion to center: decrease value */ + id = math::min(id, 0.0f); + } - _integrator += id * _k_i; - } + _integrator += id * _k_i; + } - /* integrator limit */ - //xxx: until start detection is available: integral part in control signal is limited here - float integrator_constrained = math::constrain(_integrator, -_integrator_max, _integrator_max); + /* integrator limit */ + //xxx: until start detection is available: integral part in control signal is limited here + float integrator_constrained = math::constrain(_integrator, -_integrator_max, _integrator_max); - /* Apply PI rate controller and store non-limited output */ - _last_output = _rate_setpoint * _k_ff * ctl_data.groundspeed_scaler + - _rate_error * _k_p * ctl_data.groundspeed_scaler * ctl_data.groundspeed_scaler + - integrator_constrained; - /*warnx("wheel: _last_output: %.4f, _integrator: %.4f, scaler %.4f", - (double)_last_output, (double)_integrator, (double)ctl_data.groundspeed_scaler);*/ + /* Apply PI rate controller and store non-limited output */ + _last_output = _rate_setpoint * _k_ff * ctl_data.groundspeed_scaler + + _rate_error * _k_p * ctl_data.groundspeed_scaler * ctl_data.groundspeed_scaler + + integrator_constrained; + /*warnx("wheel: _last_output: %.4f, _integrator: %.4f, scaler %.4f", + (double)_last_output, (double)_integrator, (double)ctl_data.groundspeed_scaler);*/ - return math::constrain(_last_output, -1.0f, 1.0f); + return math::constrain(_last_output, -1.0f, 1.0f); } float ECL_WheelController::control_attitude(const struct ECL_ControlData &ctl_data) { - /* Do not calculate control signal with bad inputs */ - if (!(PX4_ISFINITE(ctl_data.yaw_setpoint) && - PX4_ISFINITE(ctl_data.yaw))) { - return _rate_setpoint; - } + /* Do not calculate control signal with bad inputs */ + if (!(PX4_ISFINITE(ctl_data.yaw_setpoint) && + PX4_ISFINITE(ctl_data.yaw))) { + return _rate_setpoint; + } - /* Calculate the error */ - float yaw_error = ctl_data.yaw_setpoint - ctl_data.yaw; - /* shortest angle (wrap around) */ - yaw_error = (float)fmodf((float)fmodf((yaw_error + M_PI_F), M_TWOPI_F) + M_TWOPI_F, M_TWOPI_F) - M_PI_F; - /*warnx("yaw_error: %.4f", (double)yaw_error);*/ + /* Calculate the error */ + float yaw_error = ctl_data.yaw_setpoint - ctl_data.yaw; + /* shortest angle (wrap around) */ + yaw_error = (float)fmodf((float)fmodf((yaw_error + M_PI_F), M_TWOPI_F) + M_TWOPI_F, M_TWOPI_F) - M_PI_F; + /*warnx("yaw_error: %.4f", (double)yaw_error);*/ - /* Apply P controller: rate setpoint from current error and time constant */ - _rate_setpoint = yaw_error / _tc; + /* Apply P controller: rate setpoint from current error and time constant */ + _rate_setpoint = yaw_error / _tc; - /* limit the rate */ - if (_max_rate > 0.01f) { - if (_rate_setpoint > 0.0f) { - _rate_setpoint = (_rate_setpoint > _max_rate) ? _max_rate : _rate_setpoint; + /* limit the rate */ + if (_max_rate > 0.01f) { + if (_rate_setpoint > 0.0f) { + _rate_setpoint = (_rate_setpoint > _max_rate) ? _max_rate : _rate_setpoint; - } else { - _rate_setpoint = (_rate_setpoint < -_max_rate) ? -_max_rate : _rate_setpoint; - } + } else { + _rate_setpoint = (_rate_setpoint < -_max_rate) ? -_max_rate : _rate_setpoint; + } - } + } - return _rate_setpoint; + return _rate_setpoint; } diff --git a/attitude_fw/ecl_wheel_controller.h b/attitude_fw/ecl_wheel_controller.h index 6292c81844..898728c897 100644 --- a/attitude_fw/ecl_wheel_controller.h +++ b/attitude_fw/ecl_wheel_controller.h @@ -55,16 +55,14 @@ #include "ecl_controller.h" class __EXPORT ECL_WheelController : - public ECL_Controller + public ECL_Controller { public: - ECL_WheelController(); + ECL_WheelController(); + ~ECL_WheelController() = default; - ~ECL_WheelController(); - - float control_attitude(const struct ECL_ControlData &ctl_data); - - float control_bodyrate(const struct ECL_ControlData &ctl_data); + float control_attitude(const struct ECL_ControlData &ctl_data); + float control_bodyrate(const struct ECL_ControlData &ctl_data); }; #endif // ECL_HEADING_CONTROLLER_H diff --git a/attitude_fw/ecl_yaw_controller.cpp b/attitude_fw/ecl_yaw_controller.cpp index f49a487341..a98b03bf7b 100644 --- a/attitude_fw/ecl_yaw_controller.cpp +++ b/attitude_fw/ecl_yaw_controller.cpp @@ -55,10 +55,6 @@ ECL_YawController::ECL_YawController() : { } -ECL_YawController::~ECL_YawController() -{ -} - float ECL_YawController::control_attitude(const struct ECL_ControlData &ctl_data) { switch (_coordinated_method) { diff --git a/attitude_fw/ecl_yaw_controller.h b/attitude_fw/ecl_yaw_controller.h index ad246fe000..4f5e7d6e74 100644 --- a/attitude_fw/ecl_yaw_controller.h +++ b/attitude_fw/ecl_yaw_controller.h @@ -58,11 +58,9 @@ class __EXPORT ECL_YawController : { public: ECL_YawController(); - - ~ECL_YawController(); + ~ECL_YawController() = default; float control_attitude(const struct ECL_ControlData &ctl_data); - float control_bodyrate(const struct ECL_ControlData &ctl_data); /* Additional setters */ diff --git a/validation/data_validator.cpp b/validation/data_validator.cpp index d035a977da..f510cd9b53 100644 --- a/validation/data_validator.cpp +++ b/validation/data_validator.cpp @@ -63,11 +63,6 @@ DataValidator::DataValidator(DataValidator *prev_sibling) : } -DataValidator::~DataValidator() -{ - -} - void DataValidator::put(uint64_t timestamp, float val, uint64_t error_count_in, int priority_in) { diff --git a/validation/data_validator.h b/validation/data_validator.h index d4ac96c385..013e78851d 100644 --- a/validation/data_validator.h +++ b/validation/data_validator.h @@ -49,7 +49,7 @@ public: static const unsigned dimensions = 3; DataValidator(DataValidator *prev_sibling = nullptr); - virtual ~DataValidator(); + virtual ~DataValidator() = default; /** * Put an item into the validator.