diff --git a/src/publisher_gnss_accuracy.cpp b/src/publisher_gnss_accuracy.cpp index a2ef3ca4ffab3a22328e4f0c59e8dcf9c2d20199..da18a60dff6ffd1fb077dd6b073cadef379cdd92 100644 --- a/src/publisher_gnss_accuracy.cpp +++ b/src/publisher_gnss_accuracy.cpp @@ -40,7 +40,7 @@ PublisherGnssAccuracy::PublisherGnssAccuracy(const std::string& _unique_name, marker_color_.g = col(1); marker_color_.b = col(2); marker_color_.a = col(3); - sensor_ = _problem->getSensor(_server.getParam<std::string>(prefix_ + "/sensor")); + sensor_ = _problem->findSensor(_server.getParam<std::string>(prefix_ + "/sensor")); k_H_ = _server.getParam<double>(prefix_ + "/k_H"); k_V_ = _server.getParam<double>(prefix_ + "/k_V"); } diff --git a/src/publisher_gnss_fix.cpp b/src/publisher_gnss_fix.cpp index 70f6e3f5dd88f87e7d50a01fa58c6a8ec5d4555e..814e87091e7275a77f9eeaa9e554015af26bac54 100644 --- a/src/publisher_gnss_fix.cpp +++ b/src/publisher_gnss_fix.cpp @@ -32,7 +32,7 @@ PublishGnssFix::PublishGnssFix(const std::string& _unique_name, const ProblemPtr _problem) : Publisher(_unique_name, _server, _problem) { - sensor_ = _problem->getSensor(_server.getParam<std::string>(prefix_ + "/sensor")); + sensor_ = _problem->findSensor(_server.getParam<std::string>(prefix_ + "/sensor")); frame_id_ = _server.getParam<std::string>(prefix_ + "/frame_id"); } diff --git a/src/publisher_gnss_tf.cpp b/src/publisher_gnss_tf.cpp index ed7ab474f9586167f15b207bd0dbb2dc89110fd6..9ec259e2dca3067f12a8a5aae5653c3f6776a48b 100644 --- a/src/publisher_gnss_tf.cpp +++ b/src/publisher_gnss_tf.cpp @@ -36,7 +36,7 @@ PublisherGnssTf::PublisherGnssTf(const std::string& _unique_name, const ProblemPtr _problem) : Publisher(_unique_name, _server, _problem) { - sensor_gnss_ = std::static_pointer_cast<SensorGnss>(_problem->getSensor(_server.getParam<std::string>(prefix_ + "/sensor_gnss_name"))); + sensor_gnss_ = std::static_pointer_cast<SensorGnss>(_problem->findSensor(_server.getParam<std::string>(prefix_ + "/sensor_gnss_name"))); T_enu_map_.setIdentity(); T_enu_map_.frame_id_ = "ENU";