diff --git a/include/wolf_ros_subscriber_gnss_TDCP.h b/include/wolf_ros_subscriber_gnss_TDCP.h index 251db0b02ccce2be60e731d1943d231c851977e4..0349dce65b6a0542127a99daa4c940ab78f99d75 100644 --- a/include/wolf_ros_subscriber_gnss_TDCP.h +++ b/include/wolf_ros_subscriber_gnss_TDCP.h @@ -38,9 +38,6 @@ class SubscriberWrapperGnssTDCP : public SubscriberWrapper ros::Subscriber sub_nav_; std::shared_ptr<GNSSUtils::Navigation> last_nav_ptr_; - //GNSSUtils::Navigation last_nav_; - //GNSSUtils::Observations obs_; - //GNSSUtils::ComputePosOutput get_pos_res_; //prcopt_t prcopt_; //bool new_obs_; diff --git a/src/wolf_ros_subscriber_gnss_TDCP.cpp b/src/wolf_ros_subscriber_gnss_TDCP.cpp index 5653d0617fcfb95e31e3c7243699923020d602d1..536d6230548d67611f9cd715c9fc6a9ea52b31a0 100644 --- a/src/wolf_ros_subscriber_gnss_TDCP.cpp +++ b/src/wolf_ros_subscriber_gnss_TDCP.cpp @@ -15,7 +15,6 @@ void SubscriberWrapperGnssTDCP::initSubscriber(ros::NodeHandle& nh, const std::s sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberWrapperGnssTDCP::callbackNavigation, this); } - void SubscriberWrapperGnssTDCP::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) { ROS_INFO("callbackObs!"); @@ -24,8 +23,6 @@ void SubscriberWrapperGnssTDCP::callbackObservation(const iri_gnss_msgs::Observa // TODO copied from TDCP_ros - - // GNSSUtils::ObservationsPtr obs_ptr = std::make_shared<GNSSUtils::Observations>(); // GNSSUtils::fillObservation(*obs_ptr, msg); // CaptureGnssPtr new_capture = std::make_shared<CaptureGnss>(TimeStamp(msg->header.stamp.sec, msg->header.stamp.nsec), @@ -40,7 +37,6 @@ void SubscriberWrapperGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigati { ROS_INFO("callbackNav!"); - std::cout << "Ephemeris size: " << msg->eph.size() << "\n"; last_nav_ptr_ = std::make_shared<GNSSUtils::Navigation>(); GNSSUtils::fillNavigation(*last_nav_ptr_, msg); last_nav_ptr_->print(); diff --git a/src/wolf_ros_subscriber_gnss_fix.cpp b/src/wolf_ros_subscriber_gnss_fix.cpp index ff46cb3e127ea00bdc2480fe273064677fc4926d..2c8ea95d8a5c366f96e3806d41c95a0ad37f4ee0 100644 --- a/src/wolf_ros_subscriber_gnss_fix.cpp +++ b/src/wolf_ros_subscriber_gnss_fix.cpp @@ -18,7 +18,14 @@ void SubscriberWrapperGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& { ROS_INFO("callback!"); - //TODO + Eigen::Matrix3d cov = Eigen::Map<const Eigen::Matrix3d>(msg->position_covariance.data()); + + CaptureGnssFixPtr cap_gnss_ptr = std::make_shared<CaptureGnssFix>(TimeStamp(0), + sensor_ptr_, + Eigen::Vector3d(msg->latitude,msg->longitude,msg->altitude), + cov, + false); //false = {LatLonAlt fix and ENU cov} + cap_gnss_ptr->process(); } std::shared_ptr<SubscriberWrapper> SubscriberWrapperGnssFix::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) {