locationd: Fix GPS sensor times with fixed offsets (#25920)

* Rewind to qcom time

* Fix test

* Typo

* init unix_time fix

* add gps sensor_time_offsets

* remove all clocks code and add todo

* :emove clocks in unit test

* update refs

* update refs

Co-authored-by: nuwandavek <vivekaithal44@gmail.com>
old-commit-hash: b332441803
vw-mqb-aeb
HaraldSchafer 3 years ago committed by GitHub
parent 18681091bf
commit eac9ec1570
  1. 26
      selfdrive/locationd/locationd.cc
  2. 2
      selfdrive/locationd/locationd.h
  3. 2
      selfdrive/locationd/models/live_kf.cc
  4. 1
      selfdrive/locationd/test/test_locationd.py
  5. 2
      selfdrive/test/process_replay/ref_commit

@ -20,6 +20,11 @@ const double VALID_POS_STD = 50.0; // m
const double MAX_RESET_TRACKER = 5.0; const double MAX_RESET_TRACKER = 5.0;
const double SANE_GPS_UNCERTAINTY = 1500.0; // m const double SANE_GPS_UNCERTAINTY = 1500.0; // m
// TODO: GPS sensor time offsets are empirically calculated
// They should be replaced with synced time from a real clock
const double GPS_LOCATION_SENSOR_TIME_OFFSET = 0.630; // s
const double GPS_LOCATION_EXTERNAL_SENSOR_TIME_OFFSET = 0.095; // s
static VectorXd floatlist2vector(const capnp::List<float, capnp::Kind::PRIMITIVE>::Reader& floatlist) { static VectorXd floatlist2vector(const capnp::List<float, capnp::Kind::PRIMITIVE>::Reader& floatlist) {
VectorXd res(floatlist.size()); VectorXd res(floatlist.size());
for (int i = 0; i < floatlist.size(); i++) { for (int i = 0; i < floatlist.size(); i++) {
@ -257,7 +262,7 @@ void Localizer::input_fake_gps_observations(double current_time) {
this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R }); this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R });
} }
void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::Reader& log) { void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::Reader& log, const double sensor_time_offset) {
// ignore the message if the fix is invalid // ignore the message if the fix is invalid
bool gps_invalid_flag = (log.getFlags() % 2 == 0); bool gps_invalid_flag = (log.getFlags() % 2 == 0);
bool gps_unreasonable = (Vector2d(log.getAccuracy(), log.getVerticalAccuracy()).norm() >= SANE_GPS_UNCERTAINTY); bool gps_unreasonable = (Vector2d(log.getAccuracy(), log.getVerticalAccuracy()).norm() >= SANE_GPS_UNCERTAINTY);
@ -270,8 +275,10 @@ void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::R
return; return;
} }
double sensor_time = current_time - sensor_time_offset;
// Process message // Process message
this->last_gps_fix = current_time; this->last_gps_fix = sensor_time;
this->gps_mode = true; this->gps_mode = true;
Geodetic geodetic = { log.getLatitude(), log.getLongitude(), log.getAltitude() }; Geodetic geodetic = { log.getLatitude(), log.getLongitude(), log.getAltitude() };
this->converter = std::make_unique<LocalCoord>(geodetic); this->converter = std::make_unique<LocalCoord>(geodetic);
@ -300,14 +307,14 @@ void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::R
if (ecef_vel.norm() > 5.0 && orientation_error.norm() > 1.0) { if (ecef_vel.norm() > 5.0 && orientation_error.norm() > 1.0) {
LOGE("Locationd vs ubloxLocation orientation difference too large, kalman reset"); LOGE("Locationd vs ubloxLocation orientation difference too large, kalman reset");
this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R); this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R);
this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_ORIENTATION_FROM_GPS, { initial_pose_ecef_quat }); this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_ORIENTATION_FROM_GPS, { initial_pose_ecef_quat });
} else if (gps_est_error > 100.0) { } else if (gps_est_error > 100.0) {
LOGE("Locationd vs ubloxLocation position difference too large, kalman reset"); LOGE("Locationd vs ubloxLocation position difference too large, kalman reset");
this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R); this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R);
} }
this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_POS, { ecef_pos }, { ecef_pos_R }); this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_POS, { ecef_pos }, { ecef_pos_R });
this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R }); this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R });
} }
void Localizer::handle_car_state(double current_time, const cereal::CarState::Reader& log) { void Localizer::handle_car_state(double current_time, const cereal::CarState::Reader& log) {
@ -443,9 +450,9 @@ void Localizer::handle_msg(const cereal::Event::Reader& log) {
} else if (log.isGyroscope()) { } else if (log.isGyroscope()) {
this->handle_sensor(t, log.getGyroscope()); this->handle_sensor(t, log.getGyroscope());
} else if (log.isGpsLocation()) { } else if (log.isGpsLocation()) {
this->handle_gps(t, log.getGpsLocation()); this->handle_gps(t, log.getGpsLocation(), GPS_LOCATION_SENSOR_TIME_OFFSET);
} else if (log.isGpsLocationExternal()) { } else if (log.isGpsLocationExternal()) {
this->handle_gps(t, log.getGpsLocationExternal()); this->handle_gps(t, log.getGpsLocationExternal(), GPS_LOCATION_EXTERNAL_SENSOR_TIME_OFFSET);
} else if (log.isCarState()) { } else if (log.isCarState()) {
this->handle_car_state(t, log.getCarState()); this->handle_car_state(t, log.getCarState());
} else if (log.isCameraOdometry()) { } else if (log.isCameraOdometry()) {
@ -497,9 +504,8 @@ int Localizer::locationd_thread() {
} else { } else {
gps_location_socket = "gpsLocation"; gps_location_socket = "gpsLocation";
} }
const std::initializer_list<const char *> service_list = {gps_location_socket, const std::initializer_list<const char *> service_list = {gps_location_socket, "cameraOdometry", "liveCalibration",
"cameraOdometry", "liveCalibration", "carState", "carParams", "carState", "carParams", "accelerometer", "gyroscope"};
"accelerometer", "gyroscope"};
PubMaster pm({"liveLocationKalman"}); PubMaster pm({"liveLocationKalman"});
// TODO: remove carParams once we're always sending at 100Hz // TODO: remove carParams once we're always sending at 100Hz

@ -46,7 +46,7 @@ public:
void handle_msg_bytes(const char *data, const size_t size); void handle_msg_bytes(const char *data, const size_t size);
void handle_msg(const cereal::Event::Reader& log); void handle_msg(const cereal::Event::Reader& log);
void handle_sensor(double current_time, const cereal::SensorEventData::Reader& log); void handle_sensor(double current_time, const cereal::SensorEventData::Reader& log);
void handle_gps(double current_time, const cereal::GpsLocationData::Reader& log); void handle_gps(double current_time, const cereal::GpsLocationData::Reader& log, const double sensor_time_offset);
void handle_car_state(double current_time, const cereal::CarState::Reader& log); void handle_car_state(double current_time, const cereal::CarState::Reader& log);
void handle_cam_odo(double current_time, const cereal::CameraOdometry::Reader& log); void handle_cam_odo(double current_time, const cereal::CameraOdometry::Reader& log);
void handle_live_calib(double current_time, const cereal::LiveCalibrationData::Reader& log); void handle_live_calib(double current_time, const cereal::LiveCalibrationData::Reader& log);

@ -44,7 +44,7 @@ LiveKalman::LiveKalman() {
// init filter // init filter
this->filter = std::make_shared<EKFSym>(this->name, get_mapmat(this->Q), get_mapvec(this->initial_x), this->filter = std::make_shared<EKFSym>(this->name, get_mapmat(this->Q), get_mapvec(this->initial_x),
get_mapmat(initial_P), this->dim_state, this->dim_state_err, 0, 0, 0, std::vector<int>(), get_mapmat(initial_P), this->dim_state, this->dim_state_err, 0, 0, 0, std::vector<int>(),
std::vector<int>{3}, std::vector<std::string>(), 0.2); std::vector<int>{3}, std::vector<std::string>(), 0.8);
} }
void LiveKalman::init_state(VectorXd& state, VectorXd& covs_diag, double filter_time) { void LiveKalman::init_state(VectorXd& state, VectorXd& covs_diag, double filter_time) {

@ -53,6 +53,7 @@ class TestLocationdProc(unittest.TestCase):
msg.gpsLocationExternal.vNED = [0.0, 0.0, 0.0] msg.gpsLocationExternal.vNED = [0.0, 0.0, 0.0]
msg.gpsLocationExternal.latitude = self.lat msg.gpsLocationExternal.latitude = self.lat
msg.gpsLocationExternal.longitude = self.lon msg.gpsLocationExternal.longitude = self.lon
msg.gpsLocationExternal.unixTimestampMillis = t * 1e6
msg.gpsLocationExternal.altitude = self.alt msg.gpsLocationExternal.altitude = self.alt
elif name == 'cameraOdometry': elif name == 'cameraOdometry':
msg.cameraOdometry.rot = [0.0, 0.0, 0.0] msg.cameraOdometry.rot = [0.0, 0.0, 0.0]

@ -1 +1 @@
27022484e3f4c0265ee7243154659b2697de3af7 14bc91c326f75ce48337720668a1744184c46994
Loading…
Cancel
Save