From f54b28b66d0d854d07b35c5779f5974c369322aa Mon Sep 17 00:00:00 2001 From: PepMS Date: Thu, 7 Nov 2019 13:16:34 +0100 Subject: [PATCH 01/86] Changes --- include/wolf_ros_subscriber_gnss.h | 8 +++-- src/wolf_ros_subscriber_gnss.cpp | 52 ++++++++++++++++++++++-------- 2 files changed, 45 insertions(+), 15 deletions(-) diff --git a/include/wolf_ros_subscriber_gnss.h b/include/wolf_ros_subscriber_gnss.h index 79562aa..c746701 100644 --- a/include/wolf_ros_subscriber_gnss.h +++ b/include/wolf_ros_subscriber_gnss.h @@ -37,8 +37,13 @@ class WolfSubscriberWrapperGnss : public WolfSubscriberWrapper protected: ros::Subscriber sub_nav_; + std::shared_ptr last_nav_ptr_; GNSSUtils::Navigation last_nav_; - bool last_nav_valid_; + GNSSUtils::Observations obs_; + GNSSUtils::ComputePosOutput get_pos_res_; + + prcopt_t prcopt_; + bool new_obs_; public: // Constructor @@ -52,5 +57,4 @@ class WolfSubscriberWrapperGnss : public WolfSubscriberWrapper static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); }; - WOLF_REGISTER_SUBSCRIBER(WolfSubscriberWrapperGnss) diff --git a/src/wolf_ros_subscriber_gnss.cpp b/src/wolf_ros_subscriber_gnss.cpp index 2d6a715..ba614f5 100644 --- a/src/wolf_ros_subscriber_gnss.cpp +++ b/src/wolf_ros_subscriber_gnss.cpp @@ -4,9 +4,21 @@ using namespace wolf; // Constructor WolfSubscriberWrapperGnss::WolfSubscriberWrapperGnss(const SensorBasePtr& sensor_ptr) : - WolfSubscriberWrapper(sensor_ptr), - last_nav_valid_(false) + WolfSubscriberWrapper(sensor_ptr) { + prcopt_ = prcopt_default; + prcopt_.mode = PMODE_SINGLE; + prcopt_.soltype = 0; + prcopt_.nf = 1; + prcopt_.navsys = SYS_GPS; + prcopt_.sateph = EPHOPT_BRDC; + prcopt_.ionoopt = IONOOPT_OFF; + prcopt_.tropopt = TROPOPT_OFF; + prcopt_.dynamics = 0; + prcopt_.tidecorr = 0; + prcopt_.sbascorr = SBSOPT_FCORR; + + this->new_obs_=false; } @@ -16,29 +28,43 @@ void WolfSubscriberWrapperGnss::initSubscriber(ros::NodeHandle& nh, const std::s sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &WolfSubscriberWrapperGnss::callbackNavigation, this); } + void WolfSubscriberWrapperGnss::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) { ROS_INFO("callbackObs!"); - if (!last_nav_valid_) + if (last_nav_ptr_==nullptr) return; - GNSSUtils::Observations obs; - GNSSUtils::fillObservation(obs, msg); + // std::shared_ptr obs_ptr = std::make_shared(); + // GNSSUtils::fillObservation(*(obs_ptr), msg); - CaptureGnssPtr new_capture = std::make_shared(TimeStamp(msg->header.stamp.sec, msg->header.stamp.nsec), - sensor_ptr_, - obs, - last_nav_); - new_capture->process(); + + // GNSSUtils::Observations obs; + GNSSUtils::fillObservation(this->obs_, msg); + this->new_obs_=true; + // CaptureGnssPtr new_capture = std::make_shared(TimeStamp(msg->header.stamp.sec, msg->header.stamp.nsec), + // sensor_ptr_, + // obs_ptr, + // last_nav_ptr_); + // new_capture->process(); } void WolfSubscriberWrapperGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) { ROS_INFO("callbackNav!"); - GNSSUtils::fillNavigation(last_nav_, msg); - last_nav_valid_ = true; -} + std::cout << "Ephemeris size: " << msg->eph.size() << "\n"; + GNSSUtils::fillNavigation(this->last_nav_, msg); + last_nav_ptr_ = std::make_shared(); + this->last_nav_.print(); + + if (this->new_obs_) + { + std::cout << "Before computed!!! \n"; + this->get_pos_res_ = GNSSUtils::computePos(this->obs_, this->last_nav_, this->prcopt_); + std::cout << "Computed!!! \n"; + } +} std::shared_ptr WolfSubscriberWrapperGnss::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) { return std::make_shared(_sensor_ptr); -- GitLab From b95c7706c465c32995daf4023d6380ad26d0ed2b Mon Sep 17 00:00:00 2001 From: PepMS Date: Thu, 7 Nov 2019 15:53:53 +0100 Subject: [PATCH 02/86] Changed gnss_utils.h --- include/wolf_ros_subscriber_gnss.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/include/wolf_ros_subscriber_gnss.h b/include/wolf_ros_subscriber_gnss.h index c746701..6893956 100644 --- a/include/wolf_ros_subscriber_gnss.h +++ b/include/wolf_ros_subscriber_gnss.h @@ -28,7 +28,7 @@ **************************/ #include "wolf_ros_subscriber.h" #include "subscriber_factory.h" -#include "gnss_utils.h" +#include "gnss_utils/gnss_utils.h" using namespace wolf; -- GitLab From c85d78fd18e38ebea5aae515c9fca22f5c1615f3 Mon Sep 17 00:00:00 2001 From: PepMS Date: Mon, 18 Nov 2019 14:52:52 +0100 Subject: [PATCH 03/86] Reverted debug changes --- include/wolf_ros_subscriber_gnss.h | 6 ---- src/wolf_ros_subscriber_gnss.cpp | 48 ++++++++---------------------- 2 files changed, 12 insertions(+), 42 deletions(-) diff --git a/include/wolf_ros_subscriber_gnss.h b/include/wolf_ros_subscriber_gnss.h index 6893956..1bfd216 100644 --- a/include/wolf_ros_subscriber_gnss.h +++ b/include/wolf_ros_subscriber_gnss.h @@ -38,12 +38,6 @@ class WolfSubscriberWrapperGnss : public WolfSubscriberWrapper ros::Subscriber sub_nav_; std::shared_ptr last_nav_ptr_; - GNSSUtils::Navigation last_nav_; - GNSSUtils::Observations obs_; - GNSSUtils::ComputePosOutput get_pos_res_; - - prcopt_t prcopt_; - bool new_obs_; public: // Constructor diff --git a/src/wolf_ros_subscriber_gnss.cpp b/src/wolf_ros_subscriber_gnss.cpp index ba614f5..1662a01 100644 --- a/src/wolf_ros_subscriber_gnss.cpp +++ b/src/wolf_ros_subscriber_gnss.cpp @@ -6,19 +6,7 @@ using namespace wolf; WolfSubscriberWrapperGnss::WolfSubscriberWrapperGnss(const SensorBasePtr& sensor_ptr) : WolfSubscriberWrapper(sensor_ptr) { - prcopt_ = prcopt_default; - prcopt_.mode = PMODE_SINGLE; - prcopt_.soltype = 0; - prcopt_.nf = 1; - prcopt_.navsys = SYS_GPS; - prcopt_.sateph = EPHOPT_BRDC; - prcopt_.ionoopt = IONOOPT_OFF; - prcopt_.tropopt = TROPOPT_OFF; - prcopt_.dynamics = 0; - prcopt_.tidecorr = 0; - prcopt_.sbascorr = SBSOPT_FCORR; - - this->new_obs_=false; + } @@ -34,37 +22,25 @@ void WolfSubscriberWrapperGnss::callbackObservation(const iri_gnss_msgs::Observa ROS_INFO("callbackObs!"); if (last_nav_ptr_==nullptr) return; - - // std::shared_ptr obs_ptr = std::make_shared(); - // GNSSUtils::fillObservation(*(obs_ptr), msg); - - // GNSSUtils::Observations obs; - GNSSUtils::fillObservation(this->obs_, msg); - this->new_obs_=true; - // CaptureGnssPtr new_capture = std::make_shared(TimeStamp(msg->header.stamp.sec, msg->header.stamp.nsec), - // sensor_ptr_, - // obs_ptr, - // last_nav_ptr_); - // new_capture->process(); + std::shared_ptr obs_ptr = std::make_shared(); + GNSSUtils::fillObservation(*(obs_ptr), msg); + + CaptureGnssPtr new_capture = std::make_shared(TimeStamp(msg->header.stamp.sec, msg->header.stamp.nsec), + sensor_ptr_, + obs_ptr, + last_nav_ptr_); + new_capture->process(); } void WolfSubscriberWrapperGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) { ROS_INFO("callbackNav!"); - - std::cout << "Ephemeris size: " << msg->eph.size() << "\n"; - GNSSUtils::fillNavigation(this->last_nav_, msg); + last_nav_ptr_ = std::make_shared(); - this->last_nav_.print(); - - if (this->new_obs_) - { - std::cout << "Before computed!!! \n"; - this->get_pos_res_ = GNSSUtils::computePos(this->obs_, this->last_nav_, this->prcopt_); - std::cout << "Computed!!! \n"; - } + GNSSUtils::fillNavigation(*(last_nav_ptr_), msg); } + std::shared_ptr WolfSubscriberWrapperGnss::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) { return std::make_shared(_sensor_ptr); -- GitLab From d45de882334127506d09d76acb09848b54e133f0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Tue, 3 Mar 2020 18:42:14 +0100 Subject: [PATCH 04/86] added gnss_fix and adapted to new name WIP --- CMakeLists.txt | 1 + include/wolf_ros_subscriber_gnss.h | 20 +++---- include/wolf_ros_subscriber_gnss_fix.h | 45 +++++++++++++++ src/wolf_ros_subscriber_gnss.cpp | 77 ++++++++++++-------------- src/wolf_ros_subscriber_gnss_fix.cpp | 26 +++++++++ 5 files changed, 118 insertions(+), 51 deletions(-) create mode 100644 include/wolf_ros_subscriber_gnss_fix.h create mode 100644 src/wolf_ros_subscriber_gnss_fix.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index f09930c..940b215 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -138,6 +138,7 @@ include_directories( # src/${PROJECT_NAME}/wolf_ros.cpp # ) add_library(wolf_subscriber_gnss src/wolf_ros_subscriber_gnss.cpp) +add_library(wolf_subscriber_gnss_fix src/wolf_ros_subscriber_gnss_fix.cpp) ## Add cmake target dependencies of the library ## as an example, code may need to be generated before libraries diff --git a/include/wolf_ros_subscriber_gnss.h b/include/wolf_ros_subscriber_gnss.h index c746701..0fa6531 100644 --- a/include/wolf_ros_subscriber_gnss.h +++ b/include/wolf_ros_subscriber_gnss.h @@ -28,26 +28,26 @@ **************************/ #include "wolf_ros_subscriber.h" #include "subscriber_factory.h" -#include "gnss_utils.h" +#include "gnss_utils/gnss_utils.h" using namespace wolf; -class WolfSubscriberWrapperGnss : public WolfSubscriberWrapper +class SubscriberWrapperGnss : public SubscriberWrapper { protected: ros::Subscriber sub_nav_; std::shared_ptr last_nav_ptr_; - GNSSUtils::Navigation last_nav_; - GNSSUtils::Observations obs_; - GNSSUtils::ComputePosOutput get_pos_res_; + //GNSSUtils::Navigation last_nav_; + //GNSSUtils::Observations obs_; + //GNSSUtils::ComputePosOutput get_pos_res_; - prcopt_t prcopt_; - bool new_obs_; + //prcopt_t prcopt_; + //bool new_obs_; public: // Constructor - WolfSubscriberWrapperGnss(const SensorBasePtr& sensor_ptr); + SubscriberWrapperGnss(const SensorBasePtr& sensor_ptr); virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); @@ -55,6 +55,6 @@ class WolfSubscriberWrapperGnss : public WolfSubscriberWrapper void callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg); - static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); + static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); }; -WOLF_REGISTER_SUBSCRIBER(WolfSubscriberWrapperGnss) +WOLF_REGISTER_SUBSCRIBER(SubscriberWrapperGnss) diff --git a/include/wolf_ros_subscriber_gnss_fix.h b/include/wolf_ros_subscriber_gnss_fix.h new file mode 100644 index 0000000..bda4533 --- /dev/null +++ b/include/wolf_ros_subscriber_gnss_fix.h @@ -0,0 +1,45 @@ +/************************** + * WOLF includes * + **************************/ +#include +#include +#include +#include +#include +#include + +/************************** + * ROS includes * + **************************/ +#include +#include + +/************************** + * STD includes * + **************************/ +#include +#include +#include + +/************************** + * WOLF-ROS includes * + **************************/ +#include "wolf_ros_subscriber.h" +#include "subscriber_factory.h" +#include "gnss_utils/gnss_utils.h" + +using namespace wolf; + +class SubscriberWrapperGnssFix : public SubscriberWrapper +{ + public: + // Constructor + SubscriberWrapperGnssFix(const SensorBasePtr& sensor_ptr); + + virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); + + void callback(const sensor_msgs::NavSatFix::ConstPtr& msg); + + static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); +}; +WOLF_REGISTER_SUBSCRIBER(SubscriberWrapperGnssFix) diff --git a/src/wolf_ros_subscriber_gnss.cpp b/src/wolf_ros_subscriber_gnss.cpp index ba614f5..75fbdc4 100644 --- a/src/wolf_ros_subscriber_gnss.cpp +++ b/src/wolf_ros_subscriber_gnss.cpp @@ -3,69 +3,64 @@ using namespace wolf; // Constructor -WolfSubscriberWrapperGnss::WolfSubscriberWrapperGnss(const SensorBasePtr& sensor_ptr) : - WolfSubscriberWrapper(sensor_ptr) +SubscriberWrapperGnss::SubscriberWrapperGnss(const SensorBasePtr& sensor_ptr) : + SubscriberWrapper(sensor_ptr) { - prcopt_ = prcopt_default; - prcopt_.mode = PMODE_SINGLE; - prcopt_.soltype = 0; - prcopt_.nf = 1; - prcopt_.navsys = SYS_GPS; - prcopt_.sateph = EPHOPT_BRDC; - prcopt_.ionoopt = IONOOPT_OFF; - prcopt_.tropopt = TROPOPT_OFF; - prcopt_.dynamics = 0; - prcopt_.tidecorr = 0; - prcopt_.sbascorr = SBSOPT_FCORR; + //prcopt_ = prcopt_default; + //prcopt_.mode = PMODE_SINGLE; + //prcopt_.soltype = 0; + //prcopt_.nf = 1; + //prcopt_.navsys = SYS_GPS; + //prcopt_.sateph = EPHOPT_BRDC; + //prcopt_.ionoopt = IONOOPT_OFF; + //prcopt_.tropopt = TROPOPT_OFF; + //prcopt_.dynamics = 0; + //prcopt_.tidecorr = 0; + //prcopt_.sbascorr = SBSOPT_FCORR; - this->new_obs_=false; + //this->new_obs_=false; } -void WolfSubscriberWrapperGnss::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void SubscriberWrapperGnss::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { - sub_ = nh.subscribe(topic+std::string("_obs"), 1, &WolfSubscriberWrapperGnss::callbackObservation, this); - sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &WolfSubscriberWrapperGnss::callbackNavigation, this); + sub_ = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberWrapperGnss::callbackObservation, this); + sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberWrapperGnss::callbackNavigation, this); } -void WolfSubscriberWrapperGnss::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) +void SubscriberWrapperGnss::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) { ROS_INFO("callbackObs!"); if (last_nav_ptr_==nullptr) return; - // std::shared_ptr obs_ptr = std::make_shared(); - // GNSSUtils::fillObservation(*(obs_ptr), msg); - - - // GNSSUtils::Observations obs; - GNSSUtils::fillObservation(this->obs_, msg); - this->new_obs_=true; - // CaptureGnssPtr new_capture = std::make_shared(TimeStamp(msg->header.stamp.sec, msg->header.stamp.nsec), - // sensor_ptr_, - // obs_ptr, - // last_nav_ptr_); - // new_capture->process(); + GNSSUtils::ObservationsPtr obs_ptr = std::make_shared(); + GNSSUtils::fillObservation(*obs_ptr, msg); + CaptureGnssPtr new_capture = std::make_shared(TimeStamp(msg->header.stamp.sec, msg->header.stamp.nsec), + sensor_ptr_, + obs_ptr, + last_nav_ptr_); + new_capture->process(); } -void WolfSubscriberWrapperGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) +void SubscriberWrapperGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) { ROS_INFO("callbackNav!"); std::cout << "Ephemeris size: " << msg->eph.size() << "\n"; - GNSSUtils::fillNavigation(this->last_nav_, msg); last_nav_ptr_ = std::make_shared(); - this->last_nav_.print(); + GNSSUtils::fillNavigation(*last_nav_ptr_, msg); + last_nav_ptr_->print(); - if (this->new_obs_) - { - std::cout << "Before computed!!! \n"; - this->get_pos_res_ = GNSSUtils::computePos(this->obs_, this->last_nav_, this->prcopt_); - std::cout << "Computed!!! \n"; - } +// if (this->new_obs_) +// { +// std::cout << "Before computed!!! \n"; +// this->get_pos_res_ = GNSSUtils::computePos(this->obs_, *last_nav_ptr_, this->prcopt_); +// std::cout << "Computed!!! \n"; +// } } -std::shared_ptr WolfSubscriberWrapperGnss::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +std::shared_ptr SubscriberWrapperGnss::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) { - return std::make_shared(_sensor_ptr); + return std::make_shared(_sensor_ptr); } diff --git a/src/wolf_ros_subscriber_gnss_fix.cpp b/src/wolf_ros_subscriber_gnss_fix.cpp new file mode 100644 index 0000000..ff46cb3 --- /dev/null +++ b/src/wolf_ros_subscriber_gnss_fix.cpp @@ -0,0 +1,26 @@ +#include "../include/wolf_ros_subscriber_gnss_fix.h" + +using namespace wolf; + +// Constructor +SubscriberWrapperGnssFix::SubscriberWrapperGnssFix(const SensorBasePtr& sensor_ptr) : + SubscriberWrapper(sensor_ptr) +{ +} + + +void SubscriberWrapperGnssFix::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +{ + sub_ = nh.subscribe(topic, 1, &SubscriberWrapperGnssFix::callback, this); +} + +void SubscriberWrapperGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg) +{ + ROS_INFO("callback!"); + + //TODO +} +std::shared_ptr SubscriberWrapperGnssFix::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +{ + return std::make_shared(_sensor_ptr); +} -- GitLab From 0abeec07a18138caa412ba68ca8bc8f95a3abd34 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Tue, 3 Mar 2020 18:56:41 +0100 Subject: [PATCH 05/86] adding TDCP subscriber --- CMakeLists.txt | 11 +++++ include/wolf_ros_subscriber_gnss_TDCP.h | 60 +++++++++++++++++++++++++ src/wolf_ros_subscriber_gnss_TDCP.cpp | 54 ++++++++++++++++++++++ 3 files changed, 125 insertions(+) create mode 100644 include/wolf_ros_subscriber_gnss_TDCP.h create mode 100644 src/wolf_ros_subscriber_gnss_TDCP.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 940b215..dc7fd03 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -139,6 +139,7 @@ include_directories( # ) add_library(wolf_subscriber_gnss src/wolf_ros_subscriber_gnss.cpp) add_library(wolf_subscriber_gnss_fix src/wolf_ros_subscriber_gnss_fix.cpp) +add_library(wolf_subscriber_gnss_TDCP src/wolf_ros_subscriber_gnss_TDCP.cpp) ## Add cmake target dependencies of the library ## as an example, code may need to be generated before libraries @@ -167,6 +168,16 @@ target_link_libraries(wolf_subscriber_gnss ${wolfgnss_LIBRARIES} ${iri_gnss_msgs_LIBRARIES} ) +target_link_libraries(wolf_subscriber_gnss_fix + ${wolf_LIBRARIES} + ${wolfgnss_LIBRARIES} + ${iri_gnss_msgs_LIBRARIES} + ) +target_link_libraries(wolf_subscriber_gnss_TDCP + ${wolf_LIBRARIES} + ${wolfgnss_LIBRARIES} + ${iri_gnss_msgs_LIBRARIES} + ) ############# ## Install ## diff --git a/include/wolf_ros_subscriber_gnss_TDCP.h b/include/wolf_ros_subscriber_gnss_TDCP.h new file mode 100644 index 0000000..251db0b --- /dev/null +++ b/include/wolf_ros_subscriber_gnss_TDCP.h @@ -0,0 +1,60 @@ +/************************** + * WOLF includes * + **************************/ +#include +#include +#include +#include +#include +#include + +/************************** + * ROS includes * + **************************/ +#include +#include +#include +#include + +/************************** + * STD includes * + **************************/ +#include +#include +#include + +/************************** + * WOLF-ROS includes * + **************************/ +#include "wolf_ros_subscriber.h" +#include "subscriber_factory.h" +#include "gnss_utils/gnss_utils.h" + +using namespace wolf; + +class SubscriberWrapperGnssTDCP : public SubscriberWrapper +{ + protected: + + ros::Subscriber sub_nav_; + std::shared_ptr last_nav_ptr_; + //GNSSUtils::Navigation last_nav_; + //GNSSUtils::Observations obs_; + //GNSSUtils::ComputePosOutput get_pos_res_; + + //prcopt_t prcopt_; + //bool new_obs_; + + public: + // Constructor + SubscriberWrapperGnssTDCP(const SensorBasePtr& sensor_ptr); + + virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); + + void callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg); + + void callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg); + + static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); +}; +WOLF_REGISTER_SUBSCRIBER(SubscriberWrapperGnssTDCP) diff --git a/src/wolf_ros_subscriber_gnss_TDCP.cpp b/src/wolf_ros_subscriber_gnss_TDCP.cpp new file mode 100644 index 0000000..5653d06 --- /dev/null +++ b/src/wolf_ros_subscriber_gnss_TDCP.cpp @@ -0,0 +1,54 @@ +#include "../include/wolf_ros_subscriber_gnss_TDCP.h" + +using namespace wolf; + +// Constructor +SubscriberWrapperGnssTDCP::SubscriberWrapperGnssTDCP(const SensorBasePtr& sensor_ptr) : + SubscriberWrapper(sensor_ptr) +{ + // TODO copied from TDCP_ros +} + +void SubscriberWrapperGnssTDCP::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +{ + sub_ = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberWrapperGnssTDCP::callbackObservation, this); + 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!"); + if (last_nav_ptr_==nullptr) + return; + + // TODO copied from TDCP_ros + + + +// GNSSUtils::ObservationsPtr obs_ptr = std::make_shared(); +// GNSSUtils::fillObservation(*obs_ptr, msg); +// CaptureGnssPtr new_capture = std::make_shared(TimeStamp(msg->header.stamp.sec, msg->header.stamp.nsec), +// sensor_ptr_, +// obs_ptr, +// last_nav_ptr_); +// new_capture->process(); +// +} + +void SubscriberWrapperGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) +{ + ROS_INFO("callbackNav!"); + + std::cout << "Ephemeris size: " << msg->eph.size() << "\n"; + last_nav_ptr_ = std::make_shared(); + GNSSUtils::fillNavigation(*last_nav_ptr_, msg); + last_nav_ptr_->print(); + + // TODO copied from TDCP_ros +} + +std::shared_ptr SubscriberWrapperGnssTDCP::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +{ + return std::make_shared(_sensor_ptr); +} -- GitLab From 90b7ee1bc1ebc5952848e7762a403b1c4cf5fb8a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Thu, 5 Mar 2020 11:29:31 +0100 Subject: [PATCH 06/86] working fix subscriber, new empty TDCP subscriber --- include/wolf_ros_subscriber_gnss_TDCP.h | 3 --- src/wolf_ros_subscriber_gnss_TDCP.cpp | 4 ---- src/wolf_ros_subscriber_gnss_fix.cpp | 9 ++++++++- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/include/wolf_ros_subscriber_gnss_TDCP.h b/include/wolf_ros_subscriber_gnss_TDCP.h index 251db0b..0349dce 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 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 5653d06..536d623 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::fillObservation(*obs_ptr, msg); // CaptureGnssPtr new_capture = std::make_shared(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::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 ff46cb3..2c8ea95 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(msg->position_covariance.data()); + + CaptureGnssFixPtr cap_gnss_ptr = std::make_shared(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 SubscriberWrapperGnssFix::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) { -- GitLab From 43be1d0c3a44b79e47b748d2a09b5834b4fbd668 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Thu, 5 Mar 2020 15:29:02 +0100 Subject: [PATCH 07/86] latlon in radiants --- src/wolf_ros_subscriber_gnss_fix.cpp | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/src/wolf_ros_subscriber_gnss_fix.cpp b/src/wolf_ros_subscriber_gnss_fix.cpp index 2c8ea95..ab17ef1 100644 --- a/src/wolf_ros_subscriber_gnss_fix.cpp +++ b/src/wolf_ros_subscriber_gnss_fix.cpp @@ -16,15 +16,18 @@ void SubscriberWrapperGnssFix::initSubscriber(ros::NodeHandle& nh, const std::st void SubscriberWrapperGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg) { - ROS_INFO("callback!"); - Eigen::Matrix3d cov = Eigen::Map(msg->position_covariance.data()); - CaptureGnssFixPtr cap_gnss_ptr = std::make_shared(TimeStamp(0), + std::cout << "New fix: " << Eigen::Vector3d(msg->latitude,msg->longitude,msg->altitude).transpose() << std::endl; + + Eigen::Vector3d latlonalt_rads(msg->latitude,msg->longitude,msg->altitude); + latlonalt_rads.head<2>() *= M_PI/180.0; + + CaptureGnssFixPtr cap_gnss_ptr = std::make_shared(TimeStamp(msg->header.stamp.sec, msg->header.stamp.nsec), sensor_ptr_, - Eigen::Vector3d(msg->latitude,msg->longitude,msg->altitude), + latlonalt_rads, cov, - false); //false = {LatLonAlt fix and ENU cov} + false); // false = {LatLonAlt fix and ENU cov} cap_gnss_ptr->process(); } std::shared_ptr SubscriberWrapperGnssFix::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) -- GitLab From 1a1f723f6fef6aa43c0d81b774306e8200092a0a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Fri, 6 Mar 2020 17:23:02 +0100 Subject: [PATCH 08/86] working --- src/wolf_ros_subscriber_gnss_fix.cpp | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/src/wolf_ros_subscriber_gnss_fix.cpp b/src/wolf_ros_subscriber_gnss_fix.cpp index ab17ef1..d0b4885 100644 --- a/src/wolf_ros_subscriber_gnss_fix.cpp +++ b/src/wolf_ros_subscriber_gnss_fix.cpp @@ -18,14 +18,11 @@ void SubscriberWrapperGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& { Eigen::Matrix3d cov = Eigen::Map(msg->position_covariance.data()); - std::cout << "New fix: " << Eigen::Vector3d(msg->latitude,msg->longitude,msg->altitude).transpose() << std::endl; - - Eigen::Vector3d latlonalt_rads(msg->latitude,msg->longitude,msg->altitude); - latlonalt_rads.head<2>() *= M_PI/180.0; - CaptureGnssFixPtr cap_gnss_ptr = std::make_shared(TimeStamp(msg->header.stamp.sec, msg->header.stamp.nsec), sensor_ptr_, - latlonalt_rads, + Eigen::Vector3d(msg->latitude * M_PI / 180.0, + msg->longitude * M_PI / 180.0, + msg->altitude), cov, false); // false = {LatLonAlt fix and ENU cov} cap_gnss_ptr->process(); -- GitLab From bd347d710d4e2547b63df20014beb3c25e167031 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Thu, 12 Mar 2020 17:09:08 +0100 Subject: [PATCH 09/86] renaming subscribers --- CMakeLists.txt | 6 +++--- ...bscriber_gnss.h => wolf_subscriber_gnss.h} | 0 ...nss_TDCP.h => wolf_subscriber_gnss_TDCP.h} | 0 ..._gnss_fix.h => wolf_subscriber_gnss_fix.h} | 6 +++--- ...iber_gnss.cpp => wolf_subscriber_gnss.cpp} | 20 +++++++++---------- ...TDCP.cpp => wolf_subscriber_gnss_TDCP.cpp} | 20 +++++++++---------- ...s_fix.cpp => wolf_subscriber_gnss_fix.cpp} | 16 +++++++-------- 7 files changed, 34 insertions(+), 34 deletions(-) rename include/{wolf_ros_subscriber_gnss.h => wolf_subscriber_gnss.h} (100%) rename include/{wolf_ros_subscriber_gnss_TDCP.h => wolf_subscriber_gnss_TDCP.h} (100%) rename include/{wolf_ros_subscriber_gnss_fix.h => wolf_subscriber_gnss_fix.h} (86%) rename src/{wolf_ros_subscriber_gnss.cpp => wolf_subscriber_gnss.cpp} (68%) rename src/{wolf_ros_subscriber_gnss_TDCP.cpp => wolf_subscriber_gnss_TDCP.cpp} (57%) rename src/{wolf_ros_subscriber_gnss_fix.cpp => wolf_subscriber_gnss_fix.cpp} (57%) diff --git a/CMakeLists.txt b/CMakeLists.txt index dc7fd03..326764d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -137,9 +137,9 @@ include_directories( # add_library(${PROJECT_NAME} # src/${PROJECT_NAME}/wolf_ros.cpp # ) -add_library(wolf_subscriber_gnss src/wolf_ros_subscriber_gnss.cpp) -add_library(wolf_subscriber_gnss_fix src/wolf_ros_subscriber_gnss_fix.cpp) -add_library(wolf_subscriber_gnss_TDCP src/wolf_ros_subscriber_gnss_TDCP.cpp) +add_library(wolf_subscriber_gnss src/wolf_subscriber_gnss.cpp) +add_library(wolf_subscriber_gnss_fix src/wolf_subscriber_gnss_fix.cpp) +add_library(wolf_subscriber_gnss_TDCP src/wolf_subscriber_gnss_TDCP.cpp) ## Add cmake target dependencies of the library ## as an example, code may need to be generated before libraries diff --git a/include/wolf_ros_subscriber_gnss.h b/include/wolf_subscriber_gnss.h similarity index 100% rename from include/wolf_ros_subscriber_gnss.h rename to include/wolf_subscriber_gnss.h diff --git a/include/wolf_ros_subscriber_gnss_TDCP.h b/include/wolf_subscriber_gnss_TDCP.h similarity index 100% rename from include/wolf_ros_subscriber_gnss_TDCP.h rename to include/wolf_subscriber_gnss_TDCP.h diff --git a/include/wolf_ros_subscriber_gnss_fix.h b/include/wolf_subscriber_gnss_fix.h similarity index 86% rename from include/wolf_ros_subscriber_gnss_fix.h rename to include/wolf_subscriber_gnss_fix.h index bda4533..7140e6d 100644 --- a/include/wolf_ros_subscriber_gnss_fix.h +++ b/include/wolf_subscriber_gnss_fix.h @@ -30,11 +30,11 @@ using namespace wolf; -class SubscriberWrapperGnssFix : public SubscriberWrapper +class WolfSubscriberGnssFix : public WolfSubscriber { public: // Constructor - SubscriberWrapperGnssFix(const SensorBasePtr& sensor_ptr); + WolfSubscriberGnssFix(const SensorBasePtr& sensor_ptr); virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); @@ -42,4 +42,4 @@ class SubscriberWrapperGnssFix : public SubscriberWrapper static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); }; -WOLF_REGISTER_SUBSCRIBER(SubscriberWrapperGnssFix) +WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnssFix) diff --git a/src/wolf_ros_subscriber_gnss.cpp b/src/wolf_subscriber_gnss.cpp similarity index 68% rename from src/wolf_ros_subscriber_gnss.cpp rename to src/wolf_subscriber_gnss.cpp index b57fc34..1ddc25f 100644 --- a/src/wolf_ros_subscriber_gnss.cpp +++ b/src/wolf_subscriber_gnss.cpp @@ -1,10 +1,10 @@ -#include "../include/wolf_ros_subscriber_gnss.h" +#include "../include/wolf_subscriber_gnss.h" using namespace wolf; // Constructor -SubscriberWrapperGnss::SubscriberWrapperGnss(const SensorBasePtr& sensor_ptr) : - SubscriberWrapper(sensor_ptr) +SubscriberGnss::SubscriberGnss(const SensorBasePtr& sensor_ptr) : + Subscriber(sensor_ptr) { //prcopt_ = prcopt_default; //prcopt_.mode = PMODE_SINGLE; @@ -22,14 +22,14 @@ SubscriberWrapperGnss::SubscriberWrapperGnss(const SensorBasePtr& sensor_ptr) : } -void SubscriberWrapperGnss::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void SubscriberGnss::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { - sub_ = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberWrapperGnss::callbackObservation, this); - sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberWrapperGnss::callbackNavigation, this); + sub_ = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberGnss::callbackObservation, this); + sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberGnss::callbackNavigation, this); } -void SubscriberWrapperGnss::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) +void SubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) { ROS_INFO("callbackObs!"); if (last_nav_ptr_==nullptr) @@ -44,7 +44,7 @@ void SubscriberWrapperGnss::callbackObservation(const iri_gnss_msgs::Observation new_capture->process(); } -void SubscriberWrapperGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) +void SubscriberGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) { ROS_INFO("callbackNav!"); @@ -61,7 +61,7 @@ void SubscriberWrapperGnss::callbackNavigation(const iri_gnss_msgs::Navigation:: // } } -std::shared_ptr SubscriberWrapperGnss::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +std::shared_ptr SubscriberGnss::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) { - return std::make_shared(_sensor_ptr); + return std::make_shared(_sensor_ptr); } diff --git a/src/wolf_ros_subscriber_gnss_TDCP.cpp b/src/wolf_subscriber_gnss_TDCP.cpp similarity index 57% rename from src/wolf_ros_subscriber_gnss_TDCP.cpp rename to src/wolf_subscriber_gnss_TDCP.cpp index 536d623..42bd270 100644 --- a/src/wolf_ros_subscriber_gnss_TDCP.cpp +++ b/src/wolf_subscriber_gnss_TDCP.cpp @@ -1,21 +1,21 @@ -#include "../include/wolf_ros_subscriber_gnss_TDCP.h" +#include "../include/wolf_subscriber_gnss_TDCP.h" using namespace wolf; // Constructor -SubscriberWrapperGnssTDCP::SubscriberWrapperGnssTDCP(const SensorBasePtr& sensor_ptr) : - SubscriberWrapper(sensor_ptr) +SubscriberGnssTDCP::SubscriberGnssTDCP(const SensorBasePtr& sensor_ptr) : + Subscriber(sensor_ptr) { // TODO copied from TDCP_ros } -void SubscriberWrapperGnssTDCP::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void SubscriberGnssTDCP::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { - sub_ = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberWrapperGnssTDCP::callbackObservation, this); - sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberWrapperGnssTDCP::callbackNavigation, this); + sub_ = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberGnssTDCP::callbackObservation, this); + sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberGnssTDCP::callbackNavigation, this); } -void SubscriberWrapperGnssTDCP::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) +void SubscriberGnssTDCP::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) { ROS_INFO("callbackObs!"); if (last_nav_ptr_==nullptr) @@ -33,7 +33,7 @@ void SubscriberWrapperGnssTDCP::callbackObservation(const iri_gnss_msgs::Observa // } -void SubscriberWrapperGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) +void SubscriberGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) { ROS_INFO("callbackNav!"); @@ -44,7 +44,7 @@ void SubscriberWrapperGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigati // TODO copied from TDCP_ros } -std::shared_ptr SubscriberWrapperGnssTDCP::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +std::shared_ptr SubscriberGnssTDCP::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) { - return std::make_shared(_sensor_ptr); + return std::make_shared(_sensor_ptr); } diff --git a/src/wolf_ros_subscriber_gnss_fix.cpp b/src/wolf_subscriber_gnss_fix.cpp similarity index 57% rename from src/wolf_ros_subscriber_gnss_fix.cpp rename to src/wolf_subscriber_gnss_fix.cpp index d0b4885..95c648a 100644 --- a/src/wolf_ros_subscriber_gnss_fix.cpp +++ b/src/wolf_subscriber_gnss_fix.cpp @@ -1,20 +1,20 @@ -#include "../include/wolf_ros_subscriber_gnss_fix.h" +#include "../include/wolf_subscriber_gnss_fix.h" using namespace wolf; // Constructor -SubscriberWrapperGnssFix::SubscriberWrapperGnssFix(const SensorBasePtr& sensor_ptr) : - SubscriberWrapper(sensor_ptr) +SubscriberGnssFix::SubscriberGnssFix(const SensorBasePtr& sensor_ptr) : + Subscriber(sensor_ptr) { } -void SubscriberWrapperGnssFix::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void SubscriberGnssFix::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { - sub_ = nh.subscribe(topic, 1, &SubscriberWrapperGnssFix::callback, this); + sub_ = nh.subscribe(topic, 1, &SubscriberGnssFix::callback, this); } -void SubscriberWrapperGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg) +void SubscriberGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg) { Eigen::Matrix3d cov = Eigen::Map(msg->position_covariance.data()); @@ -27,7 +27,7 @@ void SubscriberWrapperGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& false); // false = {LatLonAlt fix and ENU cov} cap_gnss_ptr->process(); } -std::shared_ptr SubscriberWrapperGnssFix::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +std::shared_ptr SubscriberGnssFix::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) { - return std::make_shared(_sensor_ptr); + return std::make_shared(_sensor_ptr); } -- GitLab From cbc78aa67b030046c935659b5f69e0520ba80b48 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Thu, 12 Mar 2020 17:54:51 +0100 Subject: [PATCH 10/86] all compiling --- include/wolf_subscriber_gnss.h | 10 +++++----- include/wolf_subscriber_gnss_TDCP.h | 10 +++++----- include/wolf_subscriber_gnss_fix.h | 4 ++-- src/wolf_subscriber_gnss.cpp | 18 +++++++++--------- src/wolf_subscriber_gnss_TDCP.cpp | 18 +++++++++--------- src/wolf_subscriber_gnss_fix.cpp | 14 +++++++------- 6 files changed, 37 insertions(+), 37 deletions(-) diff --git a/include/wolf_subscriber_gnss.h b/include/wolf_subscriber_gnss.h index 0fa6531..de3a920 100644 --- a/include/wolf_subscriber_gnss.h +++ b/include/wolf_subscriber_gnss.h @@ -26,13 +26,13 @@ /************************** * WOLF-ROS includes * **************************/ -#include "wolf_ros_subscriber.h" +#include "wolf_subscriber.h" #include "subscriber_factory.h" #include "gnss_utils/gnss_utils.h" using namespace wolf; -class SubscriberWrapperGnss : public SubscriberWrapper +class WolfSubscriberGnss : public WolfSubscriber { protected: @@ -47,7 +47,7 @@ class SubscriberWrapperGnss : public SubscriberWrapper public: // Constructor - SubscriberWrapperGnss(const SensorBasePtr& sensor_ptr); + WolfSubscriberGnss(const SensorBasePtr& sensor_ptr); virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); @@ -55,6 +55,6 @@ class SubscriberWrapperGnss : public SubscriberWrapper void callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg); - static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); + static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); }; -WOLF_REGISTER_SUBSCRIBER(SubscriberWrapperGnss) +WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnss) diff --git a/include/wolf_subscriber_gnss_TDCP.h b/include/wolf_subscriber_gnss_TDCP.h index 0349dce..145a48b 100644 --- a/include/wolf_subscriber_gnss_TDCP.h +++ b/include/wolf_subscriber_gnss_TDCP.h @@ -26,13 +26,13 @@ /************************** * WOLF-ROS includes * **************************/ -#include "wolf_ros_subscriber.h" +#include "wolf_subscriber.h" #include "subscriber_factory.h" #include "gnss_utils/gnss_utils.h" using namespace wolf; -class SubscriberWrapperGnssTDCP : public SubscriberWrapper +class WolfSubscriberGnssTDCP : public WolfSubscriber { protected: @@ -44,7 +44,7 @@ class SubscriberWrapperGnssTDCP : public SubscriberWrapper public: // Constructor - SubscriberWrapperGnssTDCP(const SensorBasePtr& sensor_ptr); + WolfSubscriberGnssTDCP(const SensorBasePtr& sensor_ptr); virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); @@ -52,6 +52,6 @@ class SubscriberWrapperGnssTDCP : public SubscriberWrapper void callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg); - static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); + static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); }; -WOLF_REGISTER_SUBSCRIBER(SubscriberWrapperGnssTDCP) +WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnssTDCP) diff --git a/include/wolf_subscriber_gnss_fix.h b/include/wolf_subscriber_gnss_fix.h index 7140e6d..2a16a5f 100644 --- a/include/wolf_subscriber_gnss_fix.h +++ b/include/wolf_subscriber_gnss_fix.h @@ -24,7 +24,7 @@ /************************** * WOLF-ROS includes * **************************/ -#include "wolf_ros_subscriber.h" +#include "wolf_subscriber.h" #include "subscriber_factory.h" #include "gnss_utils/gnss_utils.h" @@ -40,6 +40,6 @@ class WolfSubscriberGnssFix : public WolfSubscriber void callback(const sensor_msgs::NavSatFix::ConstPtr& msg); - static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); + static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); }; WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnssFix) diff --git a/src/wolf_subscriber_gnss.cpp b/src/wolf_subscriber_gnss.cpp index 1ddc25f..0030098 100644 --- a/src/wolf_subscriber_gnss.cpp +++ b/src/wolf_subscriber_gnss.cpp @@ -3,8 +3,8 @@ using namespace wolf; // Constructor -SubscriberGnss::SubscriberGnss(const SensorBasePtr& sensor_ptr) : - Subscriber(sensor_ptr) +WolfSubscriberGnss::WolfSubscriberGnss(const SensorBasePtr& sensor_ptr) : + WolfSubscriber(sensor_ptr) { //prcopt_ = prcopt_default; //prcopt_.mode = PMODE_SINGLE; @@ -22,14 +22,14 @@ SubscriberGnss::SubscriberGnss(const SensorBasePtr& sensor_ptr) : } -void SubscriberGnss::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void WolfSubscriberGnss::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { - sub_ = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberGnss::callbackObservation, this); - sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberGnss::callbackNavigation, this); + sub_ = nh.subscribe(topic+std::string("_obs"), 1, &WolfSubscriberGnss::callbackObservation, this); + sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &WolfSubscriberGnss::callbackNavigation, this); } -void SubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) +void WolfSubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) { ROS_INFO("callbackObs!"); if (last_nav_ptr_==nullptr) @@ -44,7 +44,7 @@ void SubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::Const new_capture->process(); } -void SubscriberGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) +void WolfSubscriberGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) { ROS_INFO("callbackNav!"); @@ -61,7 +61,7 @@ void SubscriberGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPt // } } -std::shared_ptr SubscriberGnss::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +std::shared_ptr WolfSubscriberGnss::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) { - return std::make_shared(_sensor_ptr); + return std::make_shared(_sensor_ptr); } diff --git a/src/wolf_subscriber_gnss_TDCP.cpp b/src/wolf_subscriber_gnss_TDCP.cpp index 42bd270..e70df9e 100644 --- a/src/wolf_subscriber_gnss_TDCP.cpp +++ b/src/wolf_subscriber_gnss_TDCP.cpp @@ -3,19 +3,19 @@ using namespace wolf; // Constructor -SubscriberGnssTDCP::SubscriberGnssTDCP(const SensorBasePtr& sensor_ptr) : - Subscriber(sensor_ptr) +WolfSubscriberGnssTDCP::WolfSubscriberGnssTDCP(const SensorBasePtr& sensor_ptr) : + WolfSubscriber(sensor_ptr) { // TODO copied from TDCP_ros } -void SubscriberGnssTDCP::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void WolfSubscriberGnssTDCP::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { - sub_ = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberGnssTDCP::callbackObservation, this); - sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberGnssTDCP::callbackNavigation, this); + sub_ = nh.subscribe(topic+std::string("_obs"), 1, &WolfSubscriberGnssTDCP::callbackObservation, this); + sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &WolfSubscriberGnssTDCP::callbackNavigation, this); } -void SubscriberGnssTDCP::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) +void WolfSubscriberGnssTDCP::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) { ROS_INFO("callbackObs!"); if (last_nav_ptr_==nullptr) @@ -33,7 +33,7 @@ void SubscriberGnssTDCP::callbackObservation(const iri_gnss_msgs::Observation::C // } -void SubscriberGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) +void WolfSubscriberGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) { ROS_INFO("callbackNav!"); @@ -44,7 +44,7 @@ void SubscriberGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigation::Con // TODO copied from TDCP_ros } -std::shared_ptr SubscriberGnssTDCP::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +std::shared_ptr WolfSubscriberGnssTDCP::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) { - return std::make_shared(_sensor_ptr); + return std::make_shared(_sensor_ptr); } diff --git a/src/wolf_subscriber_gnss_fix.cpp b/src/wolf_subscriber_gnss_fix.cpp index 95c648a..0587ed8 100644 --- a/src/wolf_subscriber_gnss_fix.cpp +++ b/src/wolf_subscriber_gnss_fix.cpp @@ -3,18 +3,18 @@ using namespace wolf; // Constructor -SubscriberGnssFix::SubscriberGnssFix(const SensorBasePtr& sensor_ptr) : - Subscriber(sensor_ptr) +WolfSubscriberGnssFix::WolfSubscriberGnssFix(const SensorBasePtr& sensor_ptr) : + WolfSubscriber(sensor_ptr) { } -void SubscriberGnssFix::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void WolfSubscriberGnssFix::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { - sub_ = nh.subscribe(topic, 1, &SubscriberGnssFix::callback, this); + sub_ = nh.subscribe(topic, 1, &WolfSubscriberGnssFix::callback, this); } -void SubscriberGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg) +void WolfSubscriberGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg) { Eigen::Matrix3d cov = Eigen::Map(msg->position_covariance.data()); @@ -27,7 +27,7 @@ void SubscriberGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg) false); // false = {LatLonAlt fix and ENU cov} cap_gnss_ptr->process(); } -std::shared_ptr SubscriberGnssFix::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +std::shared_ptr WolfSubscriberGnssFix::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) { - return std::make_shared(_sensor_ptr); + return std::make_shared(_sensor_ptr); } -- GitLab From 48780bc0d1bd05d147a2ff741b9599d75ac77ecd Mon Sep 17 00:00:00 2001 From: PepMS Date: Thu, 19 Mar 2020 14:04:26 +0100 Subject: [PATCH 11/86] [ublox] add subs. structure to work with ublox --- CMakeLists.txt | 7 +++++ include/wolf_subscriber_gnss_ublox.h | 38 ++++++++++++++++++++++++++++ src/wolf_subscriber_gnss_ublox.cpp | 25 ++++++++++++++++++ 3 files changed, 70 insertions(+) create mode 100644 include/wolf_subscriber_gnss_ublox.h create mode 100644 src/wolf_subscriber_gnss_ublox.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 326764d..5443273 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -140,6 +140,7 @@ include_directories( add_library(wolf_subscriber_gnss src/wolf_subscriber_gnss.cpp) add_library(wolf_subscriber_gnss_fix src/wolf_subscriber_gnss_fix.cpp) add_library(wolf_subscriber_gnss_TDCP src/wolf_subscriber_gnss_TDCP.cpp) +add_library(wolf_subscriber_gnss_ublox src/wolf_subscriber_gnss_ublox.cpp) ## Add cmake target dependencies of the library ## as an example, code may need to be generated before libraries @@ -177,6 +178,12 @@ target_link_libraries(wolf_subscriber_gnss_TDCP ${wolf_LIBRARIES} ${wolfgnss_LIBRARIES} ${iri_gnss_msgs_LIBRARIES} + ) + +target_link_libraries(wolf_subscriber_gnss_ublox + ${wolf_LIBRARIES} + ${wolfgnss_LIBRARIES} + ${iri_gnss_msgs_LIBRARIES} ) ############# diff --git a/include/wolf_subscriber_gnss_ublox.h b/include/wolf_subscriber_gnss_ublox.h new file mode 100644 index 0000000..baaad15 --- /dev/null +++ b/include/wolf_subscriber_gnss_ublox.h @@ -0,0 +1,38 @@ +/************************** + * WOLF includes * + **************************/ +#include +#include +#include +#include +#include +#include + +/************************** + * ROS includes * + **************************/ +#include +#include + +/************************** + * WOLF-ROS includes * + **************************/ +#include "wolf_subscriber.h" +#include "subscriber_factory.h" +#include "gnss_utils/gnss_utils.h" + +using namespace wolf; + +class WolfSubscriberGnssUblox : public WolfSubscriber +{ + public: + // Constructor + WolfSubscriberGnssUblox(const SensorBasePtr& sensor_ptr); + + virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); + + void callback(const std_msgs::UInt8MultiArray& msg); + + static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); +}; +WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnssUblox) \ No newline at end of file diff --git a/src/wolf_subscriber_gnss_ublox.cpp b/src/wolf_subscriber_gnss_ublox.cpp new file mode 100644 index 0000000..607097e --- /dev/null +++ b/src/wolf_subscriber_gnss_ublox.cpp @@ -0,0 +1,25 @@ +#include "../include/wolf_subscriber_gnss_ublox.h" + +using namespace wolf; + +// Constructor +WolfSubscriberGnssUblox::WolfSubscriberGnssUblox(const SensorBasePtr& sensor_ptr) : + WolfSubscriber(sensor_ptr) +{ +} + + +void WolfSubscriberGnssUblox::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +{ + sub_ = nh.subscribe(topic, 1, &WolfSubscriberGnssUblox::callback, this); +} + +void WolfSubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) +{ + + // cap_gnss_ptr->process(); +} +std::shared_ptr WolfSubscriberGnssUblox::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +{ + return std::make_shared(_sensor_ptr); +} -- GitLab From 844177243ecd2f797a8e5ede67d16045b0db36da Mon Sep 17 00:00:00 2001 From: joanvallve Date: Wed, 25 Mar 2020 14:07:28 +0100 Subject: [PATCH 12/86] subscriber ublox implemented compiling --- include/wolf_subscriber_gnss_ublox.h | 9 +++++++-- src/wolf_subscriber_gnss_ublox.cpp | 15 ++++++++++++++- 2 files changed, 21 insertions(+), 3 deletions(-) diff --git a/include/wolf_subscriber_gnss_ublox.h b/include/wolf_subscriber_gnss_ublox.h index baaad15..920d61d 100644 --- a/include/wolf_subscriber_gnss_ublox.h +++ b/include/wolf_subscriber_gnss_ublox.h @@ -5,7 +5,7 @@ #include #include #include -#include +#include #include /************************** @@ -20,6 +20,7 @@ #include "wolf_subscriber.h" #include "subscriber_factory.h" #include "gnss_utils/gnss_utils.h" +#include "gnss_utils/ublox_raw.h" using namespace wolf; @@ -34,5 +35,9 @@ class WolfSubscriberGnssUblox : public WolfSubscriber void callback(const std_msgs::UInt8MultiArray& msg); static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); + + protected: + + GNSSUtils::UBloxRaw ublox_raw_; }; -WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnssUblox) \ No newline at end of file +WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnssUblox) diff --git a/src/wolf_subscriber_gnss_ublox.cpp b/src/wolf_subscriber_gnss_ublox.cpp index 607097e..8bcb1f2 100644 --- a/src/wolf_subscriber_gnss_ublox.cpp +++ b/src/wolf_subscriber_gnss_ublox.cpp @@ -15,9 +15,22 @@ void WolfSubscriberGnssUblox::initSubscriber(ros::NodeHandle& nh, const std::str } void WolfSubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) + { + // only create capture if observation is received + if (ublox_raw_.addDataStream(msg.data) == GNSSUtils::OBS) + { + GNSSUtils::ObservationsPtr obs_ptr = std::make_shared(ublox_raw_.getObservations()); + GNSSUtils::NavigationPtr nav_ptr = std::make_shared(ublox_raw_.getNavigation()); + + ros::Time now = ros::Time::now(); - // cap_gnss_ptr->process(); + auto cap_gnss_ptr = std::make_shared(TimeStamp(now.sec, now.nsec), + sensor_ptr_, + obs_ptr, + nav_ptr); + cap_gnss_ptr->process(); + } } std::shared_ptr WolfSubscriberGnssUblox::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) { -- GitLab From 788296d53ab09bf8972a8667fac9c974219e57f8 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Wed, 25 Mar 2020 17:07:28 +0100 Subject: [PATCH 13/86] added infos for debugging --- src/wolf_subscriber_gnss_ublox.cpp | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/src/wolf_subscriber_gnss_ublox.cpp b/src/wolf_subscriber_gnss_ublox.cpp index 8bcb1f2..c0755c8 100644 --- a/src/wolf_subscriber_gnss_ublox.cpp +++ b/src/wolf_subscriber_gnss_ublox.cpp @@ -17,11 +17,19 @@ void WolfSubscriberGnssUblox::initSubscriber(ros::NodeHandle& nh, const std::str void WolfSubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) { + ROS_INFO("Ublox data stream callback!"); + + GNSSUtils::RawDataType res = ublox_raw_.addDataStream(msg.data); + // only create capture if observation is received - if (ublox_raw_.addDataStream(msg.data) == GNSSUtils::OBS) + if (res == GNSSUtils::OBS) { + ROS_INFO("Observation received!"); + GNSSUtils::ObservationsPtr obs_ptr = std::make_shared(ublox_raw_.getObservations()); + ROS_INFO("Observations copied!"); GNSSUtils::NavigationPtr nav_ptr = std::make_shared(ublox_raw_.getNavigation()); + ROS_INFO("Navigation copied!"); ros::Time now = ros::Time::now(); @@ -29,7 +37,10 @@ void WolfSubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) sensor_ptr_, obs_ptr, nav_ptr); + + ROS_INFO("Capture GNSS created!"); cap_gnss_ptr->process(); + ROS_INFO("Capture GNSS processed!"); } } std::shared_ptr WolfSubscriberGnssUblox::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) -- GitLab From 0e6c961dc97c092bc69f25de475f6bb6db6eb0f6 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Thu, 26 Mar 2020 12:34:43 +0100 Subject: [PATCH 14/86] working --- src/wolf_subscriber_gnss_ublox.cpp | 17 ++++++++--------- 1 file changed, 8 insertions(+), 9 deletions(-) diff --git a/src/wolf_subscriber_gnss_ublox.cpp b/src/wolf_subscriber_gnss_ublox.cpp index c0755c8..58d304b 100644 --- a/src/wolf_subscriber_gnss_ublox.cpp +++ b/src/wolf_subscriber_gnss_ublox.cpp @@ -11,25 +11,24 @@ WolfSubscriberGnssUblox::WolfSubscriberGnssUblox(const SensorBasePtr& sensor_ptr void WolfSubscriberGnssUblox::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { - sub_ = nh.subscribe(topic, 1, &WolfSubscriberGnssUblox::callback, this); + sub_ = nh.subscribe(topic, 10, &WolfSubscriberGnssUblox::callback, this); } void WolfSubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) { - ROS_INFO("Ublox data stream callback!"); - GNSSUtils::RawDataType res = ublox_raw_.addDataStream(msg.data); + //std::cout << "res = " << (int) res << std::endl; + // only create capture if observation is received if (res == GNSSUtils::OBS) { - ROS_INFO("Observation received!"); - + //ROS_INFO("Observation received!"); GNSSUtils::ObservationsPtr obs_ptr = std::make_shared(ublox_raw_.getObservations()); - ROS_INFO("Observations copied!"); + //ROS_INFO("Observations copied!"); GNSSUtils::NavigationPtr nav_ptr = std::make_shared(ublox_raw_.getNavigation()); - ROS_INFO("Navigation copied!"); + //ROS_INFO("Navigation copied!"); ros::Time now = ros::Time::now(); @@ -38,9 +37,9 @@ void WolfSubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) obs_ptr, nav_ptr); - ROS_INFO("Capture GNSS created!"); + //ROS_INFO("Capture GNSS created!"); cap_gnss_ptr->process(); - ROS_INFO("Capture GNSS processed!"); + //ROS_INFO("Capture GNSS processed!"); } } std::shared_ptr WolfSubscriberGnssUblox::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) -- GitLab From d94c0fb946faf25cd6423a408265074bb3d22c5f Mon Sep 17 00:00:00 2001 From: jcasals Date: Thu, 26 Mar 2020 09:27:17 +0100 Subject: [PATCH 15/86] Remove wolf & wrapper from names --- CMakeLists.txt | 16 ++++++++-------- ...olf_subscriber_gnss.h => subscriber_gnss.h} | 10 +++++----- ...iber_gnss_TDCP.h => subscriber_gnss_TDCP.h} | 10 +++++----- ...criber_gnss_fix.h => subscriber_gnss_fix.h} | 10 +++++----- ...er_gnss_ublox.h => subscriber_gnss_ublox.h} | 10 +++++----- ...subscriber_gnss.cpp => subscriber_gnss.cpp} | 18 +++++++++--------- ..._gnss_TDCP.cpp => subscriber_gnss_TDCP.cpp} | 18 +++++++++--------- ...er_gnss_fix.cpp => subscriber_gnss_fix.cpp} | 14 +++++++------- ...nss_ublox.cpp => subscriber_gnss_ublox.cpp} | 12 ++++++------ 9 files changed, 59 insertions(+), 59 deletions(-) rename include/{wolf_subscriber_gnss.h => subscriber_gnss.h} (81%) rename include/{wolf_subscriber_gnss_TDCP.h => subscriber_gnss_TDCP.h} (79%) rename include/{wolf_subscriber_gnss_fix.h => subscriber_gnss_fix.h} (73%) rename include/{wolf_subscriber_gnss_ublox.h => subscriber_gnss_ublox.h} (72%) rename src/{wolf_subscriber_gnss.cpp => subscriber_gnss.cpp} (65%) rename src/{wolf_subscriber_gnss_TDCP.cpp => subscriber_gnss_TDCP.cpp} (53%) rename src/{wolf_subscriber_gnss_fix.cpp => subscriber_gnss_fix.cpp} (62%) rename src/{wolf_subscriber_gnss_ublox.cpp => subscriber_gnss_ublox.cpp} (70%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5443273..69a2ef1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -137,10 +137,10 @@ include_directories( # add_library(${PROJECT_NAME} # src/${PROJECT_NAME}/wolf_ros.cpp # ) -add_library(wolf_subscriber_gnss src/wolf_subscriber_gnss.cpp) -add_library(wolf_subscriber_gnss_fix src/wolf_subscriber_gnss_fix.cpp) -add_library(wolf_subscriber_gnss_TDCP src/wolf_subscriber_gnss_TDCP.cpp) -add_library(wolf_subscriber_gnss_ublox src/wolf_subscriber_gnss_ublox.cpp) +add_library(subscriber_gnss src/subscriber_gnss.cpp) +add_library(subscriber_gnss_fix src/subscriber_gnss_fix.cpp) +add_library(subscriber_gnss_TDCP src/subscriber_gnss_TDCP.cpp) +add_library(subscriber_gnss_ublox src/subscriber_gnss_ublox.cpp) ## Add cmake target dependencies of the library ## as an example, code may need to be generated before libraries @@ -164,23 +164,23 @@ add_library(wolf_subscriber_gnss_ublox src/wolf_subscriber_gnss_ublox.cpp) #add_dependencies(${PROJECT_NAME}_visualizer ${PROJECT_NAME}_gencfg) ## Specify libraries to link a library or executable target against -target_link_libraries(wolf_subscriber_gnss +target_link_libraries(subscriber_gnss ${wolf_LIBRARIES} ${wolfgnss_LIBRARIES} ${iri_gnss_msgs_LIBRARIES} ) -target_link_libraries(wolf_subscriber_gnss_fix +target_link_libraries(subscriber_gnss_fix ${wolf_LIBRARIES} ${wolfgnss_LIBRARIES} ${iri_gnss_msgs_LIBRARIES} ) -target_link_libraries(wolf_subscriber_gnss_TDCP +target_link_libraries(subscriber_gnss_TDCP ${wolf_LIBRARIES} ${wolfgnss_LIBRARIES} ${iri_gnss_msgs_LIBRARIES} ) -target_link_libraries(wolf_subscriber_gnss_ublox +target_link_libraries(subscriber_gnss_ublox ${wolf_LIBRARIES} ${wolfgnss_LIBRARIES} ${iri_gnss_msgs_LIBRARIES} diff --git a/include/wolf_subscriber_gnss.h b/include/subscriber_gnss.h similarity index 81% rename from include/wolf_subscriber_gnss.h rename to include/subscriber_gnss.h index de3a920..abe5874 100644 --- a/include/wolf_subscriber_gnss.h +++ b/include/subscriber_gnss.h @@ -26,13 +26,13 @@ /************************** * WOLF-ROS includes * **************************/ -#include "wolf_subscriber.h" +#include "subscriber.h" #include "subscriber_factory.h" #include "gnss_utils/gnss_utils.h" using namespace wolf; -class WolfSubscriberGnss : public WolfSubscriber +class SubscriberGnss : public Subscriber { protected: @@ -47,7 +47,7 @@ class WolfSubscriberGnss : public WolfSubscriber public: // Constructor - WolfSubscriberGnss(const SensorBasePtr& sensor_ptr); + SubscriberGnss(const SensorBasePtr& sensor_ptr); virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); @@ -55,6 +55,6 @@ class WolfSubscriberGnss : public WolfSubscriber void callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg); - static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); + static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); }; -WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnss) +WOLF_REGISTER_SUBSCRIBER(SubscriberGnss) diff --git a/include/wolf_subscriber_gnss_TDCP.h b/include/subscriber_gnss_TDCP.h similarity index 79% rename from include/wolf_subscriber_gnss_TDCP.h rename to include/subscriber_gnss_TDCP.h index 145a48b..69f2743 100644 --- a/include/wolf_subscriber_gnss_TDCP.h +++ b/include/subscriber_gnss_TDCP.h @@ -26,13 +26,13 @@ /************************** * WOLF-ROS includes * **************************/ -#include "wolf_subscriber.h" +#include "subscriber.h" #include "subscriber_factory.h" #include "gnss_utils/gnss_utils.h" using namespace wolf; -class WolfSubscriberGnssTDCP : public WolfSubscriber +class SubscriberGnssTDCP : public Subscriber { protected: @@ -44,7 +44,7 @@ class WolfSubscriberGnssTDCP : public WolfSubscriber public: // Constructor - WolfSubscriberGnssTDCP(const SensorBasePtr& sensor_ptr); + SubscriberGnssTDCP(const SensorBasePtr& sensor_ptr); virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); @@ -52,6 +52,6 @@ class WolfSubscriberGnssTDCP : public WolfSubscriber void callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg); - static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); + static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); }; -WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnssTDCP) +WOLF_REGISTER_SUBSCRIBER(SubscriberGnssTDCP) diff --git a/include/wolf_subscriber_gnss_fix.h b/include/subscriber_gnss_fix.h similarity index 73% rename from include/wolf_subscriber_gnss_fix.h rename to include/subscriber_gnss_fix.h index 2a16a5f..33c4b70 100644 --- a/include/wolf_subscriber_gnss_fix.h +++ b/include/subscriber_gnss_fix.h @@ -24,22 +24,22 @@ /************************** * WOLF-ROS includes * **************************/ -#include "wolf_subscriber.h" +#include "subscriber.h" #include "subscriber_factory.h" #include "gnss_utils/gnss_utils.h" using namespace wolf; -class WolfSubscriberGnssFix : public WolfSubscriber +class SubscriberGnssFix : public Subscriber { public: // Constructor - WolfSubscriberGnssFix(const SensorBasePtr& sensor_ptr); + SubscriberGnssFix(const SensorBasePtr& sensor_ptr); virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); void callback(const sensor_msgs::NavSatFix::ConstPtr& msg); - static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); + static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); }; -WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnssFix) +WOLF_REGISTER_SUBSCRIBER(SubscriberGnssFix) diff --git a/include/wolf_subscriber_gnss_ublox.h b/include/subscriber_gnss_ublox.h similarity index 72% rename from include/wolf_subscriber_gnss_ublox.h rename to include/subscriber_gnss_ublox.h index 920d61d..f16d2bc 100644 --- a/include/wolf_subscriber_gnss_ublox.h +++ b/include/subscriber_gnss_ublox.h @@ -17,27 +17,27 @@ /************************** * WOLF-ROS includes * **************************/ -#include "wolf_subscriber.h" +#include "subscriber.h" #include "subscriber_factory.h" #include "gnss_utils/gnss_utils.h" #include "gnss_utils/ublox_raw.h" using namespace wolf; -class WolfSubscriberGnssUblox : public WolfSubscriber +class SubscriberGnssUblox : public Subscriber { public: // Constructor - WolfSubscriberGnssUblox(const SensorBasePtr& sensor_ptr); + SubscriberGnssUblox(const SensorBasePtr& sensor_ptr); virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); void callback(const std_msgs::UInt8MultiArray& msg); - static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); + static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); protected: GNSSUtils::UBloxRaw ublox_raw_; }; -WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnssUblox) +WOLF_REGISTER_SUBSCRIBER(SubscriberGnssUblox) diff --git a/src/wolf_subscriber_gnss.cpp b/src/subscriber_gnss.cpp similarity index 65% rename from src/wolf_subscriber_gnss.cpp rename to src/subscriber_gnss.cpp index 0030098..1ddc25f 100644 --- a/src/wolf_subscriber_gnss.cpp +++ b/src/subscriber_gnss.cpp @@ -3,8 +3,8 @@ using namespace wolf; // Constructor -WolfSubscriberGnss::WolfSubscriberGnss(const SensorBasePtr& sensor_ptr) : - WolfSubscriber(sensor_ptr) +SubscriberGnss::SubscriberGnss(const SensorBasePtr& sensor_ptr) : + Subscriber(sensor_ptr) { //prcopt_ = prcopt_default; //prcopt_.mode = PMODE_SINGLE; @@ -22,14 +22,14 @@ WolfSubscriberGnss::WolfSubscriberGnss(const SensorBasePtr& sensor_ptr) : } -void WolfSubscriberGnss::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void SubscriberGnss::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { - sub_ = nh.subscribe(topic+std::string("_obs"), 1, &WolfSubscriberGnss::callbackObservation, this); - sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &WolfSubscriberGnss::callbackNavigation, this); + sub_ = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberGnss::callbackObservation, this); + sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberGnss::callbackNavigation, this); } -void WolfSubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) +void SubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) { ROS_INFO("callbackObs!"); if (last_nav_ptr_==nullptr) @@ -44,7 +44,7 @@ void WolfSubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::C new_capture->process(); } -void WolfSubscriberGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) +void SubscriberGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) { ROS_INFO("callbackNav!"); @@ -61,7 +61,7 @@ void WolfSubscriberGnss::callbackNavigation(const iri_gnss_msgs::Navigation::Con // } } -std::shared_ptr WolfSubscriberGnss::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +std::shared_ptr SubscriberGnss::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) { - return std::make_shared(_sensor_ptr); + return std::make_shared(_sensor_ptr); } diff --git a/src/wolf_subscriber_gnss_TDCP.cpp b/src/subscriber_gnss_TDCP.cpp similarity index 53% rename from src/wolf_subscriber_gnss_TDCP.cpp rename to src/subscriber_gnss_TDCP.cpp index e70df9e..42bd270 100644 --- a/src/wolf_subscriber_gnss_TDCP.cpp +++ b/src/subscriber_gnss_TDCP.cpp @@ -3,19 +3,19 @@ using namespace wolf; // Constructor -WolfSubscriberGnssTDCP::WolfSubscriberGnssTDCP(const SensorBasePtr& sensor_ptr) : - WolfSubscriber(sensor_ptr) +SubscriberGnssTDCP::SubscriberGnssTDCP(const SensorBasePtr& sensor_ptr) : + Subscriber(sensor_ptr) { // TODO copied from TDCP_ros } -void WolfSubscriberGnssTDCP::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void SubscriberGnssTDCP::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { - sub_ = nh.subscribe(topic+std::string("_obs"), 1, &WolfSubscriberGnssTDCP::callbackObservation, this); - sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &WolfSubscriberGnssTDCP::callbackNavigation, this); + sub_ = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberGnssTDCP::callbackObservation, this); + sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberGnssTDCP::callbackNavigation, this); } -void WolfSubscriberGnssTDCP::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) +void SubscriberGnssTDCP::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) { ROS_INFO("callbackObs!"); if (last_nav_ptr_==nullptr) @@ -33,7 +33,7 @@ void WolfSubscriberGnssTDCP::callbackObservation(const iri_gnss_msgs::Observatio // } -void WolfSubscriberGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) +void SubscriberGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) { ROS_INFO("callbackNav!"); @@ -44,7 +44,7 @@ void WolfSubscriberGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigation: // TODO copied from TDCP_ros } -std::shared_ptr WolfSubscriberGnssTDCP::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +std::shared_ptr SubscriberGnssTDCP::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) { - return std::make_shared(_sensor_ptr); + return std::make_shared(_sensor_ptr); } diff --git a/src/wolf_subscriber_gnss_fix.cpp b/src/subscriber_gnss_fix.cpp similarity index 62% rename from src/wolf_subscriber_gnss_fix.cpp rename to src/subscriber_gnss_fix.cpp index 0587ed8..95c648a 100644 --- a/src/wolf_subscriber_gnss_fix.cpp +++ b/src/subscriber_gnss_fix.cpp @@ -3,18 +3,18 @@ using namespace wolf; // Constructor -WolfSubscriberGnssFix::WolfSubscriberGnssFix(const SensorBasePtr& sensor_ptr) : - WolfSubscriber(sensor_ptr) +SubscriberGnssFix::SubscriberGnssFix(const SensorBasePtr& sensor_ptr) : + Subscriber(sensor_ptr) { } -void WolfSubscriberGnssFix::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void SubscriberGnssFix::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { - sub_ = nh.subscribe(topic, 1, &WolfSubscriberGnssFix::callback, this); + sub_ = nh.subscribe(topic, 1, &SubscriberGnssFix::callback, this); } -void WolfSubscriberGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg) +void SubscriberGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg) { Eigen::Matrix3d cov = Eigen::Map(msg->position_covariance.data()); @@ -27,7 +27,7 @@ void WolfSubscriberGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg false); // false = {LatLonAlt fix and ENU cov} cap_gnss_ptr->process(); } -std::shared_ptr WolfSubscriberGnssFix::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +std::shared_ptr SubscriberGnssFix::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) { - return std::make_shared(_sensor_ptr); + return std::make_shared(_sensor_ptr); } diff --git a/src/wolf_subscriber_gnss_ublox.cpp b/src/subscriber_gnss_ublox.cpp similarity index 70% rename from src/wolf_subscriber_gnss_ublox.cpp rename to src/subscriber_gnss_ublox.cpp index 58d304b..87daa4d 100644 --- a/src/wolf_subscriber_gnss_ublox.cpp +++ b/src/subscriber_gnss_ublox.cpp @@ -3,18 +3,18 @@ using namespace wolf; // Constructor -WolfSubscriberGnssUblox::WolfSubscriberGnssUblox(const SensorBasePtr& sensor_ptr) : - WolfSubscriber(sensor_ptr) +SubscriberGnssUblox::SubscriberGnssUblox(const SensorBasePtr& sensor_ptr) : + Subscriber(sensor_ptr) { } -void WolfSubscriberGnssUblox::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void SubscriberGnssUblox::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { sub_ = nh.subscribe(topic, 10, &WolfSubscriberGnssUblox::callback, this); } -void WolfSubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) +void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) { GNSSUtils::RawDataType res = ublox_raw_.addDataStream(msg.data); @@ -42,7 +42,7 @@ void WolfSubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) //ROS_INFO("Capture GNSS processed!"); } } -std::shared_ptr WolfSubscriberGnssUblox::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +std::shared_ptr SubscriberGnssUblox::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) { - return std::make_shared(_sensor_ptr); + return std::make_shared(_sensor_ptr); } -- GitLab From db28e6ee15c9ec8aa41b43109fba14876454de57 Mon Sep 17 00:00:00 2001 From: jcasals Date: Thu, 26 Mar 2020 16:05:11 +0100 Subject: [PATCH 16/86] Rename --- CMakeLists.txt | 4 ++-- ...ber_gnss_TDCP.h => subscriber_gnss_Tdcp.h} | 6 ++--- ...gnss_TDCP.cpp => subscriber_gnss_Tdcp.cpp} | 24 +++++++++---------- 3 files changed, 17 insertions(+), 17 deletions(-) rename include/{subscriber_gnss_TDCP.h => subscriber_gnss_Tdcp.h} (90%) rename src/{subscriber_gnss_TDCP.cpp => subscriber_gnss_Tdcp.cpp} (65%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 69a2ef1..75ed929 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -139,7 +139,7 @@ include_directories( # ) add_library(subscriber_gnss src/subscriber_gnss.cpp) add_library(subscriber_gnss_fix src/subscriber_gnss_fix.cpp) -add_library(subscriber_gnss_TDCP src/subscriber_gnss_TDCP.cpp) +add_library(subscriber_gnss_Tdcp src/subscriber_gnss_Tdcp.cpp) add_library(subscriber_gnss_ublox src/subscriber_gnss_ublox.cpp) ## Add cmake target dependencies of the library @@ -174,7 +174,7 @@ target_link_libraries(subscriber_gnss_fix ${wolfgnss_LIBRARIES} ${iri_gnss_msgs_LIBRARIES} ) -target_link_libraries(subscriber_gnss_TDCP +target_link_libraries(subscriber_gnss_Tdcp ${wolf_LIBRARIES} ${wolfgnss_LIBRARIES} ${iri_gnss_msgs_LIBRARIES} diff --git a/include/subscriber_gnss_TDCP.h b/include/subscriber_gnss_Tdcp.h similarity index 90% rename from include/subscriber_gnss_TDCP.h rename to include/subscriber_gnss_Tdcp.h index 69f2743..be74dbb 100644 --- a/include/subscriber_gnss_TDCP.h +++ b/include/subscriber_gnss_Tdcp.h @@ -32,7 +32,7 @@ using namespace wolf; -class SubscriberGnssTDCP : public Subscriber +class SubscriberGnssTdcp : public Subscriber { protected: @@ -44,7 +44,7 @@ class SubscriberGnssTDCP : public Subscriber public: // Constructor - SubscriberGnssTDCP(const SensorBasePtr& sensor_ptr); + SubscriberGnssTdcp(const SensorBasePtr& sensor_ptr); virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); @@ -54,4 +54,4 @@ class SubscriberGnssTDCP : public Subscriber static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); }; -WOLF_REGISTER_SUBSCRIBER(SubscriberGnssTDCP) +WOLF_REGISTER_SUBSCRIBER(SubscriberGnssTdcp) diff --git a/src/subscriber_gnss_TDCP.cpp b/src/subscriber_gnss_Tdcp.cpp similarity index 65% rename from src/subscriber_gnss_TDCP.cpp rename to src/subscriber_gnss_Tdcp.cpp index 42bd270..4f8442f 100644 --- a/src/subscriber_gnss_TDCP.cpp +++ b/src/subscriber_gnss_Tdcp.cpp @@ -1,27 +1,27 @@ -#include "../include/wolf_subscriber_gnss_TDCP.h" +#include "../include/wolf_subscriber_gnss_Tdcp.h" using namespace wolf; // Constructor -SubscriberGnssTDCP::SubscriberGnssTDCP(const SensorBasePtr& sensor_ptr) : +SubscriberGnssTdcp::SubscriberGnssTdcp(const SensorBasePtr& sensor_ptr) : Subscriber(sensor_ptr) { - // TODO copied from TDCP_ros + // TODO copied from Tdcp_ros } -void SubscriberGnssTDCP::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void SubscriberGnssTdcp::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { - sub_ = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberGnssTDCP::callbackObservation, this); - sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberGnssTDCP::callbackNavigation, this); + sub_ = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberGnssTdcp::callbackObservation, this); + sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberGnssTdcp::callbackNavigation, this); } -void SubscriberGnssTDCP::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) +void SubscriberGnssTdcp::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) { ROS_INFO("callbackObs!"); if (last_nav_ptr_==nullptr) return; - // TODO copied from TDCP_ros + // TODO copied from Tdcp_ros // GNSSUtils::ObservationsPtr obs_ptr = std::make_shared(); // GNSSUtils::fillObservation(*obs_ptr, msg); @@ -33,7 +33,7 @@ void SubscriberGnssTDCP::callbackObservation(const iri_gnss_msgs::Observation::C // } -void SubscriberGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) +void SubscriberGnssTdcp::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) { ROS_INFO("callbackNav!"); @@ -41,10 +41,10 @@ void SubscriberGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigation::Con GNSSUtils::fillNavigation(*last_nav_ptr_, msg); last_nav_ptr_->print(); - // TODO copied from TDCP_ros + // TODO copied from Tdcp_ros } -std::shared_ptr SubscriberGnssTDCP::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +std::shared_ptr SubscriberGnssTdcp::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) { - return std::make_shared(_sensor_ptr); + return std::make_shared(_sensor_ptr); } -- GitLab From dbb779a328f858c530f6371ee3ec20ae2fc53244 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Thu, 2 Apr 2020 10:20:50 +0200 Subject: [PATCH 17/86] increasing buffer size --- CMakeLists.txt | 3 +-- src/wolf_subscriber_gnss_ublox.cpp | 2 +- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5443273..a459fa1 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -178,8 +178,7 @@ target_link_libraries(wolf_subscriber_gnss_TDCP ${wolf_LIBRARIES} ${wolfgnss_LIBRARIES} ${iri_gnss_msgs_LIBRARIES} - ) - + ) target_link_libraries(wolf_subscriber_gnss_ublox ${wolf_LIBRARIES} ${wolfgnss_LIBRARIES} diff --git a/src/wolf_subscriber_gnss_ublox.cpp b/src/wolf_subscriber_gnss_ublox.cpp index 58d304b..33bcbff 100644 --- a/src/wolf_subscriber_gnss_ublox.cpp +++ b/src/wolf_subscriber_gnss_ublox.cpp @@ -11,7 +11,7 @@ WolfSubscriberGnssUblox::WolfSubscriberGnssUblox(const SensorBasePtr& sensor_ptr void WolfSubscriberGnssUblox::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { - sub_ = nh.subscribe(topic, 10, &WolfSubscriberGnssUblox::callback, this); + sub_ = nh.subscribe(topic, 100, &WolfSubscriberGnssUblox::callback, this); } void WolfSubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) -- GitLab From d9fbd27c77d77e7b66351dd47ccc644f8e693cc8 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Thu, 2 Apr 2020 14:41:32 +0200 Subject: [PATCH 18/86] fixed wrong includes --- CMakeLists.txt | 4 ++-- include/{subscriber_gnss_Tdcp.h => subscriber_gnss_tdcp.h} | 0 src/subscriber_gnss.cpp | 2 +- src/subscriber_gnss_fix.cpp | 2 +- src/{subscriber_gnss_Tdcp.cpp => subscriber_gnss_tdcp.cpp} | 2 +- 5 files changed, 5 insertions(+), 5 deletions(-) rename include/{subscriber_gnss_Tdcp.h => subscriber_gnss_tdcp.h} (100%) rename src/{subscriber_gnss_Tdcp.cpp => subscriber_gnss_tdcp.cpp} (97%) diff --git a/CMakeLists.txt b/CMakeLists.txt index f68f9b0..57ec760 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -139,7 +139,7 @@ include_directories( # ) add_library(subscriber_gnss src/subscriber_gnss.cpp) add_library(subscriber_gnss_fix src/subscriber_gnss_fix.cpp) -add_library(subscriber_gnss_Tdcp src/subscriber_gnss_Tdcp.cpp) +add_library(subscriber_gnss_tdcp src/subscriber_gnss_tdcp.cpp) add_library(subscriber_gnss_ublox src/subscriber_gnss_ublox.cpp) ## Add cmake target dependencies of the library @@ -174,7 +174,7 @@ target_link_libraries(subscriber_gnss_fix ${wolfgnss_LIBRARIES} ${iri_gnss_msgs_LIBRARIES} ) -target_link_libraries(subscriber_gnss_Tdcp +target_link_libraries(subscriber_gnss_tdcp ${wolf_LIBRARIES} ${wolfgnss_LIBRARIES} ${iri_gnss_msgs_LIBRARIES} diff --git a/include/subscriber_gnss_Tdcp.h b/include/subscriber_gnss_tdcp.h similarity index 100% rename from include/subscriber_gnss_Tdcp.h rename to include/subscriber_gnss_tdcp.h diff --git a/src/subscriber_gnss.cpp b/src/subscriber_gnss.cpp index 1ddc25f..f80d76c 100644 --- a/src/subscriber_gnss.cpp +++ b/src/subscriber_gnss.cpp @@ -1,4 +1,4 @@ -#include "../include/wolf_subscriber_gnss.h" +#include "../include/subscriber_gnss.h" using namespace wolf; diff --git a/src/subscriber_gnss_fix.cpp b/src/subscriber_gnss_fix.cpp index 95c648a..4434a70 100644 --- a/src/subscriber_gnss_fix.cpp +++ b/src/subscriber_gnss_fix.cpp @@ -1,4 +1,4 @@ -#include "../include/wolf_subscriber_gnss_fix.h" +#include "../include/subscriber_gnss_fix.h" using namespace wolf; diff --git a/src/subscriber_gnss_Tdcp.cpp b/src/subscriber_gnss_tdcp.cpp similarity index 97% rename from src/subscriber_gnss_Tdcp.cpp rename to src/subscriber_gnss_tdcp.cpp index 4f8442f..375d3c5 100644 --- a/src/subscriber_gnss_Tdcp.cpp +++ b/src/subscriber_gnss_tdcp.cpp @@ -1,4 +1,4 @@ -#include "../include/wolf_subscriber_gnss_Tdcp.h" +#include "../include/subscriber_gnss_tdcp.h" using namespace wolf; -- GitLab From 5e257538c9c1ae6490f34dedec70bb9ed0274b94 Mon Sep 17 00:00:00 2001 From: jcasals Date: Thu, 2 Apr 2020 16:49:36 +0200 Subject: [PATCH 19/86] Adapt to file renames --- include/subscriber_gnss.h | 4 ++-- include/subscriber_gnss_fix.h | 4 ++-- include/subscriber_gnss_tdcp.h | 4 ++-- include/subscriber_gnss_ublox.h | 4 ++-- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/include/subscriber_gnss.h b/include/subscriber_gnss.h index abe5874..5acba76 100644 --- a/include/subscriber_gnss.h +++ b/include/subscriber_gnss.h @@ -1,10 +1,10 @@ /************************** * WOLF includes * **************************/ -#include +#include #include #include -#include +#include #include #include diff --git a/include/subscriber_gnss_fix.h b/include/subscriber_gnss_fix.h index 33c4b70..640b190 100644 --- a/include/subscriber_gnss_fix.h +++ b/include/subscriber_gnss_fix.h @@ -1,10 +1,10 @@ /************************** * WOLF includes * **************************/ -#include +#include #include #include -#include +#include #include #include diff --git a/include/subscriber_gnss_tdcp.h b/include/subscriber_gnss_tdcp.h index be74dbb..91bf5c4 100644 --- a/include/subscriber_gnss_tdcp.h +++ b/include/subscriber_gnss_tdcp.h @@ -1,10 +1,10 @@ /************************** * WOLF includes * **************************/ -#include +#include #include #include -#include +#include #include #include diff --git a/include/subscriber_gnss_ublox.h b/include/subscriber_gnss_ublox.h index f16d2bc..c148ee0 100644 --- a/include/subscriber_gnss_ublox.h +++ b/include/subscriber_gnss_ublox.h @@ -1,10 +1,10 @@ /************************** * WOLF includes * **************************/ -#include +#include #include #include -#include +#include #include #include -- GitLab From ad738d54617f8bbe34b531c97ee88264e1965aa2 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Tue, 7 Apr 2020 16:17:45 +0200 Subject: [PATCH 20/86] adapted after gnss_utils renamings --- include/subscriber_gnss.h | 13 +++++++------ include/subscriber_gnss_tdcp.h | 4 ++-- include/subscriber_gnss_ublox.h | 5 +++-- src/subscriber_gnss.cpp | 10 +++++----- src/subscriber_gnss_tdcp.cpp | 8 ++++---- src/subscriber_gnss_ublox.cpp | 8 ++++---- 6 files changed, 25 insertions(+), 23 deletions(-) diff --git a/include/subscriber_gnss.h b/include/subscriber_gnss.h index 5acba76..f51518f 100644 --- a/include/subscriber_gnss.h +++ b/include/subscriber_gnss.h @@ -14,7 +14,7 @@ #include #include #include -#include +#include /************************** * STD includes * @@ -28,7 +28,8 @@ **************************/ #include "subscriber.h" #include "subscriber_factory.h" -#include "gnss_utils/gnss_utils.h" +#include "gnss_utils/navigation.h" +#include "gnss_utils/observations.h" using namespace wolf; @@ -37,10 +38,10 @@ class SubscriberGnss : public Subscriber protected: ros::Subscriber sub_nav_; - std::shared_ptr last_nav_ptr_; - //GNSSUtils::Navigation last_nav_; - //GNSSUtils::Observations obs_; - //GNSSUtils::ComputePosOutput get_pos_res_; + std::shared_ptr last_nav_ptr_; + //GnssUtils::Navigation last_nav_; + //GnssUtils::Observations obs_; + //GnssUtils::ComputePosOutput get_pos_res_; //prcopt_t prcopt_; //bool new_obs_; diff --git a/include/subscriber_gnss_tdcp.h b/include/subscriber_gnss_tdcp.h index 91bf5c4..d5214c6 100644 --- a/include/subscriber_gnss_tdcp.h +++ b/include/subscriber_gnss_tdcp.h @@ -14,7 +14,7 @@ #include #include #include -#include +#include /************************** * STD includes * @@ -37,7 +37,7 @@ class SubscriberGnssTdcp : public Subscriber protected: ros::Subscriber sub_nav_; - std::shared_ptr last_nav_ptr_; + std::shared_ptr last_nav_ptr_; //prcopt_t prcopt_; //bool new_obs_; diff --git a/include/subscriber_gnss_ublox.h b/include/subscriber_gnss_ublox.h index c148ee0..decf5ce 100644 --- a/include/subscriber_gnss_ublox.h +++ b/include/subscriber_gnss_ublox.h @@ -19,7 +19,8 @@ **************************/ #include "subscriber.h" #include "subscriber_factory.h" -#include "gnss_utils/gnss_utils.h" +#include "gnss_utils/navigation.h" +#include "gnss_utils/observations.h" #include "gnss_utils/ublox_raw.h" using namespace wolf; @@ -38,6 +39,6 @@ class SubscriberGnssUblox : public Subscriber protected: - GNSSUtils::UBloxRaw ublox_raw_; + GnssUtils::UBloxRaw ublox_raw_; }; WOLF_REGISTER_SUBSCRIBER(SubscriberGnssUblox) diff --git a/src/subscriber_gnss.cpp b/src/subscriber_gnss.cpp index f80d76c..f6a81d3 100644 --- a/src/subscriber_gnss.cpp +++ b/src/subscriber_gnss.cpp @@ -35,8 +35,8 @@ void SubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::Const if (last_nav_ptr_==nullptr) return; - GNSSUtils::ObservationsPtr obs_ptr = std::make_shared(); - GNSSUtils::fillObservation(*obs_ptr, msg); + GnssUtils::ObservationsPtr obs_ptr = std::make_shared(); + GnssUtils::fillObservation(*obs_ptr, msg); CaptureGnssPtr new_capture = std::make_shared(TimeStamp(msg->header.stamp.sec, msg->header.stamp.nsec), sensor_ptr_, obs_ptr, @@ -49,14 +49,14 @@ void SubscriberGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPt ROS_INFO("callbackNav!"); std::cout << "Ephemeris size: " << msg->eph.size() << "\n"; - last_nav_ptr_ = std::make_shared(); - GNSSUtils::fillNavigation(*last_nav_ptr_, msg); + last_nav_ptr_ = std::make_shared(); + GnssUtils::fillNavigation(*last_nav_ptr_, msg); last_nav_ptr_->print(); // if (this->new_obs_) // { // std::cout << "Before computed!!! \n"; -// this->get_pos_res_ = GNSSUtils::computePos(this->obs_, *last_nav_ptr_, this->prcopt_); +// this->get_pos_res_ = GnssUtils::computePos(this->obs_, *last_nav_ptr_, this->prcopt_); // std::cout << "Computed!!! \n"; // } } diff --git a/src/subscriber_gnss_tdcp.cpp b/src/subscriber_gnss_tdcp.cpp index 375d3c5..ef09f47 100644 --- a/src/subscriber_gnss_tdcp.cpp +++ b/src/subscriber_gnss_tdcp.cpp @@ -23,8 +23,8 @@ void SubscriberGnssTdcp::callbackObservation(const iri_gnss_msgs::Observation::C // TODO copied from Tdcp_ros -// GNSSUtils::ObservationsPtr obs_ptr = std::make_shared(); -// GNSSUtils::fillObservation(*obs_ptr, msg); +// GnssUtils::ObservationsPtr obs_ptr = std::make_shared(); +// GnssUtils::fillObservation(*obs_ptr, msg); // CaptureGnssPtr new_capture = std::make_shared(TimeStamp(msg->header.stamp.sec, msg->header.stamp.nsec), // sensor_ptr_, // obs_ptr, @@ -37,8 +37,8 @@ void SubscriberGnssTdcp::callbackNavigation(const iri_gnss_msgs::Navigation::Con { ROS_INFO("callbackNav!"); - last_nav_ptr_ = std::make_shared(); - GNSSUtils::fillNavigation(*last_nav_ptr_, msg); + last_nav_ptr_ = std::make_shared(); + GnssUtils::fillNavigation(*last_nav_ptr_, msg); last_nav_ptr_->print(); // TODO copied from Tdcp_ros diff --git a/src/subscriber_gnss_ublox.cpp b/src/subscriber_gnss_ublox.cpp index f24b5ef..3e59af9 100644 --- a/src/subscriber_gnss_ublox.cpp +++ b/src/subscriber_gnss_ublox.cpp @@ -17,17 +17,17 @@ void SubscriberGnssUblox::initSubscriber(ros::NodeHandle& nh, const std::string& void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) { - GNSSUtils::RawDataType res = ublox_raw_.addDataStream(msg.data); + GnssUtils::RawDataType res = ublox_raw_.addDataStream(msg.data); //std::cout << "res = " << (int) res << std::endl; // only create capture if observation is received - if (res == GNSSUtils::OBS) + if (res == GnssUtils::OBS) { //ROS_INFO("Observation received!"); - GNSSUtils::ObservationsPtr obs_ptr = std::make_shared(ublox_raw_.getObservations()); + GnssUtils::ObservationsPtr obs_ptr = std::make_shared(ublox_raw_.getObservations()); //ROS_INFO("Observations copied!"); - GNSSUtils::NavigationPtr nav_ptr = std::make_shared(ublox_raw_.getNavigation()); + GnssUtils::NavigationPtr nav_ptr = std::make_shared(ublox_raw_.getNavigation()); //ROS_INFO("Navigation copied!"); ros::Time now = ros::Time::now(); -- GitLab From 6b8f1ac55c71990617bbc2ac8f388354a15103af Mon Sep 17 00:00:00 2001 From: joanvallve Date: Thu, 9 Apr 2020 23:14:45 +0200 Subject: [PATCH 21/86] adapted to GnssUtils::Snapshot --- src/subscriber_gnss.cpp | 4 ++-- src/subscriber_gnss_ublox.cpp | 9 +++++---- 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/src/subscriber_gnss.cpp b/src/subscriber_gnss.cpp index f6a81d3..e3e7e2c 100644 --- a/src/subscriber_gnss.cpp +++ b/src/subscriber_gnss.cpp @@ -37,10 +37,10 @@ void SubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::Const GnssUtils::ObservationsPtr obs_ptr = std::make_shared(); GnssUtils::fillObservation(*obs_ptr, msg); + GnssUtils::SnapshotPtr snapshot_ptr = std::make_shared(obs_ptr, last_nav_ptr_); CaptureGnssPtr new_capture = std::make_shared(TimeStamp(msg->header.stamp.sec, msg->header.stamp.nsec), sensor_ptr_, - obs_ptr, - last_nav_ptr_); + snapshot_ptr); new_capture->process(); } diff --git a/src/subscriber_gnss_ublox.cpp b/src/subscriber_gnss_ublox.cpp index 3e59af9..313d764 100644 --- a/src/subscriber_gnss_ublox.cpp +++ b/src/subscriber_gnss_ublox.cpp @@ -25,17 +25,18 @@ void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) if (res == GnssUtils::OBS) { //ROS_INFO("Observation received!"); - GnssUtils::ObservationsPtr obs_ptr = std::make_shared(ublox_raw_.getObservations()); + auto snapshot_ptr = std::make_shared(std::make_shared(ublox_raw_.getObservations()), + std::make_shared(ublox_raw_.getNavigation())); + //GnssUtils::ObservationsPtr obs_ptr = std::make_shared(ublox_raw_.getObservations()); //ROS_INFO("Observations copied!"); - GnssUtils::NavigationPtr nav_ptr = std::make_shared(ublox_raw_.getNavigation()); + //GnssUtils::NavigationPtr nav_ptr = std::make_shared(ublox_raw_.getNavigation()); //ROS_INFO("Navigation copied!"); ros::Time now = ros::Time::now(); auto cap_gnss_ptr = std::make_shared(TimeStamp(now.sec, now.nsec), sensor_ptr_, - obs_ptr, - nav_ptr); + snapshot_ptr); //ROS_INFO("Capture GNSS created!"); cap_gnss_ptr->process(); -- GitLab From 155e431d493b72852240bc76314f44f99d486dc0 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Fri, 17 Apr 2020 19:14:50 +0200 Subject: [PATCH 22/86] more versatile topic suffixes --- src/subscriber_gnss.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/subscriber_gnss.cpp b/src/subscriber_gnss.cpp index e3e7e2c..90650fe 100644 --- a/src/subscriber_gnss.cpp +++ b/src/subscriber_gnss.cpp @@ -24,8 +24,8 @@ SubscriberGnss::SubscriberGnss(const SensorBasePtr& sensor_ptr) : void SubscriberGnss::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { - sub_ = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberGnss::callbackObservation, this); - sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberGnss::callbackNavigation, this); + sub_ = nh.subscribe(topic+std::string("obs"), 1, &SubscriberGnss::callbackObservation, this); + sub_nav_ = nh.subscribe(topic+std::string("nav"), 1, &SubscriberGnss::callbackNavigation, this); } @@ -37,7 +37,7 @@ void SubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::Const GnssUtils::ObservationsPtr obs_ptr = std::make_shared(); GnssUtils::fillObservation(*obs_ptr, msg); - GnssUtils::SnapshotPtr snapshot_ptr = std::make_shared(obs_ptr, last_nav_ptr_); + GnssUtils::SnapshotPtr snapshot_ptr = std::make_shared(obs_ptr, last_nav_ptr_); CaptureGnssPtr new_capture = std::make_shared(TimeStamp(msg->header.stamp.sec, msg->header.stamp.nsec), sensor_ptr_, snapshot_ptr); -- GitLab From 4617954e571ff869289e90329637f83249b71bc0 Mon Sep 17 00:00:00 2001 From: jcasals Date: Wed, 22 Apr 2020 11:29:39 +0200 Subject: [PATCH 23/86] Reorganize subscribers .so file (see core#306) --- CMakeLists.txt | 34 ++++++++++------------------------ 1 file changed, 10 insertions(+), 24 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 57ec760..b9c390d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -137,10 +137,11 @@ include_directories( # add_library(${PROJECT_NAME} # src/${PROJECT_NAME}/wolf_ros.cpp # ) -add_library(subscriber_gnss src/subscriber_gnss.cpp) -add_library(subscriber_gnss_fix src/subscriber_gnss_fix.cpp) -add_library(subscriber_gnss_tdcp src/subscriber_gnss_tdcp.cpp) -add_library(subscriber_gnss_ublox src/subscriber_gnss_ublox.cpp) +add_library(subscriber_${PROJECT_NAME} + src/subscriber_gnss.cpp + src/subscriber_gnss_fix.cpp + src/subscriber_gnss_tdcp.cpp + src/subscriber_gnss_ublox.cpp) ## Add cmake target dependencies of the library ## as an example, code may need to be generated before libraries @@ -164,26 +165,11 @@ add_library(subscriber_gnss_ublox src/subscriber_gnss_ublox.cpp) #add_dependencies(${PROJECT_NAME}_visualizer ${PROJECT_NAME}_gencfg) ## Specify libraries to link a library or executable target against -target_link_libraries(subscriber_gnss - ${wolf_LIBRARIES} - ${wolfgnss_LIBRARIES} - ${iri_gnss_msgs_LIBRARIES} - ) -target_link_libraries(subscriber_gnss_fix - ${wolf_LIBRARIES} - ${wolfgnss_LIBRARIES} - ${iri_gnss_msgs_LIBRARIES} - ) -target_link_libraries(subscriber_gnss_tdcp - ${wolf_LIBRARIES} - ${wolfgnss_LIBRARIES} - ${iri_gnss_msgs_LIBRARIES} - ) -target_link_libraries(subscriber_gnss_ublox - ${wolf_LIBRARIES} - ${wolfgnss_LIBRARIES} - ${iri_gnss_msgs_LIBRARIES} - ) +target_link_libraries(subscriber_${PROJECT_NAME} + ${wolf_LIBRARIES} + ${wolfgnss_LIBRARIES} + ${iri_gnss_msgs_LIBRARIES} + ) ############# ## Install ## -- GitLab From 7cc09661c899dc740481a6a0e050f205cb2e0807 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Wed, 22 Apr 2020 17:49:01 +0200 Subject: [PATCH 24/86] moved to ROS_DEBUG --- src/subscriber_gnss.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/subscriber_gnss.cpp b/src/subscriber_gnss.cpp index 90650fe..65b6a2d 100644 --- a/src/subscriber_gnss.cpp +++ b/src/subscriber_gnss.cpp @@ -31,7 +31,7 @@ void SubscriberGnss::initSubscriber(ros::NodeHandle& nh, const std::string& topi void SubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) { - ROS_INFO("callbackObs!"); + ROS_DEBUG("callbackObs!"); if (last_nav_ptr_==nullptr) return; @@ -46,12 +46,12 @@ void SubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::Const void SubscriberGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg) { - ROS_INFO("callbackNav!"); + ROS_DEBUG("callbackNav!"); - std::cout << "Ephemeris size: " << msg->eph.size() << "\n"; + //std::cout << "Ephemeris size: " << msg->eph.size() << "\n"; last_nav_ptr_ = std::make_shared(); GnssUtils::fillNavigation(*last_nav_ptr_, msg); - last_nav_ptr_->print(); + //last_nav_ptr_->print(); // if (this->new_obs_) // { -- GitLab From 4e7684edd12247d1319a55226eaf437f7b9747ec Mon Sep 17 00:00:00 2001 From: joanvallve Date: Tue, 28 Apr 2020 11:55:27 +0200 Subject: [PATCH 25/86] includes --- include/subscriber_gnss.h | 5 ++++- include/subscriber_gnss_fix.h | 5 ++++- include/subscriber_gnss_tdcp.h | 5 ++++- include/subscriber_gnss_ublox.h | 5 ++++- 4 files changed, 16 insertions(+), 4 deletions(-) diff --git a/include/subscriber_gnss.h b/include/subscriber_gnss.h index f51518f..a371987 100644 --- a/include/subscriber_gnss.h +++ b/include/subscriber_gnss.h @@ -27,7 +27,10 @@ * WOLF-ROS includes * **************************/ #include "subscriber.h" -#include "subscriber_factory.h" + +/************************** + * Other includes * + **************************/ #include "gnss_utils/navigation.h" #include "gnss_utils/observations.h" diff --git a/include/subscriber_gnss_fix.h b/include/subscriber_gnss_fix.h index 640b190..6290a11 100644 --- a/include/subscriber_gnss_fix.h +++ b/include/subscriber_gnss_fix.h @@ -25,7 +25,10 @@ * WOLF-ROS includes * **************************/ #include "subscriber.h" -#include "subscriber_factory.h" + +/************************** + * Other includes * + **************************/ #include "gnss_utils/gnss_utils.h" using namespace wolf; diff --git a/include/subscriber_gnss_tdcp.h b/include/subscriber_gnss_tdcp.h index d5214c6..43c3c7b 100644 --- a/include/subscriber_gnss_tdcp.h +++ b/include/subscriber_gnss_tdcp.h @@ -27,7 +27,10 @@ * WOLF-ROS includes * **************************/ #include "subscriber.h" -#include "subscriber_factory.h" + +/************************** + * Other includes * + **************************/ #include "gnss_utils/gnss_utils.h" using namespace wolf; diff --git a/include/subscriber_gnss_ublox.h b/include/subscriber_gnss_ublox.h index decf5ce..f6b1a32 100644 --- a/include/subscriber_gnss_ublox.h +++ b/include/subscriber_gnss_ublox.h @@ -18,7 +18,10 @@ * WOLF-ROS includes * **************************/ #include "subscriber.h" -#include "subscriber_factory.h" + +/************************** + * Other includes * + **************************/ #include "gnss_utils/navigation.h" #include "gnss_utils/observations.h" #include "gnss_utils/ublox_raw.h" -- GitLab From 0150c0d9656b525dfb313e806c3c639bfe01dc7b Mon Sep 17 00:00:00 2001 From: joanvallve Date: Mon, 1 Jun 2020 17:15:29 +0200 Subject: [PATCH 26/86] new subscribers for raw_data --- CMakeLists.txt | 10 ++++--- include/subscriber_gnss_novatel.h | 47 ++++++++++++++++++++++++++++++ include/subscriber_gnss_receiver.h | 41 ++++++++++++++++++++++++++ include/subscriber_gnss_ublox.h | 9 ++---- src/subscriber_gnss_novatel.cpp | 33 +++++++++++++++++++++ src/subscriber_gnss_receiver.cpp | 30 +++++++++++++++++++ src/subscriber_gnss_ublox.cpp | 21 ++----------- 7 files changed, 163 insertions(+), 28 deletions(-) create mode 100644 include/subscriber_gnss_novatel.h create mode 100644 include/subscriber_gnss_receiver.h create mode 100644 src/subscriber_gnss_novatel.cpp create mode 100644 src/subscriber_gnss_receiver.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index b9c390d..161bfba 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -16,12 +16,10 @@ find_package(catkin REQUIRED COMPONENTS tf dynamic_reconfigure wolf_ros_node + novatel_oem7_msgs ) ## System dependencies are found with CMake's conventions -# find_package(Boost REQUIRED COMPONENTS system) -# find_package(Ceres REQUIRED) -# find_package(Eigen3 REQUIRED) find_package(wolf REQUIRED) find_package(wolfgnss REQUIRED) @@ -141,7 +139,9 @@ add_library(subscriber_${PROJECT_NAME} src/subscriber_gnss.cpp src/subscriber_gnss_fix.cpp src/subscriber_gnss_tdcp.cpp - src/subscriber_gnss_ublox.cpp) + src/subscriber_gnss_receiver.cpp + src/subscriber_gnss_ublox.cpp + src/subscriber_gnss_novatel.cpp) ## Add cmake target dependencies of the library ## as an example, code may need to be generated before libraries @@ -163,6 +163,8 @@ add_library(subscriber_${PROJECT_NAME} ## same as for the library above #add_dependencies(${PROJECT_NAME}_node ${PROJECT_NAME}_gencfg) #add_dependencies(${PROJECT_NAME}_visualizer ${PROJECT_NAME}_gencfg) +add_dependencies(subscriber_${PROJECT_NAME} iri_gnss_msgs_generate_messages_cpp) +add_dependencies(subscriber_${PROJECT_NAME} novatel_oem7_msgs_generate_messages_cpp) ## Specify libraries to link a library or executable target against target_link_libraries(subscriber_${PROJECT_NAME} diff --git a/include/subscriber_gnss_novatel.h b/include/subscriber_gnss_novatel.h new file mode 100644 index 0000000..91a3b47 --- /dev/null +++ b/include/subscriber_gnss_novatel.h @@ -0,0 +1,47 @@ +/************************** + * WOLF includes * + **************************/ +#include +#include +#include +#include +#include +#include + +/************************** + * ROS includes * + **************************/ +#include +#include "novatel_oem7_msgs/Oem7RawMsg.h" + +/************************** + * WOLF-ROS includes * + **************************/ +#include "subscriber_gnss_receiver.h" + +/************************** + * Other includes * + **************************/ +#include "gnss_utils/navigation.h" +#include "gnss_utils/observations.h" +#include "gnss_utils/receivers/novatel_raw.h" + +using namespace wolf; + +class SubscriberGnssNovatel : public SubscriberGnssReceiver +{ + public: + // Constructor + SubscriberGnssNovatel(const SensorBasePtr& sensor_ptr); + + virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); + + void callback(const novatel_oem7_msgs::Oem7RawMsg& msg); + + static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); + + protected: + + GnssUtils::ReceiverRawAbstractPtr receiver_; +}; +WOLF_REGISTER_SUBSCRIBER(SubscriberGnssNovatel) diff --git a/include/subscriber_gnss_receiver.h b/include/subscriber_gnss_receiver.h new file mode 100644 index 0000000..15ec564 --- /dev/null +++ b/include/subscriber_gnss_receiver.h @@ -0,0 +1,41 @@ +/************************** + * WOLF includes * + **************************/ +#include +#include +#include +#include +#include +#include + +/************************** + * ROS includes * + **************************/ +#include + +/************************** + * WOLF-ROS includes * + **************************/ +#include "subscriber.h" + +/************************** + * Other includes * + **************************/ +#include "gnss_utils/navigation.h" +#include "gnss_utils/observations.h" +#include "gnss_utils/receiver_raw_base.h" + +using namespace wolf; + +class SubscriberGnssReceiver : public Subscriber +{ + public: + // Constructor + SubscriberGnssReceiver(const SensorBasePtr& sensor_ptr, GnssUtils::ReceiverRawAbstractPtr _receiver); + + protected: + + void createCaptureAndProcess(); + + GnssUtils::ReceiverRawAbstractPtr receiver_; +}; diff --git a/include/subscriber_gnss_ublox.h b/include/subscriber_gnss_ublox.h index f6b1a32..2c99b09 100644 --- a/include/subscriber_gnss_ublox.h +++ b/include/subscriber_gnss_ublox.h @@ -17,18 +17,18 @@ /************************** * WOLF-ROS includes * **************************/ -#include "subscriber.h" +#include "subscriber_gnss_receiver.h" /************************** * Other includes * **************************/ #include "gnss_utils/navigation.h" #include "gnss_utils/observations.h" -#include "gnss_utils/ublox_raw.h" +#include "gnss_utils/receivers/ublox_raw.h" using namespace wolf; -class SubscriberGnssUblox : public Subscriber +class SubscriberGnssUblox : public SubscriberGnssReceiver { public: // Constructor @@ -40,8 +40,5 @@ class SubscriberGnssUblox : public Subscriber static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); - protected: - - GnssUtils::UBloxRaw ublox_raw_; }; WOLF_REGISTER_SUBSCRIBER(SubscriberGnssUblox) diff --git a/src/subscriber_gnss_novatel.cpp b/src/subscriber_gnss_novatel.cpp new file mode 100644 index 0000000..57d8732 --- /dev/null +++ b/src/subscriber_gnss_novatel.cpp @@ -0,0 +1,33 @@ +#include "../include/subscriber_gnss_novatel.h" + +using namespace wolf; + +// Constructor +SubscriberGnssNovatel::SubscriberGnssNovatel(const SensorBasePtr& sensor_ptr) : + SubscriberGnssReceiver(sensor_ptr, std::make_shared()) +{ +} + +void SubscriberGnssNovatel::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +{ + sub_ = nh.subscribe(topic, 100, &SubscriberGnssNovatel::callback, this); +} + +void SubscriberGnssNovatel::callback(const novatel_oem7_msgs::Oem7RawMsg& msg) +{ + GnssUtils::RawDataType res = receiver_->addDataStream(msg.message_data); + + //std::cout << "res = " << (int) res << std::endl; + + // only create capture if observation is received + if (res == GnssUtils::OBS) + { + //ROS_INFO("Observation received!"); + createCaptureAndProcess(); + } +} + +std::shared_ptr SubscriberGnssNovatel::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +{ + return std::make_shared(_sensor_ptr); +} diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp new file mode 100644 index 0000000..8cb7d50 --- /dev/null +++ b/src/subscriber_gnss_receiver.cpp @@ -0,0 +1,30 @@ +#include "../include/subscriber_gnss_receiver.h" + +using namespace wolf; + +// Constructor +SubscriberGnssReceiver::SubscriberGnssReceiver(const SensorBasePtr& sensor_ptr, GnssUtils::ReceiverRawAbstractPtr _receiver) : + Subscriber(sensor_ptr), + receiver_(_receiver) +{ +} + +void SubscriberGnssReceiver::createCaptureAndProcess() +{ + auto snapshot_ptr = std::make_shared(std::make_shared(receiver_->getObservations()), + std::make_shared(receiver_->getNavigation())); + //GnssUtils::ObservationsPtr obs_ptr = std::make_shared(receiver_->getObservations()); + //ROS_INFO("Observations copied!"); + //GnssUtils::NavigationPtr nav_ptr = std::make_shared(receiver_->getNavigation()); + //ROS_INFO("Navigation copied!"); + + ros::Time now = ros::Time::now(); + + auto cap_gnss_ptr = std::make_shared(TimeStamp(now.sec, now.nsec), + sensor_ptr_, + snapshot_ptr); + + //ROS_INFO("Capture GNSS created!"); + cap_gnss_ptr->process(); + //ROS_INFO("Capture GNSS processed!"); +} diff --git a/src/subscriber_gnss_ublox.cpp b/src/subscriber_gnss_ublox.cpp index 313d764..213d5df 100644 --- a/src/subscriber_gnss_ublox.cpp +++ b/src/subscriber_gnss_ublox.cpp @@ -4,7 +4,7 @@ using namespace wolf; // Constructor SubscriberGnssUblox::SubscriberGnssUblox(const SensorBasePtr& sensor_ptr) : - Subscriber(sensor_ptr) + SubscriberGnssReceiver(sensor_ptr, std::make_shared()) { } @@ -17,7 +17,7 @@ void SubscriberGnssUblox::initSubscriber(ros::NodeHandle& nh, const std::string& void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) { - GnssUtils::RawDataType res = ublox_raw_.addDataStream(msg.data); + GnssUtils::RawDataType res = receiver_->addDataStream(msg.data); //std::cout << "res = " << (int) res << std::endl; @@ -25,22 +25,7 @@ void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) if (res == GnssUtils::OBS) { //ROS_INFO("Observation received!"); - auto snapshot_ptr = std::make_shared(std::make_shared(ublox_raw_.getObservations()), - std::make_shared(ublox_raw_.getNavigation())); - //GnssUtils::ObservationsPtr obs_ptr = std::make_shared(ublox_raw_.getObservations()); - //ROS_INFO("Observations copied!"); - //GnssUtils::NavigationPtr nav_ptr = std::make_shared(ublox_raw_.getNavigation()); - //ROS_INFO("Navigation copied!"); - - ros::Time now = ros::Time::now(); - - auto cap_gnss_ptr = std::make_shared(TimeStamp(now.sec, now.nsec), - sensor_ptr_, - snapshot_ptr); - - //ROS_INFO("Capture GNSS created!"); - cap_gnss_ptr->process(); - //ROS_INFO("Capture GNSS processed!"); + createCaptureAndProcess(); } } std::shared_ptr SubscriberGnssUblox::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) -- GitLab From 254159cec6a78f86d49d4cfa5f4910326d2f4be1 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Thu, 4 Jun 2020 16:10:43 +0200 Subject: [PATCH 27/86] bug fixed --- include/subscriber_gnss_novatel.h | 3 --- src/subscriber_gnss_receiver.cpp | 6 +----- 2 files changed, 1 insertion(+), 8 deletions(-) diff --git a/include/subscriber_gnss_novatel.h b/include/subscriber_gnss_novatel.h index 91a3b47..3f16e29 100644 --- a/include/subscriber_gnss_novatel.h +++ b/include/subscriber_gnss_novatel.h @@ -40,8 +40,5 @@ class SubscriberGnssNovatel : public SubscriberGnssReceiver static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); - protected: - - GnssUtils::ReceiverRawAbstractPtr receiver_; }; WOLF_REGISTER_SUBSCRIBER(SubscriberGnssNovatel) diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index 8cb7d50..5393afa 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -13,13 +13,9 @@ void SubscriberGnssReceiver::createCaptureAndProcess() { auto snapshot_ptr = std::make_shared(std::make_shared(receiver_->getObservations()), std::make_shared(receiver_->getNavigation())); - //GnssUtils::ObservationsPtr obs_ptr = std::make_shared(receiver_->getObservations()); - //ROS_INFO("Observations copied!"); - //GnssUtils::NavigationPtr nav_ptr = std::make_shared(receiver_->getNavigation()); - //ROS_INFO("Navigation copied!"); + //ROS_INFO("Snapshot with copied observations an dnavigation created!"); ros::Time now = ros::Time::now(); - auto cap_gnss_ptr = std::make_shared(TimeStamp(now.sec, now.nsec), sensor_ptr_, snapshot_ptr); -- GitLab From a5ecc9e46e129006a4515e9c177e71657339b02c Mon Sep 17 00:00:00 2001 From: joanvallve Date: Thu, 11 Jun 2020 00:07:52 +0200 Subject: [PATCH 28/86] handling available satellites --- include/subscriber_gnss_novatel.h | 8 +++-- include/subscriber_gnss_receiver.h | 10 +++++- include/subscriber_gnss_ublox.h | 8 +++-- src/subscriber_gnss_novatel.cpp | 19 ++++++++--- src/subscriber_gnss_receiver.cpp | 52 +++++++++++++++++++++++------- src/subscriber_gnss_ublox.cpp | 22 +++++++++---- 6 files changed, 92 insertions(+), 27 deletions(-) diff --git a/include/subscriber_gnss_novatel.h b/include/subscriber_gnss_novatel.h index 3f16e29..ce4bef7 100644 --- a/include/subscriber_gnss_novatel.h +++ b/include/subscriber_gnss_novatel.h @@ -13,6 +13,7 @@ **************************/ #include #include "novatel_oem7_msgs/Oem7RawMsg.h" +#include /************************** * WOLF-ROS includes * @@ -32,13 +33,16 @@ class SubscriberGnssNovatel : public SubscriberGnssReceiver { public: // Constructor - SubscriberGnssNovatel(const SensorBasePtr& sensor_ptr); + SubscriberGnssNovatel(const SensorBasePtr& sensor_ptr, + bool _process_not_available); virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); void callback(const novatel_oem7_msgs::Oem7RawMsg& msg); - static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); + static std::shared_ptr create(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr); }; WOLF_REGISTER_SUBSCRIBER(SubscriberGnssNovatel) diff --git a/include/subscriber_gnss_receiver.h b/include/subscriber_gnss_receiver.h index 15ec564..8a51ad6 100644 --- a/include/subscriber_gnss_receiver.h +++ b/include/subscriber_gnss_receiver.h @@ -12,6 +12,7 @@ * ROS includes * **************************/ #include +#include /************************** * WOLF-ROS includes * @@ -21,6 +22,7 @@ /************************** * Other includes * **************************/ +#include "gnss_utils/gnss_utils.h" #include "gnss_utils/navigation.h" #include "gnss_utils/observations.h" #include "gnss_utils/receiver_raw_base.h" @@ -31,11 +33,17 @@ class SubscriberGnssReceiver : public Subscriber { public: // Constructor - SubscriberGnssReceiver(const SensorBasePtr& sensor_ptr, GnssUtils::ReceiverRawAbstractPtr _receiver); + SubscriberGnssReceiver(const SensorBasePtr& sensor_ptr, + GnssUtils::ReceiverRawAbstractPtr _receiver, + bool _process_not_available); protected: void createCaptureAndProcess(); GnssUtils::ReceiverRawAbstractPtr receiver_; + bool sats_available_; + bool process_not_available_; + + ros::Publisher available_pub_; }; diff --git a/include/subscriber_gnss_ublox.h b/include/subscriber_gnss_ublox.h index 2c99b09..78c4781 100644 --- a/include/subscriber_gnss_ublox.h +++ b/include/subscriber_gnss_ublox.h @@ -13,6 +13,7 @@ **************************/ #include #include +#include /************************** * WOLF-ROS includes * @@ -32,13 +33,16 @@ class SubscriberGnssUblox : public SubscriberGnssReceiver { public: // Constructor - SubscriberGnssUblox(const SensorBasePtr& sensor_ptr); + SubscriberGnssUblox(const SensorBasePtr& sensor_ptr, + bool _process_not_available); virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); void callback(const std_msgs::UInt8MultiArray& msg); - static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); + static std::shared_ptr create(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr); }; WOLF_REGISTER_SUBSCRIBER(SubscriberGnssUblox) diff --git a/src/subscriber_gnss_novatel.cpp b/src/subscriber_gnss_novatel.cpp index 57d8732..5ec8314 100644 --- a/src/subscriber_gnss_novatel.cpp +++ b/src/subscriber_gnss_novatel.cpp @@ -3,14 +3,20 @@ using namespace wolf; // Constructor -SubscriberGnssNovatel::SubscriberGnssNovatel(const SensorBasePtr& sensor_ptr) : - SubscriberGnssReceiver(sensor_ptr, std::make_shared()) +SubscriberGnssNovatel::SubscriberGnssNovatel(const SensorBasePtr& sensor_ptr, + bool _process_not_available) : + SubscriberGnssReceiver(sensor_ptr, + std::make_shared(), + _process_not_available) { } void SubscriberGnssNovatel::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { sub_ = nh.subscribe(topic, 100, &SubscriberGnssNovatel::callback, this); + + // publisher of flag "satellites available" + available_pub_ = nh.advertise("gnss_available", 1); } void SubscriberGnssNovatel::callback(const novatel_oem7_msgs::Oem7RawMsg& msg) @@ -27,7 +33,12 @@ void SubscriberGnssNovatel::callback(const novatel_oem7_msgs::Oem7RawMsg& msg) } } -std::shared_ptr SubscriberGnssNovatel::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) +std::shared_ptr SubscriberGnssNovatel::create(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr) { - return std::make_shared(_sensor_ptr); + return std::make_shared(_sensor_ptr, + _server.getParam("ROS subscriber/" + + _unique_name + + "/process_not_available")); } diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index 5393afa..76528fe 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -3,24 +3,52 @@ using namespace wolf; // Constructor -SubscriberGnssReceiver::SubscriberGnssReceiver(const SensorBasePtr& sensor_ptr, GnssUtils::ReceiverRawAbstractPtr _receiver) : +SubscriberGnssReceiver::SubscriberGnssReceiver(const SensorBasePtr& sensor_ptr, + GnssUtils::ReceiverRawAbstractPtr _receiver, + bool _process_not_available) : Subscriber(sensor_ptr), - receiver_(_receiver) + receiver_(_receiver), + sats_available_(false), + process_not_available_(_process_not_available) { + ROS_INFO("Waiting for satellites..."); } void SubscriberGnssReceiver::createCaptureAndProcess() { - auto snapshot_ptr = std::make_shared(std::make_shared(receiver_->getObservations()), - std::make_shared(receiver_->getNavigation())); - //ROS_INFO("Snapshot with copied observations an dnavigation created!"); + // check if satellites are available already (only check once: cold start) + if (!sats_available_) + { + sats_available_ = GnssUtils::computePos(receiver_->getObservations(), + receiver_->getNavigation(), + GnssUtils::default_options).success; - ros::Time now = ros::Time::now(); - auto cap_gnss_ptr = std::make_shared(TimeStamp(now.sec, now.nsec), - sensor_ptr_, - snapshot_ptr); + // discarding first data (to give time to IMU) + if (sats_available_) + ROS_INFO("Enough satellites to start!"); + } + else + { + // publisher of flag "satellites available" + std_msgs::Bool msg; + msg.data = sats_available_; + available_pub_.publish(msg); - //ROS_INFO("Capture GNSS created!"); - cap_gnss_ptr->process(); - //ROS_INFO("Capture GNSS processed!"); + auto snapshot_ptr = std::make_shared(std::make_shared(receiver_->getObservations()), + std::make_shared(receiver_->getNavigation())); + //ROS_INFO("Snapshot with copied observations and navigation created!"); + + ros::Time now = ros::Time::now(); + auto cap_gnss_ptr = std::make_shared(TimeStamp(now.sec, now.nsec), + sensor_ptr_, + snapshot_ptr); + + //ROS_INFO("Capture GNSS created!"); + cap_gnss_ptr->process(); + //ROS_INFO("Capture GNSS processed!"); + } + // publish available + std_msgs::Bool msg; + msg.data = sats_available_; + available_pub_.publish(msg); } diff --git a/src/subscriber_gnss_ublox.cpp b/src/subscriber_gnss_ublox.cpp index 213d5df..211f86d 100644 --- a/src/subscriber_gnss_ublox.cpp +++ b/src/subscriber_gnss_ublox.cpp @@ -3,19 +3,23 @@ using namespace wolf; // Constructor -SubscriberGnssUblox::SubscriberGnssUblox(const SensorBasePtr& sensor_ptr) : - SubscriberGnssReceiver(sensor_ptr, std::make_shared()) +SubscriberGnssUblox::SubscriberGnssUblox(const SensorBasePtr& sensor_ptr, + bool _process_not_available) : + SubscriberGnssReceiver(sensor_ptr, + std::make_shared(), + _process_not_available) { } - void SubscriberGnssUblox::initSubscriber(ros::NodeHandle& nh, const std::string& topic) { sub_ = nh.subscribe(topic, 100, &SubscriberGnssUblox::callback, this); + + // publisher of flag "satellites available" + available_pub_ = nh.advertise("gnss_available", 1); } void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) - { GnssUtils::RawDataType res = receiver_->addDataStream(msg.data); @@ -28,7 +32,13 @@ void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) createCaptureAndProcess(); } } -std::shared_ptr SubscriberGnssUblox::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) + +std::shared_ptr SubscriberGnssUblox::create(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr) { - return std::make_shared(_sensor_ptr); + return std::make_shared(_sensor_ptr, + _server.getParam("ROS subscriber/" + + _unique_name + + "/process_not_available")); } -- GitLab From a75c028f1f4044963d62b2573939c730b458b7c4 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Thu, 11 Jun 2020 12:49:59 +0200 Subject: [PATCH 29/86] new subscribers constructors with param server --- include/subscriber_gnss.h | 23 ++++++++++++----------- include/subscriber_gnss_fix.h | 15 +++++++++++---- include/subscriber_gnss_novatel.h | 20 ++++++++++++-------- include/subscriber_gnss_receiver.h | 16 ++++++++++++---- include/subscriber_gnss_tdcp.h | 16 ++++++++++++---- include/subscriber_gnss_ublox.h | 20 ++++++++++++-------- src/subscriber_gnss.cpp | 25 ++++++------------------- src/subscriber_gnss_fix.cpp | 13 +++++++------ src/subscriber_gnss_novatel.cpp | 23 +++++++++-------------- src/subscriber_gnss_receiver.cpp | 19 +++++++++++-------- src/subscriber_gnss_tdcp.cpp | 12 ++++++------ src/subscriber_gnss_ublox.cpp | 23 +++++++++-------------- 12 files changed, 119 insertions(+), 106 deletions(-) diff --git a/include/subscriber_gnss.h b/include/subscriber_gnss.h index a371987..0ae14a4 100644 --- a/include/subscriber_gnss.h +++ b/include/subscriber_gnss.h @@ -1,3 +1,5 @@ +#ifndef SUBSCRIBER_GNSS_H +#define SUBSCRIBER_GNSS_H /************************** * WOLF includes * **************************/ @@ -34,7 +36,8 @@ #include "gnss_utils/navigation.h" #include "gnss_utils/observations.h" -using namespace wolf; +namespace wolf +{ class SubscriberGnss : public Subscriber { @@ -42,23 +45,21 @@ class SubscriberGnss : public Subscriber ros::Subscriber sub_nav_; std::shared_ptr last_nav_ptr_; - //GnssUtils::Navigation last_nav_; - //GnssUtils::Observations obs_; - //GnssUtils::ComputePosOutput get_pos_res_; - - //prcopt_t prcopt_; - //bool new_obs_; public: // Constructor - SubscriberGnss(const SensorBasePtr& sensor_ptr); + SubscriberGnss(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr); + WOLF_SUBSCRIBER_CREATE(SubscriberGnss); virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); void callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg); void callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg); - - static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); }; -WOLF_REGISTER_SUBSCRIBER(SubscriberGnss) +WOLF_REGISTER_SUBSCRIBER(SubscriberGnss); + +} +#endif diff --git a/include/subscriber_gnss_fix.h b/include/subscriber_gnss_fix.h index 6290a11..ebc650e 100644 --- a/include/subscriber_gnss_fix.h +++ b/include/subscriber_gnss_fix.h @@ -1,3 +1,5 @@ +#ifndef SUBSCRIBER_GNSS_FIX_H +#define SUBSCRIBER_GNSS_FIX_H /************************** * WOLF includes * **************************/ @@ -31,18 +33,23 @@ **************************/ #include "gnss_utils/gnss_utils.h" -using namespace wolf; +namespace wolf +{ class SubscriberGnssFix : public Subscriber { public: // Constructor - SubscriberGnssFix(const SensorBasePtr& sensor_ptr); + SubscriberGnssFix(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr); + WOLF_SUBSCRIBER_CREATE(SubscriberGnssFix); virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); void callback(const sensor_msgs::NavSatFix::ConstPtr& msg); - - static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); }; WOLF_REGISTER_SUBSCRIBER(SubscriberGnssFix) + +} +#endif diff --git a/include/subscriber_gnss_novatel.h b/include/subscriber_gnss_novatel.h index ce4bef7..4929e94 100644 --- a/include/subscriber_gnss_novatel.h +++ b/include/subscriber_gnss_novatel.h @@ -1,3 +1,5 @@ +#ifndef SUBSCRIBER_GNSS_NOVATEL_H +#define SUBSCRIBER_GNSS_NOVATEL_H /************************** * WOLF includes * **************************/ @@ -27,22 +29,24 @@ #include "gnss_utils/observations.h" #include "gnss_utils/receivers/novatel_raw.h" -using namespace wolf; +namespace wolf +{ class SubscriberGnssNovatel : public SubscriberGnssReceiver { public: // Constructor - SubscriberGnssNovatel(const SensorBasePtr& sensor_ptr, - bool _process_not_available); + SubscriberGnssNovatel(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr); + WOLF_SUBSCRIBER_CREATE(SubscriberGnssNovatel); virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); void callback(const novatel_oem7_msgs::Oem7RawMsg& msg); - static std::shared_ptr create(const std::string& _unique_name, - const ParamsServer& _server, - const SensorBasePtr _sensor_ptr); - }; -WOLF_REGISTER_SUBSCRIBER(SubscriberGnssNovatel) +WOLF_REGISTER_SUBSCRIBER(SubscriberGnssNovatel); + +} +#endif diff --git a/include/subscriber_gnss_receiver.h b/include/subscriber_gnss_receiver.h index 8a51ad6..3633816 100644 --- a/include/subscriber_gnss_receiver.h +++ b/include/subscriber_gnss_receiver.h @@ -1,3 +1,5 @@ +#ifndef SUBSCRIBER_GNSS_RECEIVER_H +#define SUBSCRIBER_GNSS_RECEIVER_H /************************** * WOLF includes * **************************/ @@ -27,15 +29,18 @@ #include "gnss_utils/observations.h" #include "gnss_utils/receiver_raw_base.h" -using namespace wolf; +namespace wolf +{ class SubscriberGnssReceiver : public Subscriber { public: // Constructor - SubscriberGnssReceiver(const SensorBasePtr& sensor_ptr, - GnssUtils::ReceiverRawAbstractPtr _receiver, - bool _process_not_available); + SubscriberGnssReceiver(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr, + GnssUtils::ReceiverRawAbstractPtr _receiver); + protected: @@ -47,3 +52,6 @@ class SubscriberGnssReceiver : public Subscriber ros::Publisher available_pub_; }; + +} +#endif diff --git a/include/subscriber_gnss_tdcp.h b/include/subscriber_gnss_tdcp.h index 43c3c7b..af8f7c7 100644 --- a/include/subscriber_gnss_tdcp.h +++ b/include/subscriber_gnss_tdcp.h @@ -1,3 +1,5 @@ +#ifndef SUBSCRIBER_GNSS_TDCP_H +#define SUBSCRIBER_GNSS_TDCP_H /************************** * WOLF includes * **************************/ @@ -33,7 +35,8 @@ **************************/ #include "gnss_utils/gnss_utils.h" -using namespace wolf; +namespace wolf +{ class SubscriberGnssTdcp : public Subscriber { @@ -47,7 +50,10 @@ class SubscriberGnssTdcp : public Subscriber public: // Constructor - SubscriberGnssTdcp(const SensorBasePtr& sensor_ptr); + SubscriberGnssTdcp(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr); + WOLF_SUBSCRIBER_CREATE(SubscriberGnssTdcp); virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); @@ -55,6 +61,8 @@ class SubscriberGnssTdcp : public Subscriber void callbackNavigation(const iri_gnss_msgs::Navigation::ConstPtr& msg); - static std::shared_ptr create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr); }; -WOLF_REGISTER_SUBSCRIBER(SubscriberGnssTdcp) +WOLF_REGISTER_SUBSCRIBER(SubscriberGnssTdcp); + +} +#endif diff --git a/include/subscriber_gnss_ublox.h b/include/subscriber_gnss_ublox.h index 78c4781..5f074a9 100644 --- a/include/subscriber_gnss_ublox.h +++ b/include/subscriber_gnss_ublox.h @@ -1,3 +1,5 @@ +#ifndef SUBSCRIBER_GNSS_UBLOX_H +#define SUBSCRIBER_GNSS_UBLOX_H /************************** * WOLF includes * **************************/ @@ -27,22 +29,24 @@ #include "gnss_utils/observations.h" #include "gnss_utils/receivers/ublox_raw.h" -using namespace wolf; +namespace wolf +{ class SubscriberGnssUblox : public SubscriberGnssReceiver { public: // Constructor - SubscriberGnssUblox(const SensorBasePtr& sensor_ptr, - bool _process_not_available); + SubscriberGnssUblox(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr); + WOLF_SUBSCRIBER_CREATE(SubscriberGnssUblox); virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); void callback(const std_msgs::UInt8MultiArray& msg); - static std::shared_ptr create(const std::string& _unique_name, - const ParamsServer& _server, - const SensorBasePtr _sensor_ptr); - }; -WOLF_REGISTER_SUBSCRIBER(SubscriberGnssUblox) + +WOLF_REGISTER_SUBSCRIBER(SubscriberGnssUblox); +} +#endif diff --git a/src/subscriber_gnss.cpp b/src/subscriber_gnss.cpp index 65b6a2d..9daf225 100644 --- a/src/subscriber_gnss.cpp +++ b/src/subscriber_gnss.cpp @@ -1,24 +1,14 @@ #include "../include/subscriber_gnss.h" -using namespace wolf; +namespace wolf +{ // Constructor -SubscriberGnss::SubscriberGnss(const SensorBasePtr& sensor_ptr) : - Subscriber(sensor_ptr) +SubscriberGnss::SubscriberGnss(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr) : + Subscriber(_unique_name, _server, _sensor_ptr) { - //prcopt_ = prcopt_default; - //prcopt_.mode = PMODE_SINGLE; - //prcopt_.soltype = 0; - //prcopt_.nf = 1; - //prcopt_.navsys = SYS_GPS; - //prcopt_.sateph = EPHOPT_BRDC; - //prcopt_.ionoopt = IONOOPT_OFF; - //prcopt_.tropopt = TROPOPT_OFF; - //prcopt_.dynamics = 0; - //prcopt_.tidecorr = 0; - //prcopt_.sbascorr = SBSOPT_FCORR; - - //this->new_obs_=false; } @@ -61,7 +51,4 @@ void SubscriberGnss::callbackNavigation(const iri_gnss_msgs::Navigation::ConstPt // } } -std::shared_ptr SubscriberGnss::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) -{ - return std::make_shared(_sensor_ptr); } diff --git a/src/subscriber_gnss_fix.cpp b/src/subscriber_gnss_fix.cpp index 4434a70..a7f2097 100644 --- a/src/subscriber_gnss_fix.cpp +++ b/src/subscriber_gnss_fix.cpp @@ -1,10 +1,13 @@ #include "../include/subscriber_gnss_fix.h" -using namespace wolf; +namespace wolf +{ // Constructor -SubscriberGnssFix::SubscriberGnssFix(const SensorBasePtr& sensor_ptr) : - Subscriber(sensor_ptr) +SubscriberGnssFix::SubscriberGnssFix(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr) + : Subscriber(_unique_name, _server, _sensor_ptr) { } @@ -27,7 +30,5 @@ void SubscriberGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg) false); // false = {LatLonAlt fix and ENU cov} cap_gnss_ptr->process(); } -std::shared_ptr SubscriberGnssFix::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) -{ - return std::make_shared(_sensor_ptr); + } diff --git a/src/subscriber_gnss_novatel.cpp b/src/subscriber_gnss_novatel.cpp index 5ec8314..cb3d0cd 100644 --- a/src/subscriber_gnss_novatel.cpp +++ b/src/subscriber_gnss_novatel.cpp @@ -1,13 +1,16 @@ #include "../include/subscriber_gnss_novatel.h" -using namespace wolf; +namespace wolf +{ // Constructor -SubscriberGnssNovatel::SubscriberGnssNovatel(const SensorBasePtr& sensor_ptr, - bool _process_not_available) : - SubscriberGnssReceiver(sensor_ptr, - std::make_shared(), - _process_not_available) +SubscriberGnssNovatel::SubscriberGnssNovatel(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr) : + SubscriberGnssReceiver(_unique_name, + _server, + _sensor_ptr, + std::make_shared()) { } @@ -33,12 +36,4 @@ void SubscriberGnssNovatel::callback(const novatel_oem7_msgs::Oem7RawMsg& msg) } } -std::shared_ptr SubscriberGnssNovatel::create(const std::string& _unique_name, - const ParamsServer& _server, - const SensorBasePtr _sensor_ptr) -{ - return std::make_shared(_sensor_ptr, - _server.getParam("ROS subscriber/" + - _unique_name + - "/process_not_available")); } diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index 76528fe..574e466 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -1,16 +1,17 @@ #include "../include/subscriber_gnss_receiver.h" -using namespace wolf; +namespace wolf +{ -// Constructor -SubscriberGnssReceiver::SubscriberGnssReceiver(const SensorBasePtr& sensor_ptr, - GnssUtils::ReceiverRawAbstractPtr _receiver, - bool _process_not_available) : - Subscriber(sensor_ptr), +SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr, + GnssUtils::ReceiverRawAbstractPtr _receiver) : + Subscriber(_unique_name, _server, _sensor_ptr), receiver_(_receiver), - sats_available_(false), - process_not_available_(_process_not_available) + sats_available_(false) { + process_not_available_ = _server.getParam(prefix_ + "/process_not_available"); ROS_INFO("Waiting for satellites..."); } @@ -52,3 +53,5 @@ void SubscriberGnssReceiver::createCaptureAndProcess() msg.data = sats_available_; available_pub_.publish(msg); } + +} diff --git a/src/subscriber_gnss_tdcp.cpp b/src/subscriber_gnss_tdcp.cpp index ef09f47..c6a94ba 100644 --- a/src/subscriber_gnss_tdcp.cpp +++ b/src/subscriber_gnss_tdcp.cpp @@ -1,10 +1,13 @@ #include "../include/subscriber_gnss_tdcp.h" -using namespace wolf; +namespace wolf +{ // Constructor -SubscriberGnssTdcp::SubscriberGnssTdcp(const SensorBasePtr& sensor_ptr) : - Subscriber(sensor_ptr) +SubscriberGnssTdcp::SubscriberGnssTdcp(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr) : + Subscriber(_unique_name, _server, _sensor_ptr) { // TODO copied from Tdcp_ros } @@ -44,7 +47,4 @@ void SubscriberGnssTdcp::callbackNavigation(const iri_gnss_msgs::Navigation::Con // TODO copied from Tdcp_ros } -std::shared_ptr SubscriberGnssTdcp::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) -{ - return std::make_shared(_sensor_ptr); } diff --git a/src/subscriber_gnss_ublox.cpp b/src/subscriber_gnss_ublox.cpp index 211f86d..b333161 100644 --- a/src/subscriber_gnss_ublox.cpp +++ b/src/subscriber_gnss_ublox.cpp @@ -1,13 +1,16 @@ #include "../include/subscriber_gnss_ublox.h" -using namespace wolf; +namespace wolf +{ // Constructor -SubscriberGnssUblox::SubscriberGnssUblox(const SensorBasePtr& sensor_ptr, - bool _process_not_available) : - SubscriberGnssReceiver(sensor_ptr, - std::make_shared(), - _process_not_available) +SubscriberGnssUblox::SubscriberGnssUblox(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr) : + SubscriberGnssReceiver(_unique_name, + _server, + _sensor_ptr, + std::make_shared()) { } @@ -33,12 +36,4 @@ void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) } } -std::shared_ptr SubscriberGnssUblox::create(const std::string& _unique_name, - const ParamsServer& _server, - const SensorBasePtr _sensor_ptr) -{ - return std::make_shared(_sensor_ptr, - _server.getParam("ROS subscriber/" + - _unique_name + - "/process_not_available")); } -- GitLab From edc35c30c1c5b15d1ff787c8334e62a59554ca89 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Fri, 12 Jun 2020 16:23:00 +0200 Subject: [PATCH 30/86] subscriber/publisher new API --- include/subscriber_gnss.h | 2 +- include/subscriber_gnss_fix.h | 2 +- include/subscriber_gnss_novatel.h | 2 +- include/subscriber_gnss_tdcp.h | 2 +- include/subscriber_gnss_ublox.h | 2 +- src/subscriber_gnss.cpp | 2 +- src/subscriber_gnss_fix.cpp | 2 +- src/subscriber_gnss_novatel.cpp | 2 +- src/subscriber_gnss_tdcp.cpp | 2 +- src/subscriber_gnss_ublox.cpp | 2 +- 10 files changed, 10 insertions(+), 10 deletions(-) diff --git a/include/subscriber_gnss.h b/include/subscriber_gnss.h index 0ae14a4..2df0762 100644 --- a/include/subscriber_gnss.h +++ b/include/subscriber_gnss.h @@ -53,7 +53,7 @@ class SubscriberGnss : public Subscriber const SensorBasePtr _sensor_ptr); WOLF_SUBSCRIBER_CREATE(SubscriberGnss); - virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); + virtual void initialize(ros::NodeHandle& nh, const std::string& topic); void callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg); diff --git a/include/subscriber_gnss_fix.h b/include/subscriber_gnss_fix.h index ebc650e..eb43a57 100644 --- a/include/subscriber_gnss_fix.h +++ b/include/subscriber_gnss_fix.h @@ -45,7 +45,7 @@ class SubscriberGnssFix : public Subscriber const SensorBasePtr _sensor_ptr); WOLF_SUBSCRIBER_CREATE(SubscriberGnssFix); - virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); + virtual void initialize(ros::NodeHandle& nh, const std::string& topic); void callback(const sensor_msgs::NavSatFix::ConstPtr& msg); }; diff --git a/include/subscriber_gnss_novatel.h b/include/subscriber_gnss_novatel.h index 4929e94..485da47 100644 --- a/include/subscriber_gnss_novatel.h +++ b/include/subscriber_gnss_novatel.h @@ -41,7 +41,7 @@ class SubscriberGnssNovatel : public SubscriberGnssReceiver const SensorBasePtr _sensor_ptr); WOLF_SUBSCRIBER_CREATE(SubscriberGnssNovatel); - virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); + virtual void initialize(ros::NodeHandle& nh, const std::string& topic); void callback(const novatel_oem7_msgs::Oem7RawMsg& msg); diff --git a/include/subscriber_gnss_tdcp.h b/include/subscriber_gnss_tdcp.h index af8f7c7..f4ef78f 100644 --- a/include/subscriber_gnss_tdcp.h +++ b/include/subscriber_gnss_tdcp.h @@ -55,7 +55,7 @@ class SubscriberGnssTdcp : public Subscriber const SensorBasePtr _sensor_ptr); WOLF_SUBSCRIBER_CREATE(SubscriberGnssTdcp); - virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); + virtual void initialize(ros::NodeHandle& nh, const std::string& topic); void callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg); diff --git a/include/subscriber_gnss_ublox.h b/include/subscriber_gnss_ublox.h index 5f074a9..4c2616e 100644 --- a/include/subscriber_gnss_ublox.h +++ b/include/subscriber_gnss_ublox.h @@ -41,7 +41,7 @@ class SubscriberGnssUblox : public SubscriberGnssReceiver const SensorBasePtr _sensor_ptr); WOLF_SUBSCRIBER_CREATE(SubscriberGnssUblox); - virtual void initSubscriber(ros::NodeHandle& nh, const std::string& topic); + virtual void initialize(ros::NodeHandle& nh, const std::string& topic); void callback(const std_msgs::UInt8MultiArray& msg); diff --git a/src/subscriber_gnss.cpp b/src/subscriber_gnss.cpp index 9daf225..7099f02 100644 --- a/src/subscriber_gnss.cpp +++ b/src/subscriber_gnss.cpp @@ -12,7 +12,7 @@ SubscriberGnss::SubscriberGnss(const std::string& _unique_name, } -void SubscriberGnss::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void SubscriberGnss::initialize(ros::NodeHandle& nh, const std::string& topic) { sub_ = nh.subscribe(topic+std::string("obs"), 1, &SubscriberGnss::callbackObservation, this); sub_nav_ = nh.subscribe(topic+std::string("nav"), 1, &SubscriberGnss::callbackNavigation, this); diff --git a/src/subscriber_gnss_fix.cpp b/src/subscriber_gnss_fix.cpp index a7f2097..0e72432 100644 --- a/src/subscriber_gnss_fix.cpp +++ b/src/subscriber_gnss_fix.cpp @@ -12,7 +12,7 @@ SubscriberGnssFix::SubscriberGnssFix(const std::string& _unique_name, } -void SubscriberGnssFix::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void SubscriberGnssFix::initialize(ros::NodeHandle& nh, const std::string& topic) { sub_ = nh.subscribe(topic, 1, &SubscriberGnssFix::callback, this); } diff --git a/src/subscriber_gnss_novatel.cpp b/src/subscriber_gnss_novatel.cpp index cb3d0cd..a67cd79 100644 --- a/src/subscriber_gnss_novatel.cpp +++ b/src/subscriber_gnss_novatel.cpp @@ -14,7 +14,7 @@ SubscriberGnssNovatel::SubscriberGnssNovatel(const std::string& _unique_name, { } -void SubscriberGnssNovatel::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void SubscriberGnssNovatel::initialize(ros::NodeHandle& nh, const std::string& topic) { sub_ = nh.subscribe(topic, 100, &SubscriberGnssNovatel::callback, this); diff --git a/src/subscriber_gnss_tdcp.cpp b/src/subscriber_gnss_tdcp.cpp index c6a94ba..43a1ad8 100644 --- a/src/subscriber_gnss_tdcp.cpp +++ b/src/subscriber_gnss_tdcp.cpp @@ -12,7 +12,7 @@ SubscriberGnssTdcp::SubscriberGnssTdcp(const std::string& _unique_name, // TODO copied from Tdcp_ros } -void SubscriberGnssTdcp::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void SubscriberGnssTdcp::initialize(ros::NodeHandle& nh, const std::string& topic) { sub_ = nh.subscribe(topic+std::string("_obs"), 1, &SubscriberGnssTdcp::callbackObservation, this); sub_nav_ = nh.subscribe(topic+std::string("_nav"), 1, &SubscriberGnssTdcp::callbackNavigation, this); diff --git a/src/subscriber_gnss_ublox.cpp b/src/subscriber_gnss_ublox.cpp index b333161..02b68b8 100644 --- a/src/subscriber_gnss_ublox.cpp +++ b/src/subscriber_gnss_ublox.cpp @@ -14,7 +14,7 @@ SubscriberGnssUblox::SubscriberGnssUblox(const std::string& _unique_name, { } -void SubscriberGnssUblox::initSubscriber(ros::NodeHandle& nh, const std::string& topic) +void SubscriberGnssUblox::initialize(ros::NodeHandle& nh, const std::string& topic) { sub_ = nh.subscribe(topic, 100, &SubscriberGnssUblox::callback, this); -- GitLab From e32e08a8f5302c1c18d1a8c825e72285680f16d8 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Mon, 15 Jun 2020 21:37:41 +0200 Subject: [PATCH 31/86] subscribers and publishers to visualize things --- CMakeLists.txt | 12 +++ include/publisher_gnss_tf.h | 40 ++++++++++ ...bscriber_gnss_fix_novatel_publisher_ecef.h | 41 ++++++++++ include/subscriber_gnss_fix_publisher_ecef.h | 57 ++++++++++++++ src/publisher_gnss_tf.cpp | 70 +++++++++++++++++ ...criber_gnss_fix_novatel_publisher_ecef.cpp | 31 ++++++++ src/subscriber_gnss_fix_publisher_ecef.cpp | 77 +++++++++++++++++++ 7 files changed, 328 insertions(+) create mode 100644 include/publisher_gnss_tf.h create mode 100644 include/subscriber_gnss_fix_novatel_publisher_ecef.h create mode 100644 include/subscriber_gnss_fix_publisher_ecef.h create mode 100644 src/publisher_gnss_tf.cpp create mode 100644 src/subscriber_gnss_fix_novatel_publisher_ecef.cpp create mode 100644 src/subscriber_gnss_fix_publisher_ecef.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 161bfba..79f3a08 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,6 +14,7 @@ find_package(catkin REQUIRED COMPONENTS iri_gnss_msgs std_msgs tf + tf_conversions dynamic_reconfigure wolf_ros_node novatel_oem7_msgs @@ -135,9 +136,13 @@ include_directories( # add_library(${PROJECT_NAME} # src/${PROJECT_NAME}/wolf_ros.cpp # ) +add_library(publisher_${PROJECT_NAME} + src/publisher_gnss_tf.cpp) add_library(subscriber_${PROJECT_NAME} src/subscriber_gnss.cpp src/subscriber_gnss_fix.cpp + src/subscriber_gnss_fix_publisher_ecef.cpp + src/subscriber_gnss_fix_novatel_publisher_ecef.cpp src/subscriber_gnss_tdcp.cpp src/subscriber_gnss_receiver.cpp src/subscriber_gnss_ublox.cpp @@ -171,6 +176,13 @@ target_link_libraries(subscriber_${PROJECT_NAME} ${wolf_LIBRARIES} ${wolfgnss_LIBRARIES} ${iri_gnss_msgs_LIBRARIES} + ${catkin_LIBRARIES} + ) +target_link_libraries(publisher_${PROJECT_NAME} + ${wolf_LIBRARIES} + ${wolfgnss_LIBRARIES} + ${iri_gnss_msgs_LIBRARIES} + ${catkin_LIBRARIES} ) ############# diff --git a/include/publisher_gnss_tf.h b/include/publisher_gnss_tf.h new file mode 100644 index 0000000..b88c88b --- /dev/null +++ b/include/publisher_gnss_tf.h @@ -0,0 +1,40 @@ +#ifndef PUBLISHER_GNSS_TF_H +#define PUBLISHER_GNSS_TF_H + +/************************** + * WOLF includes * + **************************/ +#include "core/problem/problem.h" +#include "gnss/sensor/sensor_gnss.h" + +#include "publisher.h" + +#include + +namespace wolf +{ + +class PublisherGnssTf: public Publisher +{ + std::string map_frame_id_, enu_frame_id_, ecef_frame_id_; + tf::StampedTransform T_enu_map_, T_ecef_enu_; + tf::TransformBroadcaster tfb_; + SensorGnssPtr sensor_gnss_; + + public: + PublisherGnssTf(const std::string& _unique_name, + const ParamsServer& _server, + const ProblemPtr _problem); + WOLF_PUBLISHER_CREATE(PublisherGnssTf); + + virtual ~PublisherGnssTf(){}; + + void initialize(ros::NodeHandle &nh, const std::string& topic) override; + + void publishDerived() override; +}; + +WOLF_REGISTER_PUBLISHER(PublisherGnssTf) +} + +#endif diff --git a/include/subscriber_gnss_fix_novatel_publisher_ecef.h b/include/subscriber_gnss_fix_novatel_publisher_ecef.h new file mode 100644 index 0000000..7d905ad --- /dev/null +++ b/include/subscriber_gnss_fix_novatel_publisher_ecef.h @@ -0,0 +1,41 @@ +#ifndef SUBSCRIBER_GNSS_FIX_NOVATEL_PUBLISHER_ECEF_H +#define SUBSCRIBER_GNSS_FIX_NOVATEL_PUBLISHER_ECEF_H + +/************************** + * ROS includes * + **************************/ +#include +#include "novatel_oem7_msgs/BESTPOS.h" + +/************************** + * STD includes * + **************************/ +#include +#include +#include + +/************************** + * WOLF-ROS includes * + **************************/ +#include "subscriber_gnss_fix_publisher_ecef.h" + +namespace wolf +{ + +class SubscriberGnssFixNovatelPublisherEcef : public SubscriberGnssFixPublisherEcef +{ + public: + // Constructor + SubscriberGnssFixNovatelPublisherEcef(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr); + WOLF_SUBSCRIBER_CREATE(SubscriberGnssFixNovatelPublisherEcef); + + void initialize(ros::NodeHandle& nh, const std::string& topic) override; + + void callback(const novatel_oem7_msgs::BESTPOS::ConstPtr& msg); +}; +WOLF_REGISTER_SUBSCRIBER(SubscriberGnssFixNovatelPublisherEcef) + +} +#endif diff --git a/include/subscriber_gnss_fix_publisher_ecef.h b/include/subscriber_gnss_fix_publisher_ecef.h new file mode 100644 index 0000000..71221da --- /dev/null +++ b/include/subscriber_gnss_fix_publisher_ecef.h @@ -0,0 +1,57 @@ +#ifndef SUBSCRIBER_GNSS_FIX_PUBLISHER_ECEF_H +#define SUBSCRIBER_GNSS_FIX_PUBLISHER_ECEF_H + +/************************** + * ROS includes * + **************************/ +#include +#include +#include +#include + +/************************** + * STD includes * + **************************/ +#include +#include +#include + +/************************** + * WOLF-ROS includes * + **************************/ +#include "subscriber.h" + +namespace wolf +{ + +class SubscriberGnssFixPublisherEcef : public Subscriber +{ + protected: + ros::Publisher pub_; + tf::TransformListener tfl_; + bool ENU_defined_; + Eigen::Matrix3d R_enu_ecef_; + Eigen::Vector3d t_enu_ecef_; + nav_msgs::Odometry odom_msg_; + ros::Time last_publish_stamp_; + double period_; + + public: + // Constructor + SubscriberGnssFixPublisherEcef(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr); + WOLF_SUBSCRIBER_CREATE(SubscriberGnssFixPublisherEcef); + + virtual void initialize(ros::NodeHandle& nh, const std::string& topic); + + void callback(const sensor_msgs::NavSatFix::ConstPtr& msg); + + void computeAndPublish(const Eigen::Vector3d& LatLonAlt, const ros::Time& stamp); + + bool listenTf(); +}; +WOLF_REGISTER_SUBSCRIBER(SubscriberGnssFixPublisherEcef) + +} +#endif diff --git a/src/publisher_gnss_tf.cpp b/src/publisher_gnss_tf.cpp new file mode 100644 index 0000000..eafb1bb --- /dev/null +++ b/src/publisher_gnss_tf.cpp @@ -0,0 +1,70 @@ +#include "publisher_gnss_tf.h" + +/************************** + * ROS includes * + **************************/ +#include +#include "tf/transform_datatypes.h" +#include "tf_conversions/tf_eigen.h" + +namespace wolf +{ + +PublisherGnssTf::PublisherGnssTf(const std::string& _unique_name, + const ParamsServer& _server, + const ProblemPtr _problem) : + Publisher(_unique_name, _server, _problem) +{ + sensor_gnss_ = std::static_pointer_cast(_problem->getSensor(_server.getParam(prefix_ + "/sensor_gnss_name"))); + + T_enu_map_.setIdentity(); + T_enu_map_.frame_id_ = "ENU"; + T_enu_map_.child_frame_id_ = "map"; + T_enu_map_.stamp_ = ros::Time::now(); + + T_ecef_enu_.setIdentity(); + T_ecef_enu_.frame_id_ = "ECEF"; + T_ecef_enu_.child_frame_id_ = "ENU"; + T_ecef_enu_.stamp_ = ros::Time::now(); +} + +void PublisherGnssTf::initialize(ros::NodeHandle& nh, const std::string& topic) +{ + // +} + +void PublisherGnssTf::publishDerived() +{ + tf::Matrix3x3 tf_R_enu_map, tf_R_enu_ecef; + tf::Vector3 tf_t_enu_map, tf_t_enu_ecef; + + if (not sensor_gnss_->isEnuDefined()) + return; + + //Eigen::Matrix3d ei_R_enu_ecef = sensor_gnss_->getREnuEcef(); + //Eigen::Vector3d ei_t_enu_ecef = sensor_gnss_->gettEnuEcef(); + + //Eigen::Matrix3d ei_R_enu_map = sensor_gnss_->getREnuMap(); + //Eigen::Vector3d ei_t_enu_map = sensor_gnss_->gettEnuMap(); + + //tf::matrixEigenToTF(ei_R_enu_ecef, tf_R_enu_ecef); + //tf::vectorEigenToTF(ei_t_enu_ecef, tf_t_enu_ecef); + tf::matrixEigenToTF(sensor_gnss_->getREnuEcef(), tf_R_enu_ecef); + tf::vectorEigenToTF(sensor_gnss_->gettEnuEcef(), tf_t_enu_ecef); + + //tf::matrixEigenToTF(ei_R_enu_map, tf_R_enu_map); + //tf::vectorEigenToTF(ei_t_enu_map, tf_t_enu_map); + tf::matrixEigenToTF(sensor_gnss_->getREnuMap(), tf_R_enu_map); + tf::vectorEigenToTF(sensor_gnss_->gettEnuMap(), tf_t_enu_map); + + T_ecef_enu_.setData(tf::Transform(tf_R_enu_ecef, tf_t_enu_ecef).inverse()); + T_enu_map_ .setData(tf::Transform(tf_R_enu_map, tf_t_enu_map)); + + T_ecef_enu_.stamp_ = ros::Time::now(); + T_enu_map_ .stamp_ = ros::Time::now(); + + tfb_.sendTransform(T_ecef_enu_); + tfb_.sendTransform(T_enu_map_); +} + +} diff --git a/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp b/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp new file mode 100644 index 0000000..85d22cf --- /dev/null +++ b/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp @@ -0,0 +1,31 @@ +#include "subscriber_gnss_fix_novatel_publisher_ecef.h" +#include "gnss_utils/utils/transformations.h" +#include "tf/transform_datatypes.h" + +namespace wolf +{ + +// Constructor +SubscriberGnssFixNovatelPublisherEcef::SubscriberGnssFixNovatelPublisherEcef(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr) + : SubscriberGnssFixPublisherEcef(_unique_name, _server, _sensor_ptr) +{ +} + + +void SubscriberGnssFixNovatelPublisherEcef::initialize(ros::NodeHandle& nh, const std::string& topic) +{ + sub_ = nh.subscribe(topic, 1, &SubscriberGnssFixNovatelPublisherEcef::callback, this); + pub_ = nh.advertise(topic+"_ECEF", 1); +} + +void SubscriberGnssFixNovatelPublisherEcef::callback(const novatel_oem7_msgs::BESTPOS::ConstPtr& _msg) +{ + computeAndPublish(Eigen::Vector3d(_msg->lat * M_PI / 180.0, + _msg->lon * M_PI / 180.0, + _msg->hgt), + _msg->header.stamp); +} + +} diff --git a/src/subscriber_gnss_fix_publisher_ecef.cpp b/src/subscriber_gnss_fix_publisher_ecef.cpp new file mode 100644 index 0000000..90f8729 --- /dev/null +++ b/src/subscriber_gnss_fix_publisher_ecef.cpp @@ -0,0 +1,77 @@ +#include "subscriber_gnss_fix_publisher_ecef.h" +#include "gnss_utils/utils/transformations.h" +#include "tf/transform_datatypes.h" +#include "tf_conversions/tf_eigen.h" + +namespace wolf +{ + +// Constructor +SubscriberGnssFixPublisherEcef::SubscriberGnssFixPublisherEcef(const std::string& _unique_name, + const ParamsServer& _server, + const SensorBasePtr _sensor_ptr) + : Subscriber(_unique_name, _server, _sensor_ptr) + , ENU_defined_(false) +{ + period_ = _server.getParam(prefix_ + "/period"); + odom_msg_.header.frame_id = "ENU"; + odom_msg_.pose.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(0,M_PI/2,0); +} + + +void SubscriberGnssFixPublisherEcef::initialize(ros::NodeHandle& nh, const std::string& topic) +{ + sub_ = nh.subscribe(topic, 1, &SubscriberGnssFixPublisherEcef::callback, this); + pub_ = nh.advertise(topic+"_ECEF", 1); +} + +void SubscriberGnssFixPublisherEcef::callback(const sensor_msgs::NavSatFix::ConstPtr& _msg) +{ + computeAndPublish(Eigen::Vector3d(_msg->latitude * M_PI / 180.0, + _msg->longitude * M_PI / 180.0, + _msg->altitude), + _msg->header.stamp); +} + +void SubscriberGnssFixPublisherEcef::computeAndPublish(const Eigen::Vector3d& LatLonAlt, const ros::Time& stamp) +{ + // listen TF ECEF-ENU once + if (not ENU_defined_) + if (not listenTf()) + return; + + if ((stamp - last_publish_stamp_).toSec() < period_) + return; + + // ECEF-ENU is defined + Eigen::Vector3d fix_ENU = R_enu_ecef_ * GnssUtils::latLonAltToEcef(LatLonAlt) + t_enu_ecef_; + + // Fill Odometry msg + odom_msg_.header.stamp = stamp; + + odom_msg_.pose.pose.position.x = fix_ENU(0); + odom_msg_.pose.pose.position.y = fix_ENU(1); + odom_msg_.pose.pose.position.z = fix_ENU(2); + + pub_.publish(odom_msg_); + + last_publish_stamp_ = stamp; +} + +bool SubscriberGnssFixPublisherEcef::listenTf() +{ + tf::StampedTransform T_ecef2enu; + if ( tfl_.waitForTransform("ENU", "ECEF", ros::Time(0), ros::Duration(0.01)) ) + { + tfl_.lookupTransform("ENU", "ECEF", ros::Time(0), T_ecef2enu); + + tf::matrixTFToEigen(T_ecef2enu.getBasis(), R_enu_ecef_); + tf::vectorTFToEigen(T_ecef2enu.getOrigin(), t_enu_ecef_); + + ENU_defined_ = true; + return true; + } + return false; +} + +} -- GitLab From 0ea482f3c151c32e53aec3c1c6623fbd43e15fbe Mon Sep 17 00:00:00 2001 From: joanvallve Date: Wed, 17 Jun 2020 12:26:08 +0200 Subject: [PATCH 32/86] undulation of Novatel to get altitude --- src/subscriber_gnss_fix_novatel_publisher_ecef.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp b/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp index 85d22cf..cd62fe0 100644 --- a/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp +++ b/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp @@ -24,7 +24,7 @@ void SubscriberGnssFixNovatelPublisherEcef::callback(const novatel_oem7_msgs::BE { computeAndPublish(Eigen::Vector3d(_msg->lat * M_PI / 180.0, _msg->lon * M_PI / 180.0, - _msg->hgt), + _msg->hgt+_msg->undulation), _msg->header.stamp); } -- GitLab From cfba438e2c03a1bc6c30b2b2b2f5f97cb9183d1e Mon Sep 17 00:00:00 2001 From: joanvallve Date: Thu, 18 Jun 2020 21:25:36 +0200 Subject: [PATCH 33/86] subcribers publishers publishing trajectories --- include/subscriber_gnss_fix_publisher_ecef.h | 18 ++- include/subscriber_gnss_novatel.h | 3 +- include/subscriber_gnss_receiver.h | 27 +++- include/subscriber_gnss_ublox.h | 1 - ...criber_gnss_fix_novatel_publisher_ecef.cpp | 3 +- src/subscriber_gnss_fix_publisher_ecef.cpp | 71 ++++++++-- src/subscriber_gnss_novatel.cpp | 5 +- src/subscriber_gnss_receiver.cpp | 134 ++++++++++++++++-- src/subscriber_gnss_ublox.cpp | 5 +- 9 files changed, 228 insertions(+), 39 deletions(-) diff --git a/include/subscriber_gnss_fix_publisher_ecef.h b/include/subscriber_gnss_fix_publisher_ecef.h index 71221da..7881408 100644 --- a/include/subscriber_gnss_fix_publisher_ecef.h +++ b/include/subscriber_gnss_fix_publisher_ecef.h @@ -6,7 +6,8 @@ **************************/ #include #include -#include +#include +#include #include /************************** @@ -27,14 +28,20 @@ namespace wolf class SubscriberGnssFixPublisherEcef : public Subscriber { protected: - ros::Publisher pub_; + // TF tf::TransformListener tfl_; bool ENU_defined_; Eigen::Matrix3d R_enu_ecef_; Eigen::Vector3d t_enu_ecef_; - nav_msgs::Odometry odom_msg_; + + // publisher ros::Time last_publish_stamp_; double period_; + bool pose_array_, marker_; + geometry_msgs::PoseArray pose_array_msg_; + visualization_msgs::Marker marker_msg_; + std_msgs::ColorRGBA marker_color_; + ros::Publisher pub_pose_array_, pub_marker_; public: // Constructor @@ -43,13 +50,16 @@ class SubscriberGnssFixPublisherEcef : public Subscriber const SensorBasePtr _sensor_ptr); WOLF_SUBSCRIBER_CREATE(SubscriberGnssFixPublisherEcef); - virtual void initialize(ros::NodeHandle& nh, const std::string& topic); + void initialize(ros::NodeHandle& nh, const std::string& topic) override; void callback(const sensor_msgs::NavSatFix::ConstPtr& msg); void computeAndPublish(const Eigen::Vector3d& LatLonAlt, const ros::Time& stamp); + protected: bool listenTf(); + + void publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp); }; WOLF_REGISTER_SUBSCRIBER(SubscriberGnssFixPublisherEcef) diff --git a/include/subscriber_gnss_novatel.h b/include/subscriber_gnss_novatel.h index 485da47..9c68953 100644 --- a/include/subscriber_gnss_novatel.h +++ b/include/subscriber_gnss_novatel.h @@ -15,7 +15,6 @@ **************************/ #include #include "novatel_oem7_msgs/Oem7RawMsg.h" -#include /************************** * WOLF-ROS includes * @@ -41,7 +40,7 @@ class SubscriberGnssNovatel : public SubscriberGnssReceiver const SensorBasePtr _sensor_ptr); WOLF_SUBSCRIBER_CREATE(SubscriberGnssNovatel); - virtual void initialize(ros::NodeHandle& nh, const std::string& topic); + void initialize(ros::NodeHandle& nh, const std::string& topic) override; void callback(const novatel_oem7_msgs::Oem7RawMsg& msg); diff --git a/include/subscriber_gnss_receiver.h b/include/subscriber_gnss_receiver.h index 3633816..b12f5d5 100644 --- a/include/subscriber_gnss_receiver.h +++ b/include/subscriber_gnss_receiver.h @@ -15,6 +15,9 @@ **************************/ #include #include +#include +#include +#include /************************** * WOLF-ROS includes * @@ -41,16 +44,36 @@ class SubscriberGnssReceiver : public Subscriber const SensorBasePtr _sensor_ptr, GnssUtils::ReceiverRawAbstractPtr _receiver); + void initialize(ros::NodeHandle& nh, const std::string& topic) override; protected: void createCaptureAndProcess(); GnssUtils::ReceiverRawAbstractPtr receiver_; - bool sats_available_; + + // sats available bool process_not_available_; + bool sats_available_; + ros::Publisher pub_available_; + + // Publish fix + void publishFix(const Eigen::Vector3d& fix_ECEF); + void publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp); + ros::Time last_publish_stamp_; + double period_; + bool publish_fix_, pose_array_, marker_; + geometry_msgs::PoseArray pose_array_msg_; + visualization_msgs::Marker marker_msg_; + std_msgs::ColorRGBA marker_color_; + ros::Publisher pub_pose_array_, pub_marker_; - ros::Publisher available_pub_; + //TF + bool listenTf(); + bool ENU_defined_; + Eigen::Matrix3d R_enu_ecef_; + Eigen::Vector3d t_enu_ecef_; + tf::TransformListener tfl_; }; } diff --git a/include/subscriber_gnss_ublox.h b/include/subscriber_gnss_ublox.h index 4c2616e..8f5f677 100644 --- a/include/subscriber_gnss_ublox.h +++ b/include/subscriber_gnss_ublox.h @@ -15,7 +15,6 @@ **************************/ #include #include -#include /************************** * WOLF-ROS includes * diff --git a/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp b/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp index cd62fe0..70127b5 100644 --- a/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp +++ b/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp @@ -16,8 +16,9 @@ SubscriberGnssFixNovatelPublisherEcef::SubscriberGnssFixNovatelPublisherEcef(con void SubscriberGnssFixNovatelPublisherEcef::initialize(ros::NodeHandle& nh, const std::string& topic) { + SubscriberGnssFixPublisherEcef::initialize(nh, topic); + sub_.shutdown(); sub_ = nh.subscribe(topic, 1, &SubscriberGnssFixNovatelPublisherEcef::callback, this); - pub_ = nh.advertise(topic+"_ECEF", 1); } void SubscriberGnssFixNovatelPublisherEcef::callback(const novatel_oem7_msgs::BESTPOS::ConstPtr& _msg) diff --git a/src/subscriber_gnss_fix_publisher_ecef.cpp b/src/subscriber_gnss_fix_publisher_ecef.cpp index 90f8729..2240096 100644 --- a/src/subscriber_gnss_fix_publisher_ecef.cpp +++ b/src/subscriber_gnss_fix_publisher_ecef.cpp @@ -13,16 +13,43 @@ SubscriberGnssFixPublisherEcef::SubscriberGnssFixPublisherEcef(const std::string : Subscriber(_unique_name, _server, _sensor_ptr) , ENU_defined_(false) { - period_ = _server.getParam(prefix_ + "/period"); - odom_msg_.header.frame_id = "ENU"; - odom_msg_.pose.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(0,M_PI/2,0); + period_ = _server.getParam(prefix_ + "/period"); + pose_array_ = _server.getParam(prefix_ + "/pose_array_msg"); + marker_ = _server.getParam(prefix_ + "/marker_msg"); + if (marker_) + { + Eigen::Vector4d col = _server.getParam(prefix_ + "/marker_color"); + marker_color_.r = col(0); + marker_color_.g = col(1); + marker_color_.b = col(2); + marker_color_.a = col(3); + } } void SubscriberGnssFixPublisherEcef::initialize(ros::NodeHandle& nh, const std::string& topic) { sub_ = nh.subscribe(topic, 1, &SubscriberGnssFixPublisherEcef::callback, this); - pub_ = nh.advertise(topic+"_ECEF", 1); + + // initialize msg and publisher + if (pose_array_) + { + pose_array_msg_.header.frame_id = "ENU"; + + pub_pose_array_ = nh.advertise(topic + "_ENU_pose_array", 1); + } + if (marker_) + { + marker_msg_.header.frame_id = "ENU"; + marker_msg_.type = visualization_msgs::Marker::LINE_STRIP; + marker_msg_.action = visualization_msgs::Marker::ADD; + marker_msg_.ns = "trajectory"; + marker_msg_.scale.x = 0.1; + marker_msg_.color = marker_color_; + marker_msg_.pose.orientation = tf::createQuaternionMsgFromYaw(0); + + pub_marker_ = nh.advertise(topic + "_ENU_marker", 1); + } } void SubscriberGnssFixPublisherEcef::callback(const sensor_msgs::NavSatFix::ConstPtr& _msg) @@ -36,9 +63,8 @@ void SubscriberGnssFixPublisherEcef::callback(const sensor_msgs::NavSatFix::Cons void SubscriberGnssFixPublisherEcef::computeAndPublish(const Eigen::Vector3d& LatLonAlt, const ros::Time& stamp) { // listen TF ECEF-ENU once - if (not ENU_defined_) - if (not listenTf()) - return; + if (not ENU_defined_ and not listenTf()) + return; if ((stamp - last_publish_stamp_).toSec() < period_) return; @@ -47,13 +73,13 @@ void SubscriberGnssFixPublisherEcef::computeAndPublish(const Eigen::Vector3d& La Eigen::Vector3d fix_ENU = R_enu_ecef_ * GnssUtils::latLonAltToEcef(LatLonAlt) + t_enu_ecef_; // Fill Odometry msg - odom_msg_.header.stamp = stamp; - - odom_msg_.pose.pose.position.x = fix_ENU(0); - odom_msg_.pose.pose.position.y = fix_ENU(1); - odom_msg_.pose.pose.position.z = fix_ENU(2); + geometry_msgs::Pose pose_msg; + pose_msg.position.x = fix_ENU(0); + pose_msg.position.y = fix_ENU(1); + pose_msg.position.z = fix_ENU(2); + pose_msg.orientation = tf::createQuaternionMsgFromRollPitchYaw(0,M_PI/2,0); - pub_.publish(odom_msg_); + publishPose(pose_msg, stamp); last_publish_stamp_ = stamp; } @@ -74,4 +100,23 @@ bool SubscriberGnssFixPublisherEcef::listenTf() return false; } +void SubscriberGnssFixPublisherEcef::publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp) +{ + // fill msgs and publish + if (pose_array_) + { + pose_array_msg_.header.stamp = stamp; + pose_array_msg_.poses.push_back(pose); + + pub_pose_array_.publish(pose_array_msg_); + } + if (marker_) + { + marker_msg_.header.stamp = stamp; + marker_msg_.points.push_back(pose.position); + + pub_marker_.publish(marker_msg_); + } +} + } diff --git a/src/subscriber_gnss_novatel.cpp b/src/subscriber_gnss_novatel.cpp index a67cd79..bc59fd5 100644 --- a/src/subscriber_gnss_novatel.cpp +++ b/src/subscriber_gnss_novatel.cpp @@ -16,10 +16,9 @@ SubscriberGnssNovatel::SubscriberGnssNovatel(const std::string& _unique_name, void SubscriberGnssNovatel::initialize(ros::NodeHandle& nh, const std::string& topic) { - sub_ = nh.subscribe(topic, 100, &SubscriberGnssNovatel::callback, this); + SubscriberGnssReceiver::initialize(nh, topic); - // publisher of flag "satellites available" - available_pub_ = nh.advertise("gnss_available", 1); + sub_ = nh.subscribe(topic, 100, &SubscriberGnssNovatel::callback, this); } void SubscriberGnssNovatel::callback(const novatel_oem7_msgs::Oem7RawMsg& msg) diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index 574e466..3477eac 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -1,4 +1,6 @@ #include "../include/subscriber_gnss_receiver.h" +#include "tf/transform_datatypes.h" +#include "tf_conversions/tf_eigen.h" namespace wolf { @@ -9,31 +11,83 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, GnssUtils::ReceiverRawAbstractPtr _receiver) : Subscriber(_unique_name, _server, _sensor_ptr), receiver_(_receiver), - sats_available_(false) + sats_available_(false), + ENU_defined_(false) { process_not_available_ = _server.getParam(prefix_ + "/process_not_available"); + publish_fix_ = _server.getParam(prefix_ + "/publish_fix/enabled"); + if (publish_fix_) + { + pose_array_ = _server.getParam(prefix_ + "/publish_fix/pose_array_msg"); + marker_ = _server.getParam(prefix_ + "/publish_fix/marker_msg"); + if (marker_) + { + Eigen::Vector4d col = _server.getParam(prefix_ + "/marker_color"); + marker_color_.r = col(0); + marker_color_.g = col(1); + marker_color_.b = col(2); + marker_color_.a = col(3); + } + } + + // user print ROS_INFO("Waiting for satellites..."); } +void SubscriberGnssReceiver::initialize(ros::NodeHandle& nh, const std::string& topic) +{ + pub_available_ = nh.advertise("gnss_available", 1); + if (publish_fix_) + { + // initialize msg and publisher + if (pose_array_) + { + pose_array_msg_.header.frame_id = "ENU"; + + pub_pose_array_ = nh.advertise(topic + "_ENU_pose_array", 1); + } + if (marker_) + { + marker_msg_.header.frame_id = "ENU"; + marker_msg_.type = visualization_msgs::Marker::LINE_STRIP; + marker_msg_.action = visualization_msgs::Marker::ADD; + marker_msg_.ns = "trajectory"; + marker_msg_.scale.x = 0.1; + marker_msg_.color = marker_color_; + marker_msg_.pose.orientation = tf::createQuaternionMsgFromYaw(0); + + pub_marker_ = nh.advertise(topic + "_ENU_marker", 1); + } + } +} + void SubscriberGnssReceiver::createCaptureAndProcess() { - // check if satellites are available already (only check once: cold start) - if (!sats_available_) + GnssUtils::ComputePosOutput fix; + + // compute fix if publishing or not sats_available + if (not sats_available_ or publish_fix_) { - sats_available_ = GnssUtils::computePos(receiver_->getObservations(), - receiver_->getNavigation(), - GnssUtils::default_options).success; + fix = GnssUtils::computePos(receiver_->getObservations(), + receiver_->getNavigation(), + GnssUtils::default_options); + } - // discarding first data (to give time to IMU) + // if (last time) satellites were not available: check if they are + if (not sats_available_) + { + sats_available_ = fix.success; + + // raising message once if (sats_available_) ROS_INFO("Enough satellites to start!"); } - else + else // discard first message with satellites to give IMU time { // publisher of flag "satellites available" std_msgs::Bool msg; msg.data = sats_available_; - available_pub_.publish(msg); + pub_available_.publish(msg); auto snapshot_ptr = std::make_shared(std::make_shared(receiver_->getObservations()), std::make_shared(receiver_->getNavigation())); @@ -48,10 +102,70 @@ void SubscriberGnssReceiver::createCaptureAndProcess() cap_gnss_ptr->process(); //ROS_INFO("Capture GNSS processed!"); } + // publish available + sats_available_ = fix.success; std_msgs::Bool msg; msg.data = sats_available_; - available_pub_.publish(msg); + pub_available_.publish(msg); + + // publish fix + if (publish_fix_) + publishFix(fix.pos); +} + +void SubscriberGnssReceiver::publishFix(const Eigen::Vector3d& fix_ECEF) +{ + // listen TF ECEF-ENU once + if (not ENU_defined_ and not listenTf()) + return; + + // ECEF-ENU is defined + Eigen::Vector3d fix_ENU = R_enu_ecef_ * fix_ECEF + t_enu_ecef_; + + // Fill Pose msg + geometry_msgs::Pose pose_msg; + pose_msg.position.x = fix_ENU(0); + pose_msg.position.y = fix_ENU(1); + pose_msg.position.z = fix_ENU(2); + pose_msg.orientation = tf::createQuaternionMsgFromRollPitchYaw(0,M_PI/2,0); + + publishPose(pose_msg, ros::Time::now()); +} + +bool SubscriberGnssReceiver::listenTf() +{ + tf::StampedTransform T_ecef2enu; + if ( tfl_.waitForTransform("ENU", "ECEF", ros::Time(0), ros::Duration(0.01)) ) + { + tfl_.lookupTransform("ENU", "ECEF", ros::Time(0), T_ecef2enu); + + tf::matrixTFToEigen(T_ecef2enu.getBasis(), R_enu_ecef_); + tf::vectorTFToEigen(T_ecef2enu.getOrigin(), t_enu_ecef_); + + ENU_defined_ = true; + return true; + } + return false; +} + +void SubscriberGnssReceiver::publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp) +{ + // fill msgs and publish + if (pose_array_) + { + pose_array_msg_.header.stamp = stamp; + pose_array_msg_.poses.push_back(pose); + + pub_pose_array_.publish(pose_array_msg_); + } + if (marker_) + { + marker_msg_.header.stamp = stamp; + marker_msg_.points.push_back(pose.position); + + pub_marker_.publish(marker_msg_); + } } } diff --git a/src/subscriber_gnss_ublox.cpp b/src/subscriber_gnss_ublox.cpp index 02b68b8..31dc86f 100644 --- a/src/subscriber_gnss_ublox.cpp +++ b/src/subscriber_gnss_ublox.cpp @@ -16,10 +16,9 @@ SubscriberGnssUblox::SubscriberGnssUblox(const std::string& _unique_name, void SubscriberGnssUblox::initialize(ros::NodeHandle& nh, const std::string& topic) { - sub_ = nh.subscribe(topic, 100, &SubscriberGnssUblox::callback, this); + SubscriberGnssReceiver::initialize(nh, topic); - // publisher of flag "satellites available" - available_pub_ = nh.advertise("gnss_available", 1); + sub_ = nh.subscribe(topic, 100, &SubscriberGnssUblox::callback, this); } void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) -- GitLab From 3899681bd036290b97aeb4bf30f71d36daba3442 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Sat, 20 Jun 2020 01:17:44 +0200 Subject: [PATCH 34/86] covariance source --- include/subscriber_gnss_fix.h | 4 ++++ src/subscriber_gnss_fix.cpp | 14 ++++++++++++-- 2 files changed, 16 insertions(+), 2 deletions(-) diff --git a/include/subscriber_gnss_fix.h b/include/subscriber_gnss_fix.h index eb43a57..ab5dcf2 100644 --- a/include/subscriber_gnss_fix.h +++ b/include/subscriber_gnss_fix.h @@ -38,6 +38,10 @@ namespace wolf class SubscriberGnssFix : public Subscriber { + std::string cov_mode_; + double cov_factor_; + Eigen::Matrix3d cov_; + public: // Constructor SubscriberGnssFix(const std::string& _unique_name, diff --git a/src/subscriber_gnss_fix.cpp b/src/subscriber_gnss_fix.cpp index 0e72432..59f0877 100644 --- a/src/subscriber_gnss_fix.cpp +++ b/src/subscriber_gnss_fix.cpp @@ -8,7 +8,16 @@ SubscriberGnssFix::SubscriberGnssFix(const std::string& _unique_name, const ParamsServer& _server, const SensorBasePtr _sensor_ptr) : Subscriber(_unique_name, _server, _sensor_ptr) + , cov_factor_(1) { + + cov_mode_ = _server.getParam(prefix_ + "/cov_mode"); + + //if (cov_mode_ == "msg") //nothing to be done + if (cov_mode_ == "manual") + cov_ = _server.getParam(prefix_ + "/cov"); + if (cov_mode_ == "factor") + cov_factor_ = _server.getParam(prefix_ + "/cov_factor"); } @@ -19,14 +28,15 @@ void SubscriberGnssFix::initialize(ros::NodeHandle& nh, const std::string& topic void SubscriberGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg) { - Eigen::Matrix3d cov = Eigen::Map(msg->position_covariance.data()); + if (cov_mode_ == "msg" or cov_mode_ == "factor") + cov_ = cov_factor_ * Eigen::Map(msg->position_covariance.data()); CaptureGnssFixPtr cap_gnss_ptr = std::make_shared(TimeStamp(msg->header.stamp.sec, msg->header.stamp.nsec), sensor_ptr_, Eigen::Vector3d(msg->latitude * M_PI / 180.0, msg->longitude * M_PI / 180.0, msg->altitude), - cov, + cov_, false); // false = {LatLonAlt fix and ENU cov} cap_gnss_ptr->process(); } -- GitLab From e79c494473c578d1ef42869b6d9a1318af7fd19c Mon Sep 17 00:00:00 2001 From: joanvallve Date: Mon, 22 Jun 2020 15:36:38 +0200 Subject: [PATCH 35/86] wip --- include/subscriber_gnss_receiver.h | 19 ++-- src/subscriber_gnss_receiver.cpp | 170 +++++++++++++++++++++-------- 2 files changed, 137 insertions(+), 52 deletions(-) diff --git a/include/subscriber_gnss_receiver.h b/include/subscriber_gnss_receiver.h index b12f5d5..6142983 100644 --- a/include/subscriber_gnss_receiver.h +++ b/include/subscriber_gnss_receiver.h @@ -58,15 +58,20 @@ class SubscriberGnssReceiver : public Subscriber ros::Publisher pub_available_; // Publish fix - void publishFix(const Eigen::Vector3d& fix_ECEF); - void publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp); - ros::Time last_publish_stamp_; - double period_; + void publishFixComp(); + void publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp, const std::string& comp); bool publish_fix_, pose_array_, marker_; - geometry_msgs::PoseArray pose_array_msg_; - visualization_msgs::Marker marker_msg_; std_msgs::ColorRGBA marker_color_; - ros::Publisher pub_pose_array_, pub_marker_; + std::string topic_fix_; + GnssUtils::Options compute_pos_opt_; + + // comparative + std::map pose_array_msgs_; + std::map marker_msgs_; + std::map last_fixes_ok_; + std::map last_fixes_pose_; + std::map publishers_pose_array_, publishers_marker_; + std::vector comp_options_; //TF bool listenTf(); diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index 3477eac..d6fb76e 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -20,14 +20,64 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, { pose_array_ = _server.getParam(prefix_ + "/publish_fix/pose_array_msg"); marker_ = _server.getParam(prefix_ + "/publish_fix/marker_msg"); + topic_fix_ = _server.getParam(prefix_ + "/publish_fix/topic"); if (marker_) { - Eigen::Vector4d col = _server.getParam(prefix_ + "/marker_color"); + Eigen::Vector4d col = _server.getParam(prefix_ + "/publish_fix/marker_color"); marker_color_.r = col(0); marker_color_.g = col(1); marker_color_.b = col(2); marker_color_.a = col(3); } + compute_pos_opt_ = GnssUtils::default_options; + // GNSS OPTIONS (see gnss_utils.h) + try{compute_pos_opt_.sateph = _server.getParam (prefix_ + "/publish_fix/gnss_options/sateph"); // satellite ephemeris/clock (0:broadcast ephemeris,1:precise ephemeris,2:broadcast + SBAS,3:ephemeris option: broadcast + SSR_APC,4:broadcast + SSR_COM,5: QZSS LEX ephemeris + }catch(...){} + try{compute_pos_opt_.ionoopt = _server.getParam (prefix_ + "/publish_fix/gnss_options/ionoopt"); // ionosphere option (0:correction off,1:broadcast mode,2:SBAS model,3:L1/L2 or L1/L5,4:estimation,5:IONEX TEC model,6:QZSS broadcast,7:QZSS LEX ionosphere,8:SLANT TEC mode) + }catch(...){} + try{compute_pos_opt_.tropopt = _server.getParam (prefix_ + "/publish_fix/gnss_options/tropopt"); // troposphere option: (0:correction off,1:Saastamoinen model,2:SBAS model,3:troposphere option: ZTD estimation,4:ZTD+grad estimation,5:ZTD correction,6:ZTD+grad correction) + }catch(...){} + try{compute_pos_opt_.sbascorr = _server.getParam (prefix_ + "/publish_fix/gnss_options/sbascorr");// SBAS option (1:long term correction,2:fast correction,4:ionosphere correction,8:ranging) + }catch(...){} + try{compute_pos_opt_.raim = _server.getParam (prefix_ + "/publish_fix/gnss_options/raim"); // RAIM enabled + }catch(...){} + try{compute_pos_opt_.elmin = D2R * _server.getParam(prefix_ + "/publish_fix/gnss_options/elmin"); // min elevation (degrees) + }catch(...){} + try{compute_pos_opt_.maxgdop = _server.getParam(prefix_ + "/publish_fix/gnss_options/maxgdop"); // maxgdop: reject threshold of gdop + }catch(...){} + + try{compute_pos_opt_.GPS = _server.getParam(prefix_ + "/publish_fix/gnss_options/constellations/GPS"); /* navigation system */ + }catch(...){} + try{compute_pos_opt_.SBS = _server.getParam(prefix_ + "/publish_fix/gnss_options/constellations/SBS"); + }catch(...){} + try{compute_pos_opt_.GLO = _server.getParam(prefix_ + "/publish_fix/gnss_options/constellations/GLO"); + }catch(...){} + try{compute_pos_opt_.GAL = _server.getParam(prefix_ + "/publish_fix/gnss_options/constellations/GAL"); + }catch(...){} + try{compute_pos_opt_.QZS = _server.getParam(prefix_ + "/publish_fix/gnss_options/constellations/QZS"); + }catch(...){} + try{compute_pos_opt_.CMP = _server.getParam(prefix_ + "/publish_fix/gnss_options/constellations/CMP"); + }catch(...){} + try{compute_pos_opt_.IRN = _server.getParam(prefix_ + "/publish_fix/gnss_options/constellations/IRN"); + }catch(...){} + try{compute_pos_opt_.LEO = _server.getParam(prefix_ + "/publish_fix/gnss_options/constellations/LEO"); + }catch(...){} + + // comparation of GNSS options + comp_options_.push_back("000"); + comp_options_.push_back("001"); + comp_options_.push_back("010"); + comp_options_.push_back("011"); + comp_options_.push_back("100"); + comp_options_.push_back("101"); + comp_options_.push_back("110"); + comp_options_.push_back("111"); + + for (auto comp : comp_options_) + { + last_fixes_ok_.emplace(comp, false); + last_fixes_pose_.emplace(comp, geometry_msgs::Pose()); + } } // user print @@ -42,21 +92,29 @@ void SubscriberGnssReceiver::initialize(ros::NodeHandle& nh, const std::string& // initialize msg and publisher if (pose_array_) { - pose_array_msg_.header.frame_id = "ENU"; + for (auto comp : comp_options_) + { + pose_array_msgs_[comp] = geometry_msgs::PoseArray(); + pose_array_msgs_.at(comp).header.frame_id = "ENU"; - pub_pose_array_ = nh.advertise(topic + "_ENU_pose_array", 1); + publishers_pose_array_[comp] = nh.advertise(topic_fix_ + comp + "_pose_array", 1); + } } if (marker_) { - marker_msg_.header.frame_id = "ENU"; - marker_msg_.type = visualization_msgs::Marker::LINE_STRIP; - marker_msg_.action = visualization_msgs::Marker::ADD; - marker_msg_.ns = "trajectory"; - marker_msg_.scale.x = 0.1; - marker_msg_.color = marker_color_; - marker_msg_.pose.orientation = tf::createQuaternionMsgFromYaw(0); - - pub_marker_ = nh.advertise(topic + "_ENU_marker", 1); + for (auto comp : comp_options_) + { + marker_msgs_[comp] = visualization_msgs::Marker(); + marker_msgs_.at(comp).header.frame_id = "ENU"; + marker_msgs_.at(comp).type = visualization_msgs::Marker::LINE_LIST; + marker_msgs_.at(comp).action = visualization_msgs::Marker::ADD; + marker_msgs_.at(comp).ns = "trajectory"; + marker_msgs_.at(comp).scale.x = 0.1; + marker_msgs_.at(comp).color = marker_color_; + marker_msgs_.at(comp).pose.orientation = tf::createQuaternionMsgFromYaw(0); + + publishers_marker_[comp] = nh.advertise(topic_fix_ + comp + "_marker", 1); + } } } } @@ -67,11 +125,9 @@ void SubscriberGnssReceiver::createCaptureAndProcess() // compute fix if publishing or not sats_available if (not sats_available_ or publish_fix_) - { fix = GnssUtils::computePos(receiver_->getObservations(), receiver_->getNavigation(), - GnssUtils::default_options); - } + compute_pos_opt_); // if (last time) satellites were not available: check if they are if (not sats_available_) @@ -111,26 +167,69 @@ void SubscriberGnssReceiver::createCaptureAndProcess() // publish fix if (publish_fix_) - publishFix(fix.pos); + publishFixComp(); } -void SubscriberGnssReceiver::publishFix(const Eigen::Vector3d& fix_ECEF) +void SubscriberGnssReceiver::publishFixComp() { // listen TF ECEF-ENU once if (not ENU_defined_ and not listenTf()) return; - // ECEF-ENU is defined - Eigen::Vector3d fix_ENU = R_enu_ecef_ * fix_ECEF + t_enu_ecef_; + for (auto comp : comp_options_) + { + compute_pos_opt_.raim = comp[0] == '1'; + compute_pos_opt_.sateph = (comp[1] == '0' ? 0 : 2); + compute_pos_opt_.ionoopt = (comp[2] == '0' ? 1 : 3); + + auto fix = GnssUtils::computePos(receiver_->getObservations(), + receiver_->getNavigation(), + compute_pos_opt_); + + + // ECEF-ENU is defined + Eigen::Vector3d fix_ENU = R_enu_ecef_ * fix.pos + t_enu_ecef_; - // Fill Pose msg - geometry_msgs::Pose pose_msg; - pose_msg.position.x = fix_ENU(0); - pose_msg.position.y = fix_ENU(1); - pose_msg.position.z = fix_ENU(2); - pose_msg.orientation = tf::createQuaternionMsgFromRollPitchYaw(0,M_PI/2,0); + // Fill Pose msg + geometry_msgs::Pose pose_msg; + pose_msg.position.x = fix_ENU(0); + pose_msg.position.y = fix_ENU(1); + pose_msg.position.z = fix_ENU(2); + pose_msg.orientation = tf::createQuaternionMsgFromRollPitchYaw(0,M_PI/2,0); - publishPose(pose_msg, ros::Time::now()); + if (fix.success) + publishPose(pose_msg, ros::Time::now(), comp); + else + std::cout << "Comp " << comp << " failed: " << fix.msg << std::endl; + + // store last + last_fixes_ok_.at(comp) = fix.success; + last_fixes_pose_.at(comp) = pose_msg; + } +} + +void SubscriberGnssReceiver::publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp, const std::string& comp) +{ + // fill msgs and publish + if (pose_array_) + { + pose_array_msgs_.at(comp).header.stamp = stamp; + pose_array_msgs_.at(comp).poses.push_back(pose); + + publishers_pose_array_.at(comp).publish(pose_array_msgs_.at(comp)); + } + if (marker_ and last_fixes_ok_.at(comp)) + { + marker_msgs_.at(comp).header.stamp = stamp; + marker_msgs_.at(comp).points.push_back(last_fixes_pose_.at(comp).position); + marker_msgs_.at(comp).points.push_back(pose.position); + marker_msgs_.at(comp).color.r = comp[0] == '1' ? 0.5 : 0; + marker_msgs_.at(comp).color.g = comp[1] == '1' ? 0.5 : 0; + marker_msgs_.at(comp).color.b = comp[2] == '1' ? 0.5 : 0; + marker_msgs_.at(comp).ns = comp; + + publishers_marker_.at(comp).publish(marker_msgs_.at(comp)); + } } bool SubscriberGnssReceiver::listenTf() @@ -149,23 +248,4 @@ bool SubscriberGnssReceiver::listenTf() return false; } -void SubscriberGnssReceiver::publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp) -{ - // fill msgs and publish - if (pose_array_) - { - pose_array_msg_.header.stamp = stamp; - pose_array_msg_.poses.push_back(pose); - - pub_pose_array_.publish(pose_array_msg_); - } - if (marker_) - { - marker_msg_.header.stamp = stamp; - marker_msg_.points.push_back(pose.position); - - pub_marker_.publish(marker_msg_); - } -} - } -- GitLab From ac3ed41cfbc15981b90ff0184aec445934b0ad47 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Tue, 23 Jun 2020 20:45:03 +0200 Subject: [PATCH 36/86] wip --- include/subscriber_gnss_receiver.h | 1 - src/publisher_gnss_tf.cpp | 4 +- src/subscriber_gnss_receiver.cpp | 127 +++++++++++++++++------------ 3 files changed, 75 insertions(+), 57 deletions(-) diff --git a/include/subscriber_gnss_receiver.h b/include/subscriber_gnss_receiver.h index 6142983..3ae3037 100644 --- a/include/subscriber_gnss_receiver.h +++ b/include/subscriber_gnss_receiver.h @@ -61,7 +61,6 @@ class SubscriberGnssReceiver : public Subscriber void publishFixComp(); void publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp, const std::string& comp); bool publish_fix_, pose_array_, marker_; - std_msgs::ColorRGBA marker_color_; std::string topic_fix_; GnssUtils::Options compute_pos_opt_; diff --git a/src/publisher_gnss_tf.cpp b/src/publisher_gnss_tf.cpp index eafb1bb..3409718 100644 --- a/src/publisher_gnss_tf.cpp +++ b/src/publisher_gnss_tf.cpp @@ -19,7 +19,6 @@ PublisherGnssTf::PublisherGnssTf(const std::string& _unique_name, T_enu_map_.setIdentity(); T_enu_map_.frame_id_ = "ENU"; - T_enu_map_.child_frame_id_ = "map"; T_enu_map_.stamp_ = ros::Time::now(); T_ecef_enu_.setIdentity(); @@ -30,7 +29,8 @@ PublisherGnssTf::PublisherGnssTf(const std::string& _unique_name, void PublisherGnssTf::initialize(ros::NodeHandle& nh, const std::string& topic) { - // + nh.param("map_frame_id", T_enu_map_.child_frame_id_, "map"); + std::cout << "PublisherGnssTf initialized using map_frame_id: " << T_enu_map_.child_frame_id_ << std::endl; } void PublisherGnssTf::publishDerived() diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index d6fb76e..6f46c05 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -18,51 +18,6 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, publish_fix_ = _server.getParam(prefix_ + "/publish_fix/enabled"); if (publish_fix_) { - pose_array_ = _server.getParam(prefix_ + "/publish_fix/pose_array_msg"); - marker_ = _server.getParam(prefix_ + "/publish_fix/marker_msg"); - topic_fix_ = _server.getParam(prefix_ + "/publish_fix/topic"); - if (marker_) - { - Eigen::Vector4d col = _server.getParam(prefix_ + "/publish_fix/marker_color"); - marker_color_.r = col(0); - marker_color_.g = col(1); - marker_color_.b = col(2); - marker_color_.a = col(3); - } - compute_pos_opt_ = GnssUtils::default_options; - // GNSS OPTIONS (see gnss_utils.h) - try{compute_pos_opt_.sateph = _server.getParam (prefix_ + "/publish_fix/gnss_options/sateph"); // satellite ephemeris/clock (0:broadcast ephemeris,1:precise ephemeris,2:broadcast + SBAS,3:ephemeris option: broadcast + SSR_APC,4:broadcast + SSR_COM,5: QZSS LEX ephemeris - }catch(...){} - try{compute_pos_opt_.ionoopt = _server.getParam (prefix_ + "/publish_fix/gnss_options/ionoopt"); // ionosphere option (0:correction off,1:broadcast mode,2:SBAS model,3:L1/L2 or L1/L5,4:estimation,5:IONEX TEC model,6:QZSS broadcast,7:QZSS LEX ionosphere,8:SLANT TEC mode) - }catch(...){} - try{compute_pos_opt_.tropopt = _server.getParam (prefix_ + "/publish_fix/gnss_options/tropopt"); // troposphere option: (0:correction off,1:Saastamoinen model,2:SBAS model,3:troposphere option: ZTD estimation,4:ZTD+grad estimation,5:ZTD correction,6:ZTD+grad correction) - }catch(...){} - try{compute_pos_opt_.sbascorr = _server.getParam (prefix_ + "/publish_fix/gnss_options/sbascorr");// SBAS option (1:long term correction,2:fast correction,4:ionosphere correction,8:ranging) - }catch(...){} - try{compute_pos_opt_.raim = _server.getParam (prefix_ + "/publish_fix/gnss_options/raim"); // RAIM enabled - }catch(...){} - try{compute_pos_opt_.elmin = D2R * _server.getParam(prefix_ + "/publish_fix/gnss_options/elmin"); // min elevation (degrees) - }catch(...){} - try{compute_pos_opt_.maxgdop = _server.getParam(prefix_ + "/publish_fix/gnss_options/maxgdop"); // maxgdop: reject threshold of gdop - }catch(...){} - - try{compute_pos_opt_.GPS = _server.getParam(prefix_ + "/publish_fix/gnss_options/constellations/GPS"); /* navigation system */ - }catch(...){} - try{compute_pos_opt_.SBS = _server.getParam(prefix_ + "/publish_fix/gnss_options/constellations/SBS"); - }catch(...){} - try{compute_pos_opt_.GLO = _server.getParam(prefix_ + "/publish_fix/gnss_options/constellations/GLO"); - }catch(...){} - try{compute_pos_opt_.GAL = _server.getParam(prefix_ + "/publish_fix/gnss_options/constellations/GAL"); - }catch(...){} - try{compute_pos_opt_.QZS = _server.getParam(prefix_ + "/publish_fix/gnss_options/constellations/QZS"); - }catch(...){} - try{compute_pos_opt_.CMP = _server.getParam(prefix_ + "/publish_fix/gnss_options/constellations/CMP"); - }catch(...){} - try{compute_pos_opt_.IRN = _server.getParam(prefix_ + "/publish_fix/gnss_options/constellations/IRN"); - }catch(...){} - try{compute_pos_opt_.LEO = _server.getParam(prefix_ + "/publish_fix/gnss_options/constellations/LEO"); - }catch(...){} - // comparation of GNSS options comp_options_.push_back("000"); comp_options_.push_back("001"); @@ -72,7 +27,45 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, comp_options_.push_back("101"); comp_options_.push_back("110"); comp_options_.push_back("111"); + comp_options_.push_back("200"); + + // params + pose_array_ = _server.getParam(prefix_ + "/publish_fix/pose_array_msg"); + marker_ = _server.getParam(prefix_ + "/publish_fix/marker_msg"); + topic_fix_ = _server.getParam(prefix_ + "/publish_fix/topic"); + + // marker color + if (marker_) + { + try{ + std::cout << "taking user defined colors...\n"; + Eigen::Vector4d col = _server.getParam(prefix_ + "/publish_fix/marker_color"); + std_msgs::ColorRGBA marker_color; + marker_color.r = col(0); + marker_color.g = col(1); + marker_color.b = col(2); + marker_color.a = col(3); + for (auto comp : comp_options_) + { + marker_msgs_[comp] = visualization_msgs::Marker(); + marker_msgs_.at(comp).color = marker_color; + } + } + catch(...) + { + std::cout << "using default colors...\n"; + for (auto comp : comp_options_) + { + marker_msgs_[comp] = visualization_msgs::Marker(); + marker_msgs_.at(comp).color.r = comp[0] == '1' ? 0.8 : (comp[0] == '2' ? 1: 0.2); + marker_msgs_.at(comp).color.g = comp[1] == '1' ? 0.8 : 0.2; + marker_msgs_.at(comp).color.b = comp[2] == '1' ? 0.8 : 0.2; + marker_msgs_.at(comp).color.a = 1; + } + } + } + // last fix for (auto comp : comp_options_) { last_fixes_ok_.emplace(comp, false); @@ -80,6 +73,40 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, } } + // GNSS OPTIONS (see gnss_utils.h) + compute_pos_opt_ = GnssUtils::default_options; + try{compute_pos_opt_.sateph = _server.getParam (prefix_ + "/gnss_options/sateph"); // satellite ephemeris/clock (0:broadcast ephemeris,1:precise ephemeris,2:broadcast + SBAS,3:ephemeris option: broadcast + SSR_APC,4:broadcast + SSR_COM,5: QZSS LEX ephemeris + }catch(...){std::cout << "default sateph" << std::endl;} + try{compute_pos_opt_.ionoopt = _server.getParam (prefix_ + "/gnss_options/ionoopt"); // ionosphere option (0:correction off,1:broadcast mode,2:SBAS model,3:L1/L2 or L1/L5,4:estimation,5:IONEX TEC model,6:QZSS broadcast,7:QZSS LEX ionosphere,8:SLANT TEC mode) + }catch(...){std::cout << "default ionoopt" << std::endl;} + try{compute_pos_opt_.tropopt = _server.getParam (prefix_ + "/gnss_options/tropopt"); // troposphere option: (0:correction off,1:Saastamoinen model,2:SBAS model,3:troposphere option: ZTD estimation,4:ZTD+grad estimation,5:ZTD correction,6:ZTD+grad correction) + }catch(...){std::cout << "default tropopt" << std::endl;} + try{compute_pos_opt_.sbascorr = _server.getParam (prefix_ + "/gnss_options/sbascorr");// SBAS option (1:long term correction,2:fast correction,4:ionosphere correction,8:ranging) + }catch(...){std::cout << "default sbascorr" << std::endl;} + try{compute_pos_opt_.raim = _server.getParam (prefix_ + "/gnss_options/raim"); // RAIM enabled + }catch(...){std::cout << "default raim" << std::endl;} + try{compute_pos_opt_.elmin = D2R * _server.getParam(prefix_ + "/gnss_options/elmin"); // min elevation (degrees) + }catch(...){std::cout << "default elmin" << std::endl;} + try{compute_pos_opt_.maxgdop = _server.getParam(prefix_ + "/gnss_options/maxgdop"); // maxgdop: reject threshold of gdop + }catch(...){std::cout << "default maxgdop" << std::endl;} + + try{compute_pos_opt_.GPS = _server.getParam(prefix_ + "/gnss_options/constellations/GPS"); /* navigation system */ + }catch(...){std::cout << "default GPS" << std::endl;} + try{compute_pos_opt_.SBS = _server.getParam(prefix_ + "/gnss_options/constellations/SBS"); + }catch(...){std::cout << "default SBS" << std::endl;} + try{compute_pos_opt_.GLO = _server.getParam(prefix_ + "/gnss_options/constellations/GLO"); + }catch(...){std::cout << "default GLO" << std::endl;} + try{compute_pos_opt_.GAL = _server.getParam(prefix_ + "/gnss_options/constellations/GAL"); + }catch(...){std::cout << "default GAL" << std::endl;} + try{compute_pos_opt_.QZS = _server.getParam(prefix_ + "/gnss_options/constellations/QZS"); + }catch(...){std::cout << "default QZS" << std::endl;} + try{compute_pos_opt_.CMP = _server.getParam(prefix_ + "/gnss_options/constellations/CMP"); + }catch(...){std::cout << "default CMP" << std::endl;} + try{compute_pos_opt_.IRN = _server.getParam(prefix_ + "/gnss_options/constellations/IRN"); + }catch(...){std::cout << "default IRN" << std::endl;} + try{compute_pos_opt_.LEO = _server.getParam(prefix_ + "/gnss_options/constellations/LEO"); + }catch(...){std::cout << "default LEO" << std::endl;} + // user print ROS_INFO("Waiting for satellites..."); } @@ -104,13 +131,11 @@ void SubscriberGnssReceiver::initialize(ros::NodeHandle& nh, const std::string& { for (auto comp : comp_options_) { - marker_msgs_[comp] = visualization_msgs::Marker(); marker_msgs_.at(comp).header.frame_id = "ENU"; marker_msgs_.at(comp).type = visualization_msgs::Marker::LINE_LIST; marker_msgs_.at(comp).action = visualization_msgs::Marker::ADD; marker_msgs_.at(comp).ns = "trajectory"; marker_msgs_.at(comp).scale.x = 0.1; - marker_msgs_.at(comp).color = marker_color_; marker_msgs_.at(comp).pose.orientation = tf::createQuaternionMsgFromYaw(0); publishers_marker_[comp] = nh.advertise(topic_fix_ + comp + "_marker", 1); @@ -178,7 +203,7 @@ void SubscriberGnssReceiver::publishFixComp() for (auto comp : comp_options_) { - compute_pos_opt_.raim = comp[0] == '1'; + compute_pos_opt_.raim = (comp[0] == '0' ? 0 : (comp[0] == '1' ? 1 : 2)); compute_pos_opt_.sateph = (comp[1] == '0' ? 0 : 2); compute_pos_opt_.ionoopt = (comp[2] == '0' ? 1 : 3); @@ -186,7 +211,6 @@ void SubscriberGnssReceiver::publishFixComp() receiver_->getNavigation(), compute_pos_opt_); - // ECEF-ENU is defined Eigen::Vector3d fix_ENU = R_enu_ecef_ * fix.pos + t_enu_ecef_; @@ -199,8 +223,6 @@ void SubscriberGnssReceiver::publishFixComp() if (fix.success) publishPose(pose_msg, ros::Time::now(), comp); - else - std::cout << "Comp " << comp << " failed: " << fix.msg << std::endl; // store last last_fixes_ok_.at(comp) = fix.success; @@ -223,9 +245,6 @@ void SubscriberGnssReceiver::publishPose(const geometry_msgs::Pose pose, const r marker_msgs_.at(comp).header.stamp = stamp; marker_msgs_.at(comp).points.push_back(last_fixes_pose_.at(comp).position); marker_msgs_.at(comp).points.push_back(pose.position); - marker_msgs_.at(comp).color.r = comp[0] == '1' ? 0.5 : 0; - marker_msgs_.at(comp).color.g = comp[1] == '1' ? 0.5 : 0; - marker_msgs_.at(comp).color.b = comp[2] == '1' ? 0.5 : 0; marker_msgs_.at(comp).ns = comp; publishers_marker_.at(comp).publish(marker_msgs_.at(comp)); -- GitLab From d4fd41b6689056f9a85c828bbc979d9de7b40a8a Mon Sep 17 00:00:00 2001 From: joanvallve Date: Thu, 25 Jun 2020 17:27:23 +0200 Subject: [PATCH 37/86] publisher fix added, not working yet --- include/publisher_fix.h | 55 ++++++++++++++++ src/publisher_fix.cpp | 143 ++++++++++++++++++++++++++++++++++++++++ 2 files changed, 198 insertions(+) create mode 100644 include/publisher_fix.h create mode 100644 src/publisher_fix.cpp diff --git a/include/publisher_fix.h b/include/publisher_fix.h new file mode 100644 index 0000000..3b71f4b --- /dev/null +++ b/include/publisher_fix.h @@ -0,0 +1,55 @@ +#ifndef PUBLISHER_FIX_H +#define PUBLISHER_FIX_H + +/************************** + * WOLF includes * + **************************/ +#include "core/problem/problem.h" + +#include "publisher.h" + +/************************** + * ROS includes * + **************************/ +#include +#include +#include +#include + +namespace wolf +{ + +class PublishFix: public Publisher +{ + geometry_msgs::PoseWithCovarianceStamped pose_msg_; + SensorBasePtr sensor_; + std::string frame_id_, map_frame_id_; + + ros::Publisher pub_pose_; + + public: + PublishFix(const std::string& _unique_name, + const ParamsServer& _server, + const ProblemPtr _problem); + WOLF_PUBLISHER_CREATE(PublishFix); + + virtual ~PublishFix(){}; + + void initialize(ros::NodeHandle &nh, const std::string& topic) override; + + void publishDerived() override; + + void publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp); + + protected: + + bool listenTf(); + Eigen::Quaterniond q_frame_; + Eigen::Vector3d t_frame_; + tf::TransformListener tfl_; +}; + +WOLF_REGISTER_PUBLISHER(PublishFix) +} + +#endif diff --git a/src/publisher_fix.cpp b/src/publisher_fix.cpp new file mode 100644 index 0000000..5a3822f --- /dev/null +++ b/src/publisher_fix.cpp @@ -0,0 +1,143 @@ +#include "publisher_fix.h" + +/************************** + * ROS includes * + **************************/ +#include +#include "tf/transform_datatypes.h" +#include "tf_conversions/tf_eigen.h" + +namespace wolf +{ + +PublishFix::PublishFix(const std::string& _unique_name, + const ParamsServer& _server, + const ProblemPtr _problem) : + Publisher(_unique_name, _server, _problem) +{ + sensor_ = _problem->getSensor(_server.getParam(prefix_ + "/sensor")); + frame_id_ = _server.getParam(prefix_ + "/frame_id"); +} + +void PublishFix::initialize(ros::NodeHandle& nh, const std::string& topic) +{ + nh.param("map_frame_id", map_frame_id_, "map"); + + // initialize msg and publisher + pose_msg_.header.frame_id = frame_id_; + + pub_pose_ = nh.advertise(topic, 1); +} + +void PublishFix::publishDerived() +{ + VectorComposite current_state = problem_->getState("PO"); + TimeStamp loc_ts = problem_->getTimeStamp(); + + // state not ready + if (current_state.count('P') == 0 or + current_state.count('O') == 0 or + loc_ts == TimeStamp(0)) + { + return; + } + + + // fill vector and quaternion + Eigen::Vector3d p = Eigen::Vector3d::Zero(); + Eigen::Quaterniond q; + + // 2D + if (problem_->getDim() == 2) + { + if (extrinsics_) + { + p.head(2) = current_state['P'] + Eigen::Rotation2Dd(current_state['O'](0)) * sensor_->getP()->getState().head(2); + if (sensor_->getO()) + q = Eigen::Quaterniond(Eigen::AngleAxisd(current_state['O'](0) + sensor_->getO()->getState()(0), + Eigen::Vector3d::UnitZ())); + else + q = Eigen::Quaterniond(Eigen::AngleAxisd(current_state['O'](0), + Eigen::Vector3d::UnitZ())); + } + else + { + p.head(2) = current_state['P']; + q = Eigen::Quaterniond(Eigen::AngleAxisd(current_state['O'](0), Eigen::Vector3d::UnitZ())); + } + } + // 3D + else + { + if (extrinsics_) + { + p = current_state['P'] + Eigen::Quaterniond(Eigen::Vector4d(current_state['O'])) * sensor_->getP()->getState(); + if (sensor_->getO()) + q = Eigen::Quaterniond(Eigen::Vector4d(current_state['O'])) * Eigen::Quaterniond(Eigen::Vector4d(sensor_->getO()->getState())); + else + q = Eigen::Quaterniond(Eigen::Vector4d(current_state['O'])); + } + else + { + p = current_state['P']; + q = Eigen::Quaterniond(Eigen::Vector4d(current_state['O'])); + } + } + + // Change frame + if (frame_id_ != map_frame_id_ and listenTf()) + { + p = t_frame_ + q_frame_ * p; + q = q_frame_ * q; + } + + // Fill Pose msg + geometry_msgs::Pose pose_msg; + pose_msg.position.x = p(0); + pose_msg.position.y = p(1); + pose_msg.position.z = p(2); + + pose_msg.orientation.x = q.x(); + pose_msg.orientation.y = q.y(); + pose_msg.orientation.z = q.z(); + pose_msg.orientation.w = q.w(); + publishPose(pose_msg, ros::Time(loc_ts.getSeconds(), loc_ts.getNanoSeconds())); +} + +void PublishFix::publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp) +{ + // fill msgs and publish + if (pose_array_) + { + pose_array_msg_.header.stamp = stamp; + pose_array_msg_.poses.push_back(pose); + + pub_pose_array_.publish(pose_array_msg_); + } + if (marker_) + { + marker_msg_.header.stamp = stamp; + marker_msg_.points.push_back(pose.position); + + pub_marker_.publish(marker_msg_); + } +} + +bool PublishFix::listenTf() +{ + tf::StampedTransform T; + if ( tfl_.waitForTransform(frame_id_, map_frame_id_, ros::Time(0), ros::Duration(0.01)) ) + { + tfl_.lookupTransform(frame_id_, map_frame_id_, ros::Time(0), T); + + Eigen::Matrix3d R; + tf::matrixTFToEigen(T.getBasis(), R); + tf::vectorTFToEigen(T.getOrigin(), t_frame_); + q_frame_ = Eigen::Quaterniond(R); + + return true; + } + return false; +} + +} -- GitLab From a97e76554c4572cd9357f4e7e69f4bc851a06a49 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Sun, 28 Jun 2020 00:38:41 +0200 Subject: [PATCH 38/86] publisher of protection levels marker --- CMakeLists.txt | 3 +- include/publisher_gnss_accuracy.h | 43 ++++++++++++ src/publisher_gnss_accuracy.cpp | 111 ++++++++++++++++++++++++++++++ 3 files changed, 156 insertions(+), 1 deletion(-) create mode 100644 include/publisher_gnss_accuracy.h create mode 100644 src/publisher_gnss_accuracy.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 79f3a08..d558112 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -137,7 +137,8 @@ include_directories( # src/${PROJECT_NAME}/wolf_ros.cpp # ) add_library(publisher_${PROJECT_NAME} - src/publisher_gnss_tf.cpp) + src/publisher_gnss_tf.cpp + src/publisher_gnss_accuracy.cpp) add_library(subscriber_${PROJECT_NAME} src/subscriber_gnss.cpp src/subscriber_gnss_fix.cpp diff --git a/include/publisher_gnss_accuracy.h b/include/publisher_gnss_accuracy.h new file mode 100644 index 0000000..598565d --- /dev/null +++ b/include/publisher_gnss_accuracy.h @@ -0,0 +1,43 @@ +#ifndef PUBLISHER_GNSS_ACCURACY_H +#define PUBLISHER_GNSS_ACCURACY_H + +/************************** + * WOLF includes * + **************************/ +#include "core/problem/problem.h" + +#include "publisher.h" + +/************************** + * ROS includes * + **************************/ +#include +#include + +namespace wolf +{ + +class PublisherGnssAccuracy: public Publisher +{ + visualization_msgs::Marker PL_marker_msg_; + std_msgs::ColorRGBA marker_color_; + SensorBasePtr sensor_; + double k_H_, k_V_; + + public: + PublisherGnssAccuracy(const std::string& _unique_name, + const ParamsServer& _server, + const ProblemPtr _problem); + WOLF_PUBLISHER_CREATE(PublisherGnssAccuracy); + + virtual ~PublisherGnssAccuracy(){}; + + void initialize(ros::NodeHandle &nh, const std::string& topic) override; + + void publishDerived() override; +}; + +WOLF_REGISTER_PUBLISHER(PublisherGnssAccuracy) +} + +#endif diff --git a/src/publisher_gnss_accuracy.cpp b/src/publisher_gnss_accuracy.cpp new file mode 100644 index 0000000..57ca412 --- /dev/null +++ b/src/publisher_gnss_accuracy.cpp @@ -0,0 +1,111 @@ +#include "publisher_gnss_accuracy.h" + +/************************** + * ROS includes * + **************************/ +#include +#include "tf/transform_datatypes.h" + +namespace wolf +{ + +PublisherGnssAccuracy::PublisherGnssAccuracy(const std::string& _unique_name, + const ParamsServer& _server, + const ProblemPtr _problem) : + Publisher(_unique_name, _server, _problem) +{ + Eigen::Vector4d col = _server.getParam(prefix_ + "/marker_color"); + marker_color_.r = col(0); + marker_color_.g = col(1); + marker_color_.b = col(2); + marker_color_.a = col(3); + sensor_ = _problem->getSensor(_server.getParam(prefix_ + "/sensor")); + k_H_ = _server.getParam(prefix_ + "/k_H"); + k_V_ = _server.getParam(prefix_ + "/k_V"); +} + +void PublisherGnssAccuracy::initialize(ros::NodeHandle& nh, const std::string& topic) +{ + nh.param("map_frame_id", PL_marker_msg_.header.frame_id, "map"); + + PL_marker_msg_.type = visualization_msgs::Marker::CYLINDER; + PL_marker_msg_.action = visualization_msgs::Marker::ADD; + PL_marker_msg_.ns = "PL"; + PL_marker_msg_.color = marker_color_; + PL_marker_msg_.pose.orientation = tf::createQuaternionMsgFromYaw(0); + + publisher_ = nh.advertise(topic, 1); +} + +void PublisherGnssAccuracy::publishDerived() +{ + // CURRENT POSITION + VectorComposite current_state = problem_->getState("PO"); + TimeStamp loc_ts = problem_->getTimeStamp(); + + // state not ready + if (current_state.count('P') == 0 or + current_state.count('O') == 0 or + not loc_ts.ok()) + { + return; + } + + // fill position of GNSS antenna + Eigen::Vector3d p = Eigen::Vector3d::Zero(); + // 2D + if (problem_->getDim() == 2) + p.head(2) = current_state['P'] + Eigen::Rotation2Dd(current_state['O'](0)) * sensor_->getP()->getState().head(2); + // 3D + else + p = current_state['P'] + Eigen::Quaterniond(Eigen::Vector4d(current_state['O'])) * sensor_->getP()->getState(); + + // COVARIANCE + bool new_cov = false; + Eigen::MatrixXd cov(3,3); + // 2D + if (problem_->getDim() == 2) + throw std::runtime_error("not implemented"); + // 3D + else + { + new_cov = problem_->getCovarianceBlock(problem_->getLastKeyFrame()->getP(), + problem_->getLastKeyFrame()->getP(), + cov, 0, 0); + WOLF_WARN_COND(not new_cov, "Last KF covariance could not be recovered, using the previous one"); + } + + // PROTECTION LEVELS + double HPL, VPL; + if (new_cov) + { + // Horizontal + Eigen::SelfAdjointEigenSolver es(cov.topLeftCorner<2,2>(), Eigen::EigenvaluesOnly); + + if (es.info() == Eigen::Success) + HPL = k_H_ * sqrt(es.eigenvalues().maxCoeff()); + else + new_cov = false; + + WOLF_WARN_COND(not new_cov, "eigen decomposition failed! Cov horizontal:\n", cov.topLeftCorner<2,2>()); + + // Vertical + VPL = k_V_ * sqrt(cov(2,2)); + } + + // CYLINDER MARKER + PL_marker_msg_.header.stamp = ros::Time(loc_ts.getSeconds(), loc_ts.getNanoSeconds()); + PL_marker_msg_.pose.position.x = p(0); + PL_marker_msg_.pose.position.y = p(1); + PL_marker_msg_.pose.position.z = p(2); + + if (new_cov) + { + PL_marker_msg_.scale.x = HPL; + PL_marker_msg_.scale.y = HPL; + PL_marker_msg_.scale.z = VPL; + } + publisher_.publish(PL_marker_msg_); +} + +} -- GitLab From 2022cb10f885c3f461157166fdd1a1df73da14bc Mon Sep 17 00:00:00 2001 From: joanvallve Date: Thu, 2 Jul 2020 16:09:42 +0200 Subject: [PATCH 39/86] subscribers changes --- include/subscriber_gnss_fix_publisher_ecef.h | 6 ++++-- include/subscriber_gnss_receiver.h | 5 +++-- src/subscriber_gnss_fix_publisher_ecef.cpp | 14 ++++++++++++++ src/subscriber_gnss_receiver.cpp | 18 ++++++++++++++++++ 4 files changed, 39 insertions(+), 4 deletions(-) diff --git a/include/subscriber_gnss_fix_publisher_ecef.h b/include/subscriber_gnss_fix_publisher_ecef.h index 7881408..73588e5 100644 --- a/include/subscriber_gnss_fix_publisher_ecef.h +++ b/include/subscriber_gnss_fix_publisher_ecef.h @@ -7,6 +7,7 @@ #include #include #include +#include #include #include @@ -37,11 +38,12 @@ class SubscriberGnssFixPublisherEcef : public Subscriber // publisher ros::Time last_publish_stamp_; double period_; - bool pose_array_, marker_; + bool pose_array_, pose_, marker_; geometry_msgs::PoseArray pose_array_msg_; + geometry_msgs::PoseStamped pose_msg_; visualization_msgs::Marker marker_msg_; std_msgs::ColorRGBA marker_color_; - ros::Publisher pub_pose_array_, pub_marker_; + ros::Publisher pub_pose_array_, pub_marker_, pub_pose_; public: // Constructor diff --git a/include/subscriber_gnss_receiver.h b/include/subscriber_gnss_receiver.h index 3ae3037..b146b6d 100644 --- a/include/subscriber_gnss_receiver.h +++ b/include/subscriber_gnss_receiver.h @@ -60,16 +60,17 @@ class SubscriberGnssReceiver : public Subscriber // Publish fix void publishFixComp(); void publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp, const std::string& comp); - bool publish_fix_, pose_array_, marker_; + bool publish_fix_, pose_, pose_array_, marker_; std::string topic_fix_; GnssUtils::Options compute_pos_opt_; // comparative + std::map pose_msgs_; std::map pose_array_msgs_; std::map marker_msgs_; std::map last_fixes_ok_; std::map last_fixes_pose_; - std::map publishers_pose_array_, publishers_marker_; + std::map publishers_pose_, publishers_pose_array_, publishers_marker_; std::vector comp_options_; //TF diff --git a/src/subscriber_gnss_fix_publisher_ecef.cpp b/src/subscriber_gnss_fix_publisher_ecef.cpp index 2240096..d038bc0 100644 --- a/src/subscriber_gnss_fix_publisher_ecef.cpp +++ b/src/subscriber_gnss_fix_publisher_ecef.cpp @@ -14,6 +14,7 @@ SubscriberGnssFixPublisherEcef::SubscriberGnssFixPublisherEcef(const std::string , ENU_defined_(false) { period_ = _server.getParam(prefix_ + "/period"); + pose_ = _server.getParam(prefix_ + "/pose_msg"); pose_array_ = _server.getParam(prefix_ + "/pose_array_msg"); marker_ = _server.getParam(prefix_ + "/marker_msg"); if (marker_) @@ -32,6 +33,12 @@ void SubscriberGnssFixPublisherEcef::initialize(ros::NodeHandle& nh, const std:: sub_ = nh.subscribe(topic, 1, &SubscriberGnssFixPublisherEcef::callback, this); // initialize msg and publisher + if (pose_) + { + pose_msg_.header.frame_id = "ENU"; + + pub_pose_ = nh.advertise(topic + "_ENU_pose", 1); + } if (pose_array_) { pose_array_msg_.header.frame_id = "ENU"; @@ -103,6 +110,13 @@ bool SubscriberGnssFixPublisherEcef::listenTf() void SubscriberGnssFixPublisherEcef::publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp) { // fill msgs and publish + if (pose_) + { + pose_msg_.header.stamp = stamp; + pose_msg_.pose = pose; + + pub_pose_.publish(pose_msg_); + } if (pose_array_) { pose_array_msg_.header.stamp = stamp; diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index 6f46c05..7050dd0 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -30,6 +30,7 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, comp_options_.push_back("200"); // params + pose_ = _server.getParam(prefix_ + "/publish_fix/pose_msg"); pose_array_ = _server.getParam(prefix_ + "/publish_fix/pose_array_msg"); marker_ = _server.getParam(prefix_ + "/publish_fix/marker_msg"); topic_fix_ = _server.getParam(prefix_ + "/publish_fix/topic"); @@ -117,6 +118,16 @@ void SubscriberGnssReceiver::initialize(ros::NodeHandle& nh, const std::string& if (publish_fix_) { // initialize msg and publisher + if (pose_) + { + for (auto comp : comp_options_) + { + pose_msgs_[comp] = geometry_msgs::PoseStamped(); + pose_msgs_.at(comp).header.frame_id = "ENU"; + + publishers_pose_[comp] = nh.advertise(topic_fix_ + comp + "_pose", 1); + } + } if (pose_array_) { for (auto comp : comp_options_) @@ -233,6 +244,13 @@ void SubscriberGnssReceiver::publishFixComp() void SubscriberGnssReceiver::publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp, const std::string& comp) { // fill msgs and publish + if (pose_) + { + pose_msgs_.at(comp).header.stamp = stamp; + pose_msgs_.at(comp).pose = pose; + + publishers_pose_.at(comp).publish(pose_msgs_.at(comp)); + } if (pose_array_) { pose_array_msgs_.at(comp).header.stamp = stamp; -- GitLab From 0d4bcf647015bfb989fd0475b217dba8a3478707 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Tue, 7 Jul 2020 17:12:26 +0200 Subject: [PATCH 40/86] WIP --- include/subscriber_gnss_receiver.h | 3 +- src/publisher_gnss_accuracy.cpp | 2 +- src/subscriber_gnss_receiver.cpp | 80 ++++++++++++++++++++++-------- 3 files changed, 62 insertions(+), 23 deletions(-) diff --git a/include/subscriber_gnss_receiver.h b/include/subscriber_gnss_receiver.h index b146b6d..0700684 100644 --- a/include/subscriber_gnss_receiver.h +++ b/include/subscriber_gnss_receiver.h @@ -59,7 +59,8 @@ class SubscriberGnssReceiver : public Subscriber // Publish fix void publishFixComp(); - void publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp, const std::string& comp); + void fillMsgs(const geometry_msgs::Pose pose, const std::string& comp); + void publish(const ros::Time& stamp, const std::string& comp); bool publish_fix_, pose_, pose_array_, marker_; std::string topic_fix_; GnssUtils::Options compute_pos_opt_; diff --git a/src/publisher_gnss_accuracy.cpp b/src/publisher_gnss_accuracy.cpp index 57ca412..798b5cf 100644 --- a/src/publisher_gnss_accuracy.cpp +++ b/src/publisher_gnss_accuracy.cpp @@ -72,7 +72,7 @@ void PublisherGnssAccuracy::publishDerived() new_cov = problem_->getCovarianceBlock(problem_->getLastKeyFrame()->getP(), problem_->getLastKeyFrame()->getP(), cov, 0, 0); - WOLF_WARN_COND(not new_cov, "Last KF covariance could not be recovered, using the previous one"); + WOLF_DEBUG_COND(not new_cov, "Last KF covariance could not be recovered, using the previous one"); } // PROTECTION LEVELS diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index 7050dd0..255c4d1 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -27,7 +27,6 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, comp_options_.push_back("101"); comp_options_.push_back("110"); comp_options_.push_back("111"); - comp_options_.push_back("200"); // params pose_ = _server.getParam(prefix_ + "/publish_fix/pose_msg"); @@ -58,9 +57,9 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, for (auto comp : comp_options_) { marker_msgs_[comp] = visualization_msgs::Marker(); - marker_msgs_.at(comp).color.r = comp[0] == '1' ? 0.8 : (comp[0] == '2' ? 1: 0.2); - marker_msgs_.at(comp).color.g = comp[1] == '1' ? 0.8 : 0.2; - marker_msgs_.at(comp).color.b = comp[2] == '1' ? 0.8 : 0.2; + marker_msgs_.at(comp).color.r = comp[0] == '1' ? 0.8 : 0.4; + marker_msgs_.at(comp).color.g = comp[1] == '1' ? 0.8 : 0.4; + marker_msgs_.at(comp).color.b = comp[2] == '1' ? 0.8 : 0.4; marker_msgs_.at(comp).color.a = 1; } } @@ -145,7 +144,7 @@ void SubscriberGnssReceiver::initialize(ros::NodeHandle& nh, const std::string& marker_msgs_.at(comp).header.frame_id = "ENU"; marker_msgs_.at(comp).type = visualization_msgs::Marker::LINE_LIST; marker_msgs_.at(comp).action = visualization_msgs::Marker::ADD; - marker_msgs_.at(comp).ns = "trajectory"; + marker_msgs_.at(comp).ns = comp; marker_msgs_.at(comp).scale.x = 0.1; marker_msgs_.at(comp).pose.orientation = tf::createQuaternionMsgFromYaw(0); @@ -196,7 +195,7 @@ void SubscriberGnssReceiver::createCaptureAndProcess() } // publish available - sats_available_ = fix.success; + //sats_available_ = fix.success; std_msgs::Bool msg; msg.data = sats_available_; pub_available_.publish(msg); @@ -214,13 +213,43 @@ void SubscriberGnssReceiver::publishFixComp() for (auto comp : comp_options_) { - compute_pos_opt_.raim = (comp[0] == '0' ? 0 : (comp[0] == '1' ? 1 : 2)); - compute_pos_opt_.sateph = (comp[1] == '0' ? 0 : 2); - compute_pos_opt_.ionoopt = (comp[2] == '0' ? 1 : 3); + // RAIM + if (comp[0] == '0') + compute_pos_opt_.raim = 0; + else + compute_pos_opt_.raim = 1; + + // SBAS + if (comp[1] == '0') + { + compute_pos_opt_.sateph = 0; //eph broadcasted + compute_pos_opt_.ionoopt = 1; //iono broadcasted + compute_pos_opt_.tropopt = 1; //trop broadcasted + compute_pos_opt_.sbascorr = 0; //sbas corrections + } + else + { + compute_pos_opt_.sateph = 2; //eph sbas + compute_pos_opt_.ionoopt = 2; //iono sbas + compute_pos_opt_.tropopt = 2; //trop broadcasted + compute_pos_opt_.sbascorr = 15; //sbas corrections + } + // IONOFREE combination + if (comp[2] == '1') + { + compute_pos_opt_.ionoopt = 3; //iono-free combination + if (comp[1] == '1') + compute_pos_opt_.sbascorr = 11; //sbas corrections without iono + } + + //std::cout << "//////////// Computing fix comp = " << comp << std::endl; auto fix = GnssUtils::computePos(receiver_->getObservations(), receiver_->getNavigation(), compute_pos_opt_); + WOLF_INFO_COND(comp == "010" and not fix.success, "computePos failed with msg: ", fix.msg); + + //std::cout << "//////////// Computed" << std::endl; // ECEF-ENU is defined Eigen::Vector3d fix_ENU = R_enu_ecef_ * fix.pos + t_enu_ecef_; @@ -233,7 +262,9 @@ void SubscriberGnssReceiver::publishFixComp() pose_msg.orientation = tf::createQuaternionMsgFromRollPitchYaw(0,M_PI/2,0); if (fix.success) - publishPose(pose_msg, ros::Time::now(), comp); + fillMsgs(pose_msg, comp); + + publish(ros::Time::now(), comp); // store last last_fixes_ok_.at(comp) = fix.success; @@ -241,30 +272,37 @@ void SubscriberGnssReceiver::publishFixComp() } } -void SubscriberGnssReceiver::publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp, const std::string& comp) +void SubscriberGnssReceiver::fillMsgs(const geometry_msgs::Pose pose, const std::string& comp) { - // fill msgs and publish + // fill msgs if (pose_) - { - pose_msgs_.at(comp).header.stamp = stamp; pose_msgs_.at(comp).pose = pose; + if (pose_array_) + pose_array_msgs_.at(comp).poses.push_back(pose); + + if (marker_ and last_fixes_ok_.at(comp)) + { + marker_msgs_.at(comp).points.push_back(last_fixes_pose_.at(comp).position); + marker_msgs_.at(comp).points.push_back(pose.position); + } +} + +void SubscriberGnssReceiver::publish(const ros::Time& stamp, const std::string& comp) +{ + if (pose_) + { + pose_msgs_.at(comp).header.stamp = stamp; publishers_pose_.at(comp).publish(pose_msgs_.at(comp)); } if (pose_array_) { pose_array_msgs_.at(comp).header.stamp = stamp; - pose_array_msgs_.at(comp).poses.push_back(pose); - publishers_pose_array_.at(comp).publish(pose_array_msgs_.at(comp)); } - if (marker_ and last_fixes_ok_.at(comp)) + if (marker_) { marker_msgs_.at(comp).header.stamp = stamp; - marker_msgs_.at(comp).points.push_back(last_fixes_pose_.at(comp).position); - marker_msgs_.at(comp).points.push_back(pose.position); - marker_msgs_.at(comp).ns = comp; - publishers_marker_.at(comp).publish(marker_msgs_.at(comp)); } } -- GitLab From 4154c4b92678a46df70d366188bc21bf701d9613 Mon Sep 17 00:00:00 2001 From: jcasals Date: Thu, 16 Jul 2020 09:06:03 +0200 Subject: [PATCH 41/86] Adapt to rename wolf -> wolfcore --- CMakeLists.txt | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index d558112..f41d6b4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -21,7 +21,7 @@ find_package(catkin REQUIRED COMPONENTS ) ## System dependencies are found with CMake's conventions -find_package(wolf REQUIRED) +find_package(wolfcore REQUIRED) find_package(wolfgnss REQUIRED) ## Uncomment this if the package has a setup.py. This macro ensures @@ -121,11 +121,11 @@ catkin_package( ## Specify additional locations of header files ## Your package locations should be listed before other locations -message("Wolf include path: ${wolf_INCLUDE_DIR}") +message("Wolf include path: ${wolfcore_INCLUDE_DIRS}") include_directories( include ${EIGEN_INCLUDE_DIRS} - ${wolf_INCLUDE_DIRS} + ${wolfcore_INCLUDE_DIRS} ${wolfgnss_INCLUDE_DIRS} ${gnss_utils_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS} @@ -174,7 +174,7 @@ add_dependencies(subscriber_${PROJECT_NAME} novatel_oem7_msgs_generate_messages_ ## Specify libraries to link a library or executable target against target_link_libraries(subscriber_${PROJECT_NAME} - ${wolf_LIBRARIES} + ${wolfcore_LIBRARIES} ${wolfgnss_LIBRARIES} ${iri_gnss_msgs_LIBRARIES} ${catkin_LIBRARIES} -- GitLab From 696c9922b187af188a913d8afcb0f8d7c6f754c9 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Fri, 17 Jul 2020 12:45:57 +0200 Subject: [PATCH 42/86] bug fixed --- src/subscriber_gnss_receiver.cpp | 47 ++++++++++++++++++-------------- 1 file changed, 26 insertions(+), 21 deletions(-) diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index 255c4d1..a138bbb 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -18,15 +18,15 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, publish_fix_ = _server.getParam(prefix_ + "/publish_fix/enabled"); if (publish_fix_) { - // comparation of GNSS options - comp_options_.push_back("000"); - comp_options_.push_back("001"); + // comparation of GNSS options RAIM-SBAS-IONO + //comp_options_.push_back("000"); + //comp_options_.push_back("001"); comp_options_.push_back("010"); - comp_options_.push_back("011"); - comp_options_.push_back("100"); - comp_options_.push_back("101"); - comp_options_.push_back("110"); - comp_options_.push_back("111"); + //comp_options_.push_back("011"); + //comp_options_.push_back("100"); + //comp_options_.push_back("101"); + //comp_options_.push_back("110"); + //comp_options_.push_back("111"); // params pose_ = _server.getParam(prefix_ + "/publish_fix/pose_msg"); @@ -160,9 +160,11 @@ void SubscriberGnssReceiver::createCaptureAndProcess() // compute fix if publishing or not sats_available if (not sats_available_ or publish_fix_) + { fix = GnssUtils::computePos(receiver_->getObservations(), receiver_->getNavigation(), compute_pos_opt_); + } // if (last time) satellites were not available: check if they are if (not sats_available_) @@ -211,42 +213,45 @@ void SubscriberGnssReceiver::publishFixComp() if (not ENU_defined_ and not listenTf()) return; + GnssUtils::Options comp_pos_opt = compute_pos_opt_; + for (auto comp : comp_options_) { // RAIM if (comp[0] == '0') - compute_pos_opt_.raim = 0; + comp_pos_opt.raim = 0; else - compute_pos_opt_.raim = 1; + comp_pos_opt.raim = 1; // SBAS if (comp[1] == '0') { - compute_pos_opt_.sateph = 0; //eph broadcasted - compute_pos_opt_.ionoopt = 1; //iono broadcasted - compute_pos_opt_.tropopt = 1; //trop broadcasted - compute_pos_opt_.sbascorr = 0; //sbas corrections + comp_pos_opt.sateph = 0; //eph broadcasted + comp_pos_opt.ionoopt = 1; //iono broadcasted + comp_pos_opt.tropopt = 1; //trop broadcasted + comp_pos_opt.sbascorr = 0; //sbas corrections } else { - compute_pos_opt_.sateph = 2; //eph sbas - compute_pos_opt_.ionoopt = 2; //iono sbas - compute_pos_opt_.tropopt = 2; //trop broadcasted - compute_pos_opt_.sbascorr = 15; //sbas corrections + comp_pos_opt.GAL = false; + comp_pos_opt.sateph = 2; //eph sbas + comp_pos_opt.ionoopt = 0;//2; //iono sbas + comp_pos_opt.tropopt = 0;//2; //trop broadcasted + comp_pos_opt.sbascorr = 15; //sbas corrections } // IONOFREE combination if (comp[2] == '1') { - compute_pos_opt_.ionoopt = 3; //iono-free combination + comp_pos_opt.ionoopt = 3; //iono-free combination if (comp[1] == '1') - compute_pos_opt_.sbascorr = 11; //sbas corrections without iono + comp_pos_opt.sbascorr = 11; //sbas corrections without iono } //std::cout << "//////////// Computing fix comp = " << comp << std::endl; auto fix = GnssUtils::computePos(receiver_->getObservations(), receiver_->getNavigation(), - compute_pos_opt_); + comp_pos_opt); WOLF_INFO_COND(comp == "010" and not fix.success, "computePos failed with msg: ", fix.msg); //std::cout << "//////////// Computed" << std::endl; -- GitLab From 9fb21099490ac8b90c5d893a9677fcba14e45363 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Sat, 18 Jul 2020 13:01:09 +0200 Subject: [PATCH 43/86] receiver work --- src/subscriber_gnss_receiver.cpp | 67 ++++++++++++++++++++++---------- 1 file changed, 46 insertions(+), 21 deletions(-) diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index a138bbb..028cd9b 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -18,11 +18,24 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, publish_fix_ = _server.getParam(prefix_ + "/publish_fix/enabled"); if (publish_fix_) { - // comparation of GNSS options RAIM-SBAS-IONO + /* comparation of GNSS options: + * 3 numbers: RAIM - EPH - IONO/TROPO + * RAIM: 0-1 + * EPH: + * 0: broadcasted + * 1: SBAS + * IONO/TROPO: + * 0: broadcasted + * 1: SBAS + * 2: iono-free (tropo broadcasted) + */ + //comp_options_.push_back("000"); //comp_options_.push_back("001"); + //comp_options_.push_back("002"); comp_options_.push_back("010"); //comp_options_.push_back("011"); + //comp_options_.push_back("012"); //comp_options_.push_back("100"); //comp_options_.push_back("101"); //comp_options_.push_back("110"); @@ -53,14 +66,24 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, } catch(...) { + Eigen::MatrixXd colors(7,4); + colors << 1, 1, 1, 1, + 1, 1, 0, 1, + 1, 0, 1, 1, + 0, 1, 1, 1, + .5,.5,1, 1, + .5,1, .5,1, + 1,.5,.5, 1; + std::cout << "using default colors...\n"; - for (auto comp : comp_options_) + for (auto id_comp = 0; id_comp < comp_options_.size(); id_comp++) { + auto comp = comp_options_[id_comp]; marker_msgs_[comp] = visualization_msgs::Marker(); - marker_msgs_.at(comp).color.r = comp[0] == '1' ? 0.8 : 0.4; - marker_msgs_.at(comp).color.g = comp[1] == '1' ? 0.8 : 0.4; - marker_msgs_.at(comp).color.b = comp[2] == '1' ? 0.8 : 0.4; - marker_msgs_.at(comp).color.a = 1; + marker_msgs_.at(comp).color.r = colors(id_comp,0); + marker_msgs_.at(comp).color.g = colors(id_comp,1); + marker_msgs_.at(comp).color.b = colors(id_comp,2); + marker_msgs_.at(comp).color.a = colors(id_comp,3);; } } } @@ -217,36 +240,38 @@ void SubscriberGnssReceiver::publishFixComp() for (auto comp : comp_options_) { + comp_pos_opt.sbascorr = 15; //sbas corrections + // RAIM if (comp[0] == '0') comp_pos_opt.raim = 0; else comp_pos_opt.raim = 1; - // SBAS + // EPHEMERIS + // broadcasted if (comp[1] == '0') - { - comp_pos_opt.sateph = 0; //eph broadcasted - comp_pos_opt.ionoopt = 1; //iono broadcasted - comp_pos_opt.tropopt = 1; //trop broadcasted - comp_pos_opt.sbascorr = 0; //sbas corrections - } + comp_pos_opt.sateph = 0; + // sbas else { comp_pos_opt.GAL = false; - comp_pos_opt.sateph = 2; //eph sbas - comp_pos_opt.ionoopt = 0;//2; //iono sbas - comp_pos_opt.tropopt = 0;//2; //trop broadcasted - comp_pos_opt.sbascorr = 15; //sbas corrections + comp_pos_opt.sateph = 2; } - // IONOFREE combination + // IONO/TROPO + // broadcasted (default '0') + comp_pos_opt.ionoopt = 1; + comp_pos_opt.tropopt = 1; + // sbas corrections if (comp[2] == '1') { - comp_pos_opt.ionoopt = 3; //iono-free combination - if (comp[1] == '1') - comp_pos_opt.sbascorr = 11; //sbas corrections without iono + comp_pos_opt.ionoopt = 2; + comp_pos_opt.tropopt = 2; } + // iono free + else if (comp[2] == '2') + comp_pos_opt.ionoopt = 3; //std::cout << "//////////// Computing fix comp = " << comp << std::endl; auto fix = GnssUtils::computePos(receiver_->getObservations(), -- GitLab From 27d754c0397efd1cf85e7fd6b38c1599fa95a4b0 Mon Sep 17 00:00:00 2001 From: jcasals Date: Tue, 21 Jul 2020 09:45:20 +0200 Subject: [PATCH 44/86] getLastKeyFrame -> getLastFrame --- src/publisher_gnss_accuracy.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/publisher_gnss_accuracy.cpp b/src/publisher_gnss_accuracy.cpp index 798b5cf..6b4a625 100644 --- a/src/publisher_gnss_accuracy.cpp +++ b/src/publisher_gnss_accuracy.cpp @@ -69,8 +69,8 @@ void PublisherGnssAccuracy::publishDerived() // 3D else { - new_cov = problem_->getCovarianceBlock(problem_->getLastKeyFrame()->getP(), - problem_->getLastKeyFrame()->getP(), + new_cov = problem_->getCovarianceBlock(problem_->getLastFrame()->getP(), + problem_->getLastFrame()->getP(), cov, 0, 0); WOLF_DEBUG_COND(not new_cov, "Last KF covariance could not be recovered, using the previous one"); } -- GitLab From f57bad9f5313fa874214803937cba00d19a6fe41 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Fri, 24 Jul 2020 13:02:21 +0200 Subject: [PATCH 45/86] all configs --- src/subscriber_gnss_receiver.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index 028cd9b..c34f022 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -30,12 +30,12 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, * 2: iono-free (tropo broadcasted) */ - //comp_options_.push_back("000"); - //comp_options_.push_back("001"); - //comp_options_.push_back("002"); + comp_options_.push_back("000"); + comp_options_.push_back("001"); + comp_options_.push_back("002"); comp_options_.push_back("010"); - //comp_options_.push_back("011"); - //comp_options_.push_back("012"); + comp_options_.push_back("011"); + comp_options_.push_back("012"); //comp_options_.push_back("100"); //comp_options_.push_back("101"); //comp_options_.push_back("110"); -- GitLab From e2744003ad774daf4ef6fbff63f513b888640cdd Mon Sep 17 00:00:00 2001 From: joanvallve Date: Mon, 7 Sep 2020 22:58:09 +0200 Subject: [PATCH 46/86] minor --- src/subscriber_gnss_receiver.cpp | 29 ++++++++++++++++++++--------- 1 file changed, 20 insertions(+), 9 deletions(-) diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index c34f022..d0e85de 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -36,6 +36,12 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, comp_options_.push_back("010"); comp_options_.push_back("011"); comp_options_.push_back("012"); + comp_options_.push_back("100"); + comp_options_.push_back("101"); + comp_options_.push_back("102"); + comp_options_.push_back("110"); + comp_options_.push_back("111"); + comp_options_.push_back("112"); //comp_options_.push_back("100"); //comp_options_.push_back("101"); //comp_options_.push_back("110"); @@ -66,14 +72,19 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, } catch(...) { - Eigen::MatrixXd colors(7,4); - colors << 1, 1, 1, 1, - 1, 1, 0, 1, - 1, 0, 1, 1, - 0, 1, 1, 1, - .5,.5,1, 1, - .5,1, .5,1, - 1,.5,.5, 1; + Eigen::MatrixXd colors(12,4); + colors << 1, 1, 1, 1, + 1, 1, 0, 1, + 1, 0, 1, 1, + 0, 1, 1, 1, + .5, .5, 1, 1, + .5, 1, .5, 1, + 1, .5, .5, 1, + .5, .5, .5, 1, + 0, .5, .5, 1, + .5, .5, 0, 1, + .5, 0, .5, 1, + 0, 0, .5, 1; std::cout << "using default colors...\n"; for (auto id_comp = 0; id_comp < comp_options_.size(); id_comp++) @@ -182,7 +193,7 @@ void SubscriberGnssReceiver::createCaptureAndProcess() GnssUtils::ComputePosOutput fix; // compute fix if publishing or not sats_available - if (not sats_available_ or publish_fix_) + if (not sats_available_) { fix = GnssUtils::computePos(receiver_->getObservations(), receiver_->getNavigation(), -- GitLab From 32e09a3750741edf0f768762bb9f896db9eb68f7 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Wed, 9 Sep 2020 18:40:07 +0200 Subject: [PATCH 47/86] automatic publishing if any subscriber --- src/subscriber_gnss_fix_publisher_ecef.cpp | 61 ++++++++++------------ 1 file changed, 29 insertions(+), 32 deletions(-) diff --git a/src/subscriber_gnss_fix_publisher_ecef.cpp b/src/subscriber_gnss_fix_publisher_ecef.cpp index d038bc0..6edf1a6 100644 --- a/src/subscriber_gnss_fix_publisher_ecef.cpp +++ b/src/subscriber_gnss_fix_publisher_ecef.cpp @@ -14,49 +14,46 @@ SubscriberGnssFixPublisherEcef::SubscriberGnssFixPublisherEcef(const std::string , ENU_defined_(false) { period_ = _server.getParam(prefix_ + "/period"); - pose_ = _server.getParam(prefix_ + "/pose_msg"); - pose_array_ = _server.getParam(prefix_ + "/pose_array_msg"); - marker_ = _server.getParam(prefix_ + "/marker_msg"); - if (marker_) - { + + // marker color + try{ + std::cout << "SubscriberGnssFixPublisherEcef: taking user defined marker color...\n"; Eigen::Vector4d col = _server.getParam(prefix_ + "/marker_color"); marker_color_.r = col(0); marker_color_.g = col(1); marker_color_.b = col(2); marker_color_.a = col(3); } + catch(...) + { + std::cout << "SubscriberGnssFixPublisherEcef: using default marker color: BLUE\n"; + marker_color_.r = 0; + marker_color_.g = 0; + marker_color_.b = 1; + marker_color_.a = 1; + } } - void SubscriberGnssFixPublisherEcef::initialize(ros::NodeHandle& nh, const std::string& topic) { sub_ = nh.subscribe(topic, 1, &SubscriberGnssFixPublisherEcef::callback, this); - // initialize msg and publisher - if (pose_) - { - pose_msg_.header.frame_id = "ENU"; + // initialize msgs and publishers + pose_msg_.header.frame_id = "ENU"; + pub_pose_ = nh.advertise(topic + "_ENU_pose", 1); - pub_pose_ = nh.advertise(topic + "_ENU_pose", 1); - } - if (pose_array_) - { - pose_array_msg_.header.frame_id = "ENU"; + pose_array_msg_.header.frame_id = "ENU"; + pub_pose_array_ = nh.advertise(topic + "_ENU_pose_array", 1); - pub_pose_array_ = nh.advertise(topic + "_ENU_pose_array", 1); - } - if (marker_) - { - marker_msg_.header.frame_id = "ENU"; - marker_msg_.type = visualization_msgs::Marker::LINE_STRIP; - marker_msg_.action = visualization_msgs::Marker::ADD; - marker_msg_.ns = "trajectory"; - marker_msg_.scale.x = 0.1; - marker_msg_.color = marker_color_; - marker_msg_.pose.orientation = tf::createQuaternionMsgFromYaw(0); - - pub_marker_ = nh.advertise(topic + "_ENU_marker", 1); - } + marker_msg_.header.frame_id = "ENU"; + marker_msg_.type = visualization_msgs::Marker::LINE_STRIP; + marker_msg_.action = visualization_msgs::Marker::ADD; + marker_msg_.ns = "trajectory"; + marker_msg_.scale.x = 0.1; + marker_msg_.color = marker_color_; + marker_msg_.pose.orientation = tf::createQuaternionMsgFromYaw(0); + + pub_marker_ = nh.advertise(topic + "_ENU_marker", 1); } void SubscriberGnssFixPublisherEcef::callback(const sensor_msgs::NavSatFix::ConstPtr& _msg) @@ -110,21 +107,21 @@ bool SubscriberGnssFixPublisherEcef::listenTf() void SubscriberGnssFixPublisherEcef::publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp) { // fill msgs and publish - if (pose_) + if (pub_pose_.getNumSubscribers() != 0) { pose_msg_.header.stamp = stamp; pose_msg_.pose = pose; pub_pose_.publish(pose_msg_); } - if (pose_array_) + if (pub_pose_array_.getNumSubscribers() != 0) { pose_array_msg_.header.stamp = stamp; pose_array_msg_.poses.push_back(pose); pub_pose_array_.publish(pose_array_msg_); } - if (marker_) + if (pub_marker_.getNumSubscribers() != 0) { marker_msg_.header.stamp = stamp; marker_msg_.points.push_back(pose.position); -- GitLab From 664a4ead1c5d8eff0b1d5c1e4f100b777305b4bf Mon Sep 17 00:00:00 2001 From: joanvallve Date: Wed, 9 Sep 2020 18:40:28 +0200 Subject: [PATCH 48/86] new iono and eph options --- include/subscriber_gnss_receiver.h | 2 +- src/subscriber_gnss_receiver.cpp | 219 ++++++++++++++++------------- 2 files changed, 119 insertions(+), 102 deletions(-) diff --git a/include/subscriber_gnss_receiver.h b/include/subscriber_gnss_receiver.h index 0700684..33da0f6 100644 --- a/include/subscriber_gnss_receiver.h +++ b/include/subscriber_gnss_receiver.h @@ -61,7 +61,7 @@ class SubscriberGnssReceiver : public Subscriber void publishFixComp(); void fillMsgs(const geometry_msgs::Pose pose, const std::string& comp); void publish(const ros::Time& stamp, const std::string& comp); - bool publish_fix_, pose_, pose_array_, marker_; + bool publish_fix_; std::string topic_fix_; GnssUtils::Options compute_pos_opt_; diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index d0e85de..01deaea 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -22,15 +22,26 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, * 3 numbers: RAIM - EPH - IONO/TROPO * RAIM: 0-1 * EPH: - * 0: broadcasted - * 1: SBAS + * 0: EPHOPT_BRDC + * 1: EPHOPT_SBAS (only SBAS) + * 2: EPHOPT_SBAS2 (SBAS and BRDC) + * 3: EPHOPT_SBAS3 (only SBAS if possible, otherwise SBAS+BRDC) + * 4: EPHOPT_SBAS4 (only SBAS if possible, otherwise BRDC) * IONO/TROPO: * 0: broadcasted * 1: SBAS * 2: iono-free (tropo broadcasted) */ - comp_options_.push_back("000"); + std::list raim{0};//,1} + std::list eph{0,1,2,3,4}; + std::list corr{0,1};//,2}; + for (auto r : raim) + for (auto e : eph) + for (auto c : corr) + comp_options_.push_back(std::string(std::to_string(r)+std::to_string(e)+std::to_string(c))); + + /*comp_options_.push_back("000"); comp_options_.push_back("001"); comp_options_.push_back("002"); comp_options_.push_back("010"); @@ -41,61 +52,51 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, comp_options_.push_back("102"); comp_options_.push_back("110"); comp_options_.push_back("111"); - comp_options_.push_back("112"); - //comp_options_.push_back("100"); - //comp_options_.push_back("101"); - //comp_options_.push_back("110"); - //comp_options_.push_back("111"); + comp_options_.push_back("112");*/ // params - pose_ = _server.getParam(prefix_ + "/publish_fix/pose_msg"); - pose_array_ = _server.getParam(prefix_ + "/publish_fix/pose_array_msg"); - marker_ = _server.getParam(prefix_ + "/publish_fix/marker_msg"); topic_fix_ = _server.getParam(prefix_ + "/publish_fix/topic"); // marker color - if (marker_) - { - try{ - std::cout << "taking user defined colors...\n"; - Eigen::Vector4d col = _server.getParam(prefix_ + "/publish_fix/marker_color"); - std_msgs::ColorRGBA marker_color; - marker_color.r = col(0); - marker_color.g = col(1); - marker_color.b = col(2); - marker_color.a = col(3); - for (auto comp : comp_options_) - { - marker_msgs_[comp] = visualization_msgs::Marker(); - marker_msgs_.at(comp).color = marker_color; - } + try{ + std::cout << "SubscriberGnssReceiver: taking user defined marker color...\n"; + Eigen::Vector4d col = _server.getParam(prefix_ + "/publish_fix/marker_color"); + std_msgs::ColorRGBA marker_color; + marker_color.r = col(0); + marker_color.g = col(1); + marker_color.b = col(2); + marker_color.a = col(3); + for (auto comp : comp_options_) + { + marker_msgs_[comp] = visualization_msgs::Marker(); + marker_msgs_.at(comp).color = marker_color; } - catch(...) + } + catch(...) + { + std::cout << "SubscriberGnssReceiver: taking default marker colors...\n"; + Eigen::MatrixXd colors(12,4); + colors << 1, 1, 1, 1, + 1, 1, 0, 1, + 1, 0, 1, 1, + 0, 1, 1, 1, + .5, .5, 1, 1, + .5, 1, .5, 1, + 1, .5, .5, 1, + .5, .5, .5, 1, + 0, .5, .5, 1, + .5, .5, 0, 1, + .5, 0, .5, 1, + 0, 0, .5, 1; + + for (auto id_comp = 0; id_comp < comp_options_.size(); id_comp++) { - Eigen::MatrixXd colors(12,4); - colors << 1, 1, 1, 1, - 1, 1, 0, 1, - 1, 0, 1, 1, - 0, 1, 1, 1, - .5, .5, 1, 1, - .5, 1, .5, 1, - 1, .5, .5, 1, - .5, .5, .5, 1, - 0, .5, .5, 1, - .5, .5, 0, 1, - .5, 0, .5, 1, - 0, 0, .5, 1; - - std::cout << "using default colors...\n"; - for (auto id_comp = 0; id_comp < comp_options_.size(); id_comp++) - { - auto comp = comp_options_[id_comp]; - marker_msgs_[comp] = visualization_msgs::Marker(); - marker_msgs_.at(comp).color.r = colors(id_comp,0); - marker_msgs_.at(comp).color.g = colors(id_comp,1); - marker_msgs_.at(comp).color.b = colors(id_comp,2); - marker_msgs_.at(comp).color.a = colors(id_comp,3);; - } + auto comp = comp_options_[id_comp]; + marker_msgs_[comp] = visualization_msgs::Marker(); + marker_msgs_.at(comp).color.r = colors(id_comp,0); + marker_msgs_.at(comp).color.g = colors(id_comp,1); + marker_msgs_.at(comp).color.b = colors(id_comp,2); + marker_msgs_.at(comp).color.a = colors(id_comp,3);; } } @@ -150,40 +151,31 @@ void SubscriberGnssReceiver::initialize(ros::NodeHandle& nh, const std::string& pub_available_ = nh.advertise("gnss_available", 1); if (publish_fix_) { - // initialize msg and publisher - if (pose_) + // initialize msgs and publishers + for (auto comp : comp_options_) { - for (auto comp : comp_options_) - { - pose_msgs_[comp] = geometry_msgs::PoseStamped(); - pose_msgs_.at(comp).header.frame_id = "ENU"; + pose_msgs_[comp] = geometry_msgs::PoseStamped(); + pose_msgs_.at(comp).header.frame_id = "ENU"; - publishers_pose_[comp] = nh.advertise(topic_fix_ + comp + "_pose", 1); - } + publishers_pose_[comp] = nh.advertise(topic_fix_ + comp + "_pose", 1); } - if (pose_array_) + for (auto comp : comp_options_) { - for (auto comp : comp_options_) - { - pose_array_msgs_[comp] = geometry_msgs::PoseArray(); - pose_array_msgs_.at(comp).header.frame_id = "ENU"; + pose_array_msgs_[comp] = geometry_msgs::PoseArray(); + pose_array_msgs_.at(comp).header.frame_id = "ENU"; - publishers_pose_array_[comp] = nh.advertise(topic_fix_ + comp + "_pose_array", 1); - } + publishers_pose_array_[comp] = nh.advertise(topic_fix_ + comp + "_pose_array", 1); } - if (marker_) + for (auto comp : comp_options_) { - for (auto comp : comp_options_) - { - marker_msgs_.at(comp).header.frame_id = "ENU"; - marker_msgs_.at(comp).type = visualization_msgs::Marker::LINE_LIST; - marker_msgs_.at(comp).action = visualization_msgs::Marker::ADD; - marker_msgs_.at(comp).ns = comp; - marker_msgs_.at(comp).scale.x = 0.1; - marker_msgs_.at(comp).pose.orientation = tf::createQuaternionMsgFromYaw(0); - - publishers_marker_[comp] = nh.advertise(topic_fix_ + comp + "_marker", 1); - } + marker_msgs_.at(comp).header.frame_id = "ENU"; + marker_msgs_.at(comp).type = visualization_msgs::Marker::LINE_LIST; + marker_msgs_.at(comp).action = visualization_msgs::Marker::ADD; + marker_msgs_.at(comp).ns = comp; + marker_msgs_.at(comp).scale.x = 0.1; + marker_msgs_.at(comp).pose.orientation = tf::createQuaternionMsgFromYaw(0); + + publishers_marker_[comp] = nh.advertise(topic_fix_ + comp + "_marker", 1); } } } @@ -251,44 +243,68 @@ void SubscriberGnssReceiver::publishFixComp() for (auto comp : comp_options_) { + if (publishers_pose_.at(comp).getNumSubscribers() == 0 and + publishers_pose_array_.at(comp).getNumSubscribers() == 0 and + publishers_marker_.at(comp).getNumSubscribers() == 0) + { + // store last as unsuccessful + last_fixes_ok_.at(comp) = false; + + continue; + } + comp_pos_opt.sbascorr = 15; //sbas corrections // RAIM - if (comp[0] == '0') - comp_pos_opt.raim = 0; - else - comp_pos_opt.raim = 1; + comp_pos_opt.raim = (int)(comp[0]-'0'); // EPHEMERIS - // broadcasted - if (comp[1] == '0') - comp_pos_opt.sateph = 0; - // sbas - else + switch (comp[1]) { - comp_pos_opt.GAL = false; - comp_pos_opt.sateph = 2; + case '0': + comp_pos_opt.sateph = EPHOPT_BRDC; + break; + case '1': + comp_pos_opt.sateph = EPHOPT_SBAS; + break; + case '2': + comp_pos_opt.sateph = EPHOPT_SBAS2; + break; + case '3': + comp_pos_opt.sateph = EPHOPT_SBAS3; + break; + case '4': + comp_pos_opt.sateph = EPHOPT_SBAS4; + break; } // IONO/TROPO // broadcasted (default '0') - comp_pos_opt.ionoopt = 1; - comp_pos_opt.tropopt = 1; + comp_pos_opt.ionoopt = IONOOPT_BRDC; + comp_pos_opt.tropopt = TROPOPT_SAAS; // sbas corrections if (comp[2] == '1') { - comp_pos_opt.ionoopt = 2; - comp_pos_opt.tropopt = 2; + comp_pos_opt.tropopt = TROPOPT_SBAS; + comp_pos_opt.ionoopt = IONOOPT_SBAS; + + // iono comb according to eph SBAS variant + if (comp_pos_opt.sateph == EPHOPT_SBAS2) + comp_pos_opt.ionoopt = IONOOPT_SBAS2; + if (comp_pos_opt.sateph == EPHOPT_SBAS3) + comp_pos_opt.ionoopt = IONOOPT_SBAS3; + if (comp_pos_opt.sateph == EPHOPT_SBAS4) + comp_pos_opt.ionoopt = IONOOPT_SBAS4; } // iono free else if (comp[2] == '2') - comp_pos_opt.ionoopt = 3; + comp_pos_opt.ionoopt = IONOOPT_IFLC; //std::cout << "//////////// Computing fix comp = " << comp << std::endl; auto fix = GnssUtils::computePos(receiver_->getObservations(), receiver_->getNavigation(), comp_pos_opt); - WOLF_INFO_COND(comp == "010" and not fix.success, "computePos failed with msg: ", fix.msg); + WOLF_INFO_COND(not fix.success, "computePos failed (opt ", comp, ") with msg: ", fix.msg); //std::cout << "//////////// Computed" << std::endl; @@ -316,13 +332,14 @@ void SubscriberGnssReceiver::publishFixComp() void SubscriberGnssReceiver::fillMsgs(const geometry_msgs::Pose pose, const std::string& comp) { // fill msgs - if (pose_) + if (publishers_pose_.at(comp).getNumSubscribers() != 0) pose_msgs_.at(comp).pose = pose; - if (pose_array_) + if (publishers_pose_array_.at(comp).getNumSubscribers() != 0) pose_array_msgs_.at(comp).poses.push_back(pose); - if (marker_ and last_fixes_ok_.at(comp)) + if (publishers_marker_.at(comp).getNumSubscribers() != 0 and + last_fixes_ok_.at(comp)) { marker_msgs_.at(comp).points.push_back(last_fixes_pose_.at(comp).position); marker_msgs_.at(comp).points.push_back(pose.position); @@ -331,17 +348,17 @@ void SubscriberGnssReceiver::fillMsgs(const geometry_msgs::Pose pose, const std: void SubscriberGnssReceiver::publish(const ros::Time& stamp, const std::string& comp) { - if (pose_) + if (publishers_pose_.at(comp).getNumSubscribers() != 0) { pose_msgs_.at(comp).header.stamp = stamp; publishers_pose_.at(comp).publish(pose_msgs_.at(comp)); } - if (pose_array_) + if (publishers_pose_array_.at(comp).getNumSubscribers() != 0) { pose_array_msgs_.at(comp).header.stamp = stamp; publishers_pose_array_.at(comp).publish(pose_array_msgs_.at(comp)); } - if (marker_) + if (publishers_marker_.at(comp).getNumSubscribers() != 0) { marker_msgs_.at(comp).header.stamp = stamp; publishers_marker_.at(comp).publish(marker_msgs_.at(comp)); -- GitLab From 5f64861b2d5c9b622254d34633d9b9adf522d29d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Tue, 29 Sep 2020 13:03:20 +0200 Subject: [PATCH 49/86] Update README.md --- README.md | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/README.md b/README.md index 1266069..e2c345f 100644 --- a/README.md +++ b/README.md @@ -1,2 +1,15 @@ # wolf_ros_gnss +This is the ros package of the [WOLF GNSS plugin](https://gitlab.iri.upc.edu/mobile_robotics/wolf_projects/wolf_lib/plugins/gnss). + +# Other dependencies + +Clone Novatel OEM7 msgs package and generate ROS messages. In a new terminal: + +``` +roscd +cd ../src +git clone ssh://git@gitlab.iri.upc.edu:2202/mobile_robotics/gauss_project/novatel_oem7_driver.git +cd .. +catkin_make --only-pkg-with-deps novatel_oem7_msgs +``` \ No newline at end of file -- GitLab From 0a75f090c2abc84f4ec7d3c5f3d2ba5e409abeb8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Tue, 29 Sep 2020 13:07:25 +0200 Subject: [PATCH 50/86] Update README.md --- README.md | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index e2c345f..e34f8f1 100644 --- a/README.md +++ b/README.md @@ -4,7 +4,18 @@ This is the ros package of the [WOLF GNSS plugin](https://gitlab.iri.upc.edu/mob # Other dependencies -Clone Novatel OEM7 msgs package and generate ROS messages. In a new terminal: +**iri_gnss_msgs** +Clone package and generate ROS messages. In a new terminal: + +``` +roscd +cd ../src +git clone ssh://git@gitlab.iri.upc.edu:2202/mobile_robotics/gauss_project/iri_gnss_msgs.git +cd .. +catkin_make --only-pkg-with-deps iri_gnss_msgs +``` +**Novatel OEM7 msgs** +Clone package and generate ROS messages. In a new terminal: ``` roscd -- GitLab From 2d824be8b26cf10ec22cc6cf2a8627de46a26fe9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Tue, 29 Sep 2020 13:07:43 +0200 Subject: [PATCH 51/86] Update README.md --- README.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/README.md b/README.md index e34f8f1..2a5b9a6 100644 --- a/README.md +++ b/README.md @@ -5,6 +5,7 @@ This is the ros package of the [WOLF GNSS plugin](https://gitlab.iri.upc.edu/mob # Other dependencies **iri_gnss_msgs** + Clone package and generate ROS messages. In a new terminal: ``` @@ -15,6 +16,7 @@ cd .. catkin_make --only-pkg-with-deps iri_gnss_msgs ``` **Novatel OEM7 msgs** + Clone package and generate ROS messages. In a new terminal: ``` -- GitLab From 96a5ec9103ea202b31a4815e1a826b94479fb632 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Tue, 29 Sep 2020 14:32:54 +0200 Subject: [PATCH 52/86] plugin core changed name --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f41d6b4..a026eaf 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -180,7 +180,7 @@ target_link_libraries(subscriber_${PROJECT_NAME} ${catkin_LIBRARIES} ) target_link_libraries(publisher_${PROJECT_NAME} - ${wolf_LIBRARIES} + ${wolfcore_LIBRARIES} ${wolfgnss_LIBRARIES} ${iri_gnss_msgs_LIBRARIES} ${catkin_LIBRARIES} -- GitLab From 1de51d0b180bee7dfecc3d1907467d24ce53a23b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Thu, 1 Oct 2020 17:45:40 +0200 Subject: [PATCH 53/86] debugging --- src/subscriber_gnss_receiver.cpp | 26 +++++++++++++++++++++++++- 1 file changed, 25 insertions(+), 1 deletion(-) diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index 01deaea..f58553f 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -241,6 +241,8 @@ void SubscriberGnssReceiver::publishFixComp() GnssUtils::Options comp_pos_opt = compute_pos_opt_; + WOLF_DEBUG("COMPARING RTKLIB pntpos CONFIGURATIONS /////////////////"); + for (auto comp : comp_options_) { if (publishers_pose_.at(comp).getNumSubscribers() == 0 and @@ -300,11 +302,32 @@ void SubscriberGnssReceiver::publishFixComp() else if (comp[2] == '2') comp_pos_opt.ionoopt = IONOOPT_IFLC; + WOLF_DEBUG("opt ", comp, ": ", + " RAIM: ", comp_pos_opt.raim, + " EPH: ", comp_pos_opt.sateph, + " IONO: ", comp_pos_opt.ionoopt, + " TROP: ", comp_pos_opt.tropopt) + //std::cout << "//////////// Computing fix comp = " << comp << std::endl; auto fix = GnssUtils::computePos(receiver_->getObservations(), receiver_->getNavigation(), comp_pos_opt); - WOLF_INFO_COND(not fix.success, "computePos failed (opt ", comp, ") with msg: ", fix.msg); + + // print + #ifdef _WOLF_DEBUG + std::string discarded_str, used_str; + for (auto sat : fix.discarded_sats) + discarded_str += std::to_string(sat) + " "; + for (auto sat : fix.used_sats) + used_str += std::to_string(sat) + " "; + #endif + + WOLF_INFO_COND(not fix.success, "computePos failed (opt ", comp, ") with msg: ", fix.msg, + "\n\tused sats: ", fix.used_sats.size(), " (", used_str, ")", + "\n\tdiscarded sats: ", fix.discarded_sats.size(), " (", discarded_str, ")"); + WOLF_DEBUG_COND(fix.success, "computePos succeed (opt ", comp, ")", + "\n\tused sats: ", fix.used_sats.size(), " (", used_str, ")", + "\n\tdiscarded sats: ", fix.discarded_sats.size(), " (", discarded_str, ")"); //std::cout << "//////////// Computed" << std::endl; @@ -327,6 +350,7 @@ void SubscriberGnssReceiver::publishFixComp() last_fixes_ok_.at(comp) = fix.success; last_fixes_pose_.at(comp) = pose_msg; } + WOLF_DEBUG("////////////////////////////////////////////////"); } void SubscriberGnssReceiver::fillMsgs(const geometry_msgs::Pose pose, const std::string& comp) -- GitLab From 7c733672cf5e87fa9e693d4151017e51d82b9736 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Tue, 6 Oct 2020 00:02:06 +0200 Subject: [PATCH 54/86] debug --- src/subscriber_gnss_receiver.cpp | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index f58553f..9cc19a7 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -314,13 +314,11 @@ void SubscriberGnssReceiver::publishFixComp() comp_pos_opt); // print - #ifdef _WOLF_DEBUG - std::string discarded_str, used_str; - for (auto sat : fix.discarded_sats) - discarded_str += std::to_string(sat) + " "; - for (auto sat : fix.used_sats) - used_str += std::to_string(sat) + " "; - #endif + std::string discarded_str, used_str; + for (auto sat : fix.discarded_sats) + discarded_str += std::to_string(sat) + " "; + for (auto sat : fix.used_sats) + used_str += std::to_string(sat) + " "; WOLF_INFO_COND(not fix.success, "computePos failed (opt ", comp, ") with msg: ", fix.msg, "\n\tused sats: ", fix.used_sats.size(), " (", used_str, ")", -- GitLab From a0f4607d60efc9e7e85539058955f59eddb29032 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Thu, 8 Oct 2020 19:29:24 +0200 Subject: [PATCH 55/86] wip --- CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a026eaf..7f1f72a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -129,7 +129,6 @@ include_directories( ${wolfgnss_INCLUDE_DIRS} ${gnss_utils_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS} - ${CERES_INCLUDE_DIRS} ) # link_directories(/usr/local/lib/iri-algorithms) ## Declare a C++ library -- GitLab From f1190c23689ad614e3a76d38d5491e442dbe6210 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Sat, 17 Oct 2020 23:47:46 +0200 Subject: [PATCH 56/86] Novatel dependency added to package.xml --- package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/package.xml b/package.xml index fdff95e..4b2aeb9 100644 --- a/package.xml +++ b/package.xml @@ -55,6 +55,7 @@ iri_gnss_msgs tf wolf_ros_node + novatel_oem7_msgs roscpp sensor_msgs std_msgs -- GitLab From 8928784b259a4b76a187962a90967b0f902c89d8 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Mon, 19 Oct 2020 18:12:37 +0200 Subject: [PATCH 57/86] include to get DEBUG from gnss plugin --- include/subscriber_gnss_receiver.h | 1 + 1 file changed, 1 insertion(+) diff --git a/include/subscriber_gnss_receiver.h b/include/subscriber_gnss_receiver.h index 33da0f6..badab15 100644 --- a/include/subscriber_gnss_receiver.h +++ b/include/subscriber_gnss_receiver.h @@ -3,6 +3,7 @@ /************************** * WOLF includes * **************************/ +#include #include #include #include -- GitLab From 8142587d7538e0d13750f9133efbc77e02e63317 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Mon, 9 Nov 2020 16:56:20 +0100 Subject: [PATCH 58/86] novatel_oem7_msgs and iri_gnss_msgs are optional now --- CMakeLists.txt | 107 ++++++++++++------ .../{publisher_fix.h => publisher_gnss_fix.h} | 16 +-- ...blisher_fix.cpp => publisher_gnss_fix.cpp} | 27 +++-- 3 files changed, 95 insertions(+), 55 deletions(-) rename include/{publisher_fix.h => publisher_gnss_fix.h} (70%) rename src/{publisher_fix.cpp => publisher_gnss_fix.cpp} (86%) diff --git a/CMakeLists.txt b/CMakeLists.txt index 7f1f72a..eecb474 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -11,15 +11,17 @@ add_compile_options(-std=c++11) find_package(catkin REQUIRED COMPONENTS roscpp sensor_msgs - iri_gnss_msgs std_msgs tf tf_conversions dynamic_reconfigure wolf_ros_node - novatel_oem7_msgs ) +# OPTIONAL PACKAGES +find_package(iri_gnss_msgs QUIET) +find_package(novatel_oem7_msgs QUIET) + ## System dependencies are found with CMake's conventions find_package(wolfcore REQUIRED) find_package(wolfgnss REQUIRED) @@ -119,34 +121,73 @@ catkin_package( ## Build ## ########### +set(INCLUDE_DIRS + include + ${EIGEN_INCLUDE_DIRS} + ${wolfcore_INCLUDE_DIRS} + ${wolfgnss_INCLUDE_DIRS} + ${gnss_utils_INCLUDE_DIRS} + ${catkin_INCLUDE_DIRS} + ) + +set(PUB_SRCS + #src/publisher_gnss_fix.cpp + src/publisher_gnss_tf.cpp + src/publisher_gnss_accuracy.cpp + ) + +set(SUB_SRCS + src/subscriber_gnss_fix.cpp + src/subscriber_gnss_fix_publisher_ecef.cpp + src/subscriber_gnss_receiver.cpp + src/subscriber_gnss_ublox.cpp + ) + +set(LIBRARIES + ${wolfcore_LIBRARIES} + ${wolfgnss_LIBRARIES} + ${iri_gnss_msgs_LIBRARIES} + ${catkin_LIBRARIES} + ) + + +# OPTIONAL iri_gnss_msgs dependant code +if (iri_gnss_msgs_FOUND) + message("iri_gnss_msgs FOUND: compiling dependant code") + list(APPEND SUB_SRCS + src/subscriber_gnss.cpp + src/subscriber_gnss_tdcp.cpp + ) + list(APPEND INCLUDE_DIRS ${iri_gnss_msgs_INCLUDE_DIRS}) + list(APPEND LIBRARIES ${iri_gnss_msgs_LIBRARIES}) +endif() + +# OPTIONAL iri_gnss_msgs dependant code +if (novatel_oem7_msgs_FOUND) + message("novatel_oem7_msgs FOUND: compiling dependant code") + list(APPEND SUB_SRCS + src/subscriber_gnss_novatel.cpp + ) + if (iri_gnss_msgs_FOUND) + list(APPEND SUB_SRCS + src/subscriber_gnss_fix_novatel_publisher_ecef.cpp + ) + endif() + list(APPEND INCLUDE_DIRS ${novatel_oem7_msgs_INCLUDE_DIRS}) +endif() + ## Specify additional locations of header files ## Your package locations should be listed before other locations message("Wolf include path: ${wolfcore_INCLUDE_DIRS}") -include_directories( - include - ${EIGEN_INCLUDE_DIRS} - ${wolfcore_INCLUDE_DIRS} - ${wolfgnss_INCLUDE_DIRS} - ${gnss_utils_INCLUDE_DIRS} - ${catkin_INCLUDE_DIRS} -) +message("iri_gnss_msgs include path: ${iri_gnss_msgs_INCLUDE_DIRS}") +include_directories(${INCLUDE_DIRS}) # link_directories(/usr/local/lib/iri-algorithms) ## Declare a C++ library # add_library(${PROJECT_NAME} # src/${PROJECT_NAME}/wolf_ros.cpp # ) -add_library(publisher_${PROJECT_NAME} - src/publisher_gnss_tf.cpp - src/publisher_gnss_accuracy.cpp) -add_library(subscriber_${PROJECT_NAME} - src/subscriber_gnss.cpp - src/subscriber_gnss_fix.cpp - src/subscriber_gnss_fix_publisher_ecef.cpp - src/subscriber_gnss_fix_novatel_publisher_ecef.cpp - src/subscriber_gnss_tdcp.cpp - src/subscriber_gnss_receiver.cpp - src/subscriber_gnss_ublox.cpp - src/subscriber_gnss_novatel.cpp) +add_library(publisher_${PROJECT_NAME} ${PUB_SRCS}) +add_library(subscriber_${PROJECT_NAME} ${SUB_SRCS}) ## Add cmake target dependencies of the library ## as an example, code may need to be generated before libraries @@ -168,22 +209,16 @@ add_library(subscriber_${PROJECT_NAME} ## same as for the library above #add_dependencies(${PROJECT_NAME}_node ${PROJECT_NAME}_gencfg) #add_dependencies(${PROJECT_NAME}_visualizer ${PROJECT_NAME}_gencfg) -add_dependencies(subscriber_${PROJECT_NAME} iri_gnss_msgs_generate_messages_cpp) -add_dependencies(subscriber_${PROJECT_NAME} novatel_oem7_msgs_generate_messages_cpp) +if (iri_gnss_msgs_FOUND) + add_dependencies(subscriber_${PROJECT_NAME} iri_gnss_msgs_generate_messages_cpp) +endif() +if (novatel_oem7_msgs_FOUND) + add_dependencies(subscriber_${PROJECT_NAME} novatel_oem7_msgs_generate_messages_cpp) +endif() ## Specify libraries to link a library or executable target against -target_link_libraries(subscriber_${PROJECT_NAME} - ${wolfcore_LIBRARIES} - ${wolfgnss_LIBRARIES} - ${iri_gnss_msgs_LIBRARIES} - ${catkin_LIBRARIES} - ) -target_link_libraries(publisher_${PROJECT_NAME} - ${wolfcore_LIBRARIES} - ${wolfgnss_LIBRARIES} - ${iri_gnss_msgs_LIBRARIES} - ${catkin_LIBRARIES} - ) +target_link_libraries(subscriber_${PROJECT_NAME} ${LIBRARIES}) +target_link_libraries(publisher_${PROJECT_NAME} ${LIBRARIES}) ############# ## Install ## diff --git a/include/publisher_fix.h b/include/publisher_gnss_fix.h similarity index 70% rename from include/publisher_fix.h rename to include/publisher_gnss_fix.h index 3b71f4b..5582f1d 100644 --- a/include/publisher_fix.h +++ b/include/publisher_gnss_fix.h @@ -19,21 +19,23 @@ namespace wolf { -class PublishFix: public Publisher +class PublishGnssFix: public Publisher { - geometry_msgs::PoseWithCovarianceStamped pose_msg_; + geometry_msgs::PoseArray pose_array_msg_; + geometry_msgs::PoseStamped pose_msg_; + visualization_msgs::Marker marker_msg_; SensorBasePtr sensor_; std::string frame_id_, map_frame_id_; - ros::Publisher pub_pose_; + ros::Publisher pub_pose_array_, pub_marker_, pub_pose_; public: - PublishFix(const std::string& _unique_name, + PublishGnssFix(const std::string& _unique_name, const ParamsServer& _server, const ProblemPtr _problem); - WOLF_PUBLISHER_CREATE(PublishFix); + WOLF_PUBLISHER_CREATE(PublishGnssFix); - virtual ~PublishFix(){}; + virtual ~PublishGnssFix(){}; void initialize(ros::NodeHandle &nh, const std::string& topic) override; @@ -49,7 +51,7 @@ class PublishFix: public Publisher tf::TransformListener tfl_; }; -WOLF_REGISTER_PUBLISHER(PublishFix) +WOLF_REGISTER_PUBLISHER(PublishGnssFix) } #endif diff --git a/src/publisher_fix.cpp b/src/publisher_gnss_fix.cpp similarity index 86% rename from src/publisher_fix.cpp rename to src/publisher_gnss_fix.cpp index 5a3822f..0eae2ae 100644 --- a/src/publisher_fix.cpp +++ b/src/publisher_gnss_fix.cpp @@ -1,16 +1,12 @@ -#include "publisher_fix.h" - -/************************** - * ROS includes * - **************************/ #include #include "tf/transform_datatypes.h" #include "tf_conversions/tf_eigen.h" +#include "../include/publisher_gnss_fix.h" namespace wolf { -PublishFix::PublishFix(const std::string& _unique_name, +PublishGnssFix::PublishGnssFix(const std::string& _unique_name, const ParamsServer& _server, const ProblemPtr _problem) : Publisher(_unique_name, _server, _problem) @@ -19,7 +15,7 @@ PublishFix::PublishFix(const std::string& _unique_name, frame_id_ = _server.getParam(prefix_ + "/frame_id"); } -void PublishFix::initialize(ros::NodeHandle& nh, const std::string& topic) +void PublishGnssFix::initialize(ros::NodeHandle& nh, const std::string& topic) { nh.param("map_frame_id", map_frame_id_, "map"); @@ -29,7 +25,7 @@ void PublishFix::initialize(ros::NodeHandle& nh, const std::string& topic) pub_pose_ = nh.advertise(topic, 1); } -void PublishFix::publishDerived() +void PublishGnssFix::publishDerived() { VectorComposite current_state = problem_->getState("PO"); TimeStamp loc_ts = problem_->getTimeStamp(); @@ -104,17 +100,24 @@ void PublishFix::publishDerived() publishPose(pose_msg, ros::Time(loc_ts.getSeconds(), loc_ts.getNanoSeconds())); } -void PublishFix::publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp) +void PublishGnssFix::publishPose(const geometry_msgs::Pose pose, const ros::Time& stamp) { // fill msgs and publish - if (pose_array_) + if (pub_pose_.getNumSubscribers() != 0) + { + pose_msg_.header.stamp = stamp; + pose_msg_.pose = pose; + + pub_pose_.publish(pose_msg_); + } + if (pub_pose_array_.getNumSubscribers() != 0) { pose_array_msg_.header.stamp = stamp; pose_array_msg_.poses.push_back(pose); pub_pose_array_.publish(pose_array_msg_); } - if (marker_) + if (pub_marker_.getNumSubscribers() != 0) { marker_msg_.header.stamp = stamp; marker_msg_.points.push_back(pose.position); @@ -123,7 +126,7 @@ void PublishFix::publishPose(const geometry_msgs::Pose pose, const ros::Time& st } } -bool PublishFix::listenTf() +bool PublishGnssFix::listenTf() { tf::StampedTransform T; if ( tfl_.waitForTransform(frame_id_, map_frame_id_, ros::Time(0), ros::Duration(0.01)) ) -- GitLab From 0d5b519d8fce88264f2ad382486481d359164b1a Mon Sep 17 00:00:00 2001 From: joanvallve Date: Wed, 18 Nov 2020 16:01:24 +0100 Subject: [PATCH 59/86] stamp --- include/subscriber_gnss_receiver.h | 2 +- src/subscriber_gnss_novatel.cpp | 2 +- src/subscriber_gnss_receiver.cpp | 5 ++--- src/subscriber_gnss_ublox.cpp | 3 ++- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/include/subscriber_gnss_receiver.h b/include/subscriber_gnss_receiver.h index badab15..6d6e2ad 100644 --- a/include/subscriber_gnss_receiver.h +++ b/include/subscriber_gnss_receiver.h @@ -49,7 +49,7 @@ class SubscriberGnssReceiver : public Subscriber protected: - void createCaptureAndProcess(); + void createCaptureAndProcess(const ros::Time& _stamp); GnssUtils::ReceiverRawAbstractPtr receiver_; diff --git a/src/subscriber_gnss_novatel.cpp b/src/subscriber_gnss_novatel.cpp index bc59fd5..a903c61 100644 --- a/src/subscriber_gnss_novatel.cpp +++ b/src/subscriber_gnss_novatel.cpp @@ -31,7 +31,7 @@ void SubscriberGnssNovatel::callback(const novatel_oem7_msgs::Oem7RawMsg& msg) if (res == GnssUtils::OBS) { //ROS_INFO("Observation received!"); - createCaptureAndProcess(); + createCaptureAndProcess(msg.header.stamp); } } diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index 9cc19a7..b6a1e65 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -180,7 +180,7 @@ void SubscriberGnssReceiver::initialize(ros::NodeHandle& nh, const std::string& } } -void SubscriberGnssReceiver::createCaptureAndProcess() +void SubscriberGnssReceiver::createCaptureAndProcess(const ros::Time& _stamp) { GnssUtils::ComputePosOutput fix; @@ -212,8 +212,7 @@ void SubscriberGnssReceiver::createCaptureAndProcess() std::make_shared(receiver_->getNavigation())); //ROS_INFO("Snapshot with copied observations and navigation created!"); - ros::Time now = ros::Time::now(); - auto cap_gnss_ptr = std::make_shared(TimeStamp(now.sec, now.nsec), + auto cap_gnss_ptr = std::make_shared(TimeStamp(_stamp.sec, _stamp.nsec), sensor_ptr_, snapshot_ptr); diff --git a/src/subscriber_gnss_ublox.cpp b/src/subscriber_gnss_ublox.cpp index 31dc86f..d4f43b3 100644 --- a/src/subscriber_gnss_ublox.cpp +++ b/src/subscriber_gnss_ublox.cpp @@ -23,6 +23,7 @@ void SubscriberGnssUblox::initialize(ros::NodeHandle& nh, const std::string& top void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) { + auto stamp = ros::Time::now(); GnssUtils::RawDataType res = receiver_->addDataStream(msg.data); //std::cout << "res = " << (int) res << std::endl; @@ -31,7 +32,7 @@ void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) if (res == GnssUtils::OBS) { //ROS_INFO("Observation received!"); - createCaptureAndProcess(); + createCaptureAndProcess(stamp); } } -- GitLab From 0ffc7a2275e897e1ffed23255a2bbf2c0803f38e Mon Sep 17 00:00:00 2001 From: joanvallve Date: Wed, 10 Feb 2021 12:52:15 +0100 Subject: [PATCH 60/86] new publisher for monitoring processor_tracker_gnss --- CMakeLists.txt | 1 + include/publisher_tracker_gnss_info.h | 43 +++++++++++++++++++++++++ src/publisher_tracker_gnss_info.cpp | 45 +++++++++++++++++++++++++++ 3 files changed, 89 insertions(+) create mode 100644 include/publisher_tracker_gnss_info.h create mode 100644 src/publisher_tracker_gnss_info.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index eecb474..500b89f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -134,6 +134,7 @@ set(PUB_SRCS #src/publisher_gnss_fix.cpp src/publisher_gnss_tf.cpp src/publisher_gnss_accuracy.cpp + src/publisher_tracker_gnss_info.cpp ) set(SUB_SRCS diff --git a/include/publisher_tracker_gnss_info.h b/include/publisher_tracker_gnss_info.h new file mode 100644 index 0000000..0a2d815 --- /dev/null +++ b/include/publisher_tracker_gnss_info.h @@ -0,0 +1,43 @@ +#ifndef PUBLISHER_TRACKER_GNSS_INFO_H +#define PUBLISHER_TRACKER_GNSS_INFO_H + +/************************** + * WOLF includes * + **************************/ +#include "core/problem/problem.h" +#include "gnss/processor/processor_tracker_gnss.h" + +#include "publisher.h" + +/************************** + * ROS includes * + **************************/ +#include + +namespace wolf +{ + +class PublisherTrackerGnssInfo: public Publisher +{ + protected: + + ProcessorTrackerGnssPtr processor_tracker_gnss_; + ros::Publisher publisher_untracked_; + + public: + PublisherTrackerGnssInfo(const std::string& _unique_name, + const ParamsServer& _server, + const ProblemPtr _problem); + WOLF_PUBLISHER_CREATE(PublisherTrackerGnssInfo); + + virtual ~PublisherTrackerGnssInfo(){}; + + void initialize(ros::NodeHandle &nh, const std::string& topic) override; + + void publishDerived() override; +}; + +WOLF_REGISTER_PUBLISHER(PublisherTrackerGnssInfo) +} + +#endif diff --git a/src/publisher_tracker_gnss_info.cpp b/src/publisher_tracker_gnss_info.cpp new file mode 100644 index 0000000..1a8ab69 --- /dev/null +++ b/src/publisher_tracker_gnss_info.cpp @@ -0,0 +1,45 @@ +#include "../include/publisher_tracker_gnss_info.h" + +#include "std_msgs/UInt16.h" +#include "tf/transform_datatypes.h" + +namespace wolf +{ + +PublisherTrackerGnssInfo::PublisherTrackerGnssInfo(const std::string& _unique_name, + const ParamsServer& _server, + const ProblemPtr _problem) : + Publisher(_unique_name, _server, _problem), + processor_tracker_gnss_(nullptr) +{ + auto proc_name = _server.getParam(prefix_ + "/processor_gnss"); + for (auto sen : _problem->getHardware()->getSensorList()) + { + for (auto proc : sen->getProcessorList()) + if (proc_name == proc->getName()) + { + processor_tracker_gnss_ = std::dynamic_pointer_cast(proc); + if (not processor_tracker_gnss_) + throw std::runtime_error("PublisherTrackerGnssInfo: the processor with name " + proc_name + " is not of type ProcessorTrackerGnss."); + break; + } + if (processor_tracker_gnss_) + break; + } + if (not processor_tracker_gnss_) + throw std::runtime_error("PublisherTrackerGnssInfo: the processor with name " + proc_name + " was not found."); +} + +void PublisherTrackerGnssInfo::initialize(ros::NodeHandle& nh, const std::string& topic) +{ + publisher_ = nh.advertise(topic + "_tracked", 1); + publisher_untracked_ = nh.advertise(topic + "_untracked", 1); +} + +void PublisherTrackerGnssInfo::publishDerived() +{ + publisher_.publish(std_msgs::UInt16(processor_tracker_gnss_->getNTrackedSats())); + publisher_untracked_.publish(std_msgs::UInt16(processor_tracker_gnss_->getNUntrackedSats())); +} + +} -- GitLab From ee828875ac005df2f614ce5fa088bcf685a00aad Mon Sep 17 00:00:00 2001 From: joanvallve Date: Wed, 10 Feb 2021 14:24:59 +0100 Subject: [PATCH 61/86] bug fixed --- src/publisher_tracker_gnss_info.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/src/publisher_tracker_gnss_info.cpp b/src/publisher_tracker_gnss_info.cpp index 1a8ab69..0057ce0 100644 --- a/src/publisher_tracker_gnss_info.cpp +++ b/src/publisher_tracker_gnss_info.cpp @@ -38,8 +38,11 @@ void PublisherTrackerGnssInfo::initialize(ros::NodeHandle& nh, const std::string void PublisherTrackerGnssInfo::publishDerived() { - publisher_.publish(std_msgs::UInt16(processor_tracker_gnss_->getNTrackedSats())); - publisher_untracked_.publish(std_msgs::UInt16(processor_tracker_gnss_->getNUntrackedSats())); + std_msgs::UInt16 msg; + msg.data = processor_tracker_gnss_->getNTrackedSats(); + publisher_.publish(msg); + msg.data = processor_tracker_gnss_->getNUntrackedSats(); + publisher_untracked_.publish(msg); } } -- GitLab From 0be4bdbd578304a044332bbf9a1049f2c62efa83 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Wed, 17 Feb 2021 17:27:05 +0100 Subject: [PATCH 62/86] printing error in computing first fix --- src/subscriber_gnss_receiver.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index b6a1e65..140e072 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -190,6 +190,9 @@ void SubscriberGnssReceiver::createCaptureAndProcess(const ros::Time& _stamp) fix = GnssUtils::computePos(receiver_->getObservations(), receiver_->getNavigation(), compute_pos_opt_); + + if (not fix.success) + WOLF_INFO("SubscriberGnssReceiver: Couldn't compute fix. Output message: ", fix.msg); } // if (last time) satellites were not available: check if they are -- GitLab From a3f5fb698c9ab2e7dc6494a155dcf8245fd19f07 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Thu, 18 Feb 2021 22:14:14 +0100 Subject: [PATCH 63/86] added check of publishers receiving messages --- src/subscriber_gnss.cpp | 2 ++ src/subscriber_gnss_fix.cpp | 2 ++ src/subscriber_gnss_fix_novatel_publisher_ecef.cpp | 2 ++ src/subscriber_gnss_fix_publisher_ecef.cpp | 2 ++ src/subscriber_gnss_novatel.cpp | 2 ++ src/subscriber_gnss_ublox.cpp | 2 ++ 6 files changed, 12 insertions(+) diff --git a/src/subscriber_gnss.cpp b/src/subscriber_gnss.cpp index 7099f02..3d4337f 100644 --- a/src/subscriber_gnss.cpp +++ b/src/subscriber_gnss.cpp @@ -21,6 +21,8 @@ void SubscriberGnss::initialize(ros::NodeHandle& nh, const std::string& topic) void SubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) { + setLastStamp(msg->header.stamp); + ROS_DEBUG("callbackObs!"); if (last_nav_ptr_==nullptr) return; diff --git a/src/subscriber_gnss_fix.cpp b/src/subscriber_gnss_fix.cpp index 59f0877..29a69f5 100644 --- a/src/subscriber_gnss_fix.cpp +++ b/src/subscriber_gnss_fix.cpp @@ -28,6 +28,8 @@ void SubscriberGnssFix::initialize(ros::NodeHandle& nh, const std::string& topic void SubscriberGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg) { + setLastStamp(msg->header.stamp); + if (cov_mode_ == "msg" or cov_mode_ == "factor") cov_ = cov_factor_ * Eigen::Map(msg->position_covariance.data()); diff --git a/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp b/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp index 70127b5..0d77429 100644 --- a/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp +++ b/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp @@ -23,6 +23,8 @@ void SubscriberGnssFixNovatelPublisherEcef::initialize(ros::NodeHandle& nh, cons void SubscriberGnssFixNovatelPublisherEcef::callback(const novatel_oem7_msgs::BESTPOS::ConstPtr& _msg) { + setLastStamp(_msg->header.stamp); + computeAndPublish(Eigen::Vector3d(_msg->lat * M_PI / 180.0, _msg->lon * M_PI / 180.0, _msg->hgt+_msg->undulation), diff --git a/src/subscriber_gnss_fix_publisher_ecef.cpp b/src/subscriber_gnss_fix_publisher_ecef.cpp index 6edf1a6..afa3316 100644 --- a/src/subscriber_gnss_fix_publisher_ecef.cpp +++ b/src/subscriber_gnss_fix_publisher_ecef.cpp @@ -58,6 +58,8 @@ void SubscriberGnssFixPublisherEcef::initialize(ros::NodeHandle& nh, const std:: void SubscriberGnssFixPublisherEcef::callback(const sensor_msgs::NavSatFix::ConstPtr& _msg) { + setLastStamp(_msg->header.stamp); + computeAndPublish(Eigen::Vector3d(_msg->latitude * M_PI / 180.0, _msg->longitude * M_PI / 180.0, _msg->altitude), diff --git a/src/subscriber_gnss_novatel.cpp b/src/subscriber_gnss_novatel.cpp index a903c61..118c1e1 100644 --- a/src/subscriber_gnss_novatel.cpp +++ b/src/subscriber_gnss_novatel.cpp @@ -23,6 +23,8 @@ void SubscriberGnssNovatel::initialize(ros::NodeHandle& nh, const std::string& t void SubscriberGnssNovatel::callback(const novatel_oem7_msgs::Oem7RawMsg& msg) { + setLastStamp(msg->header.stamp); + GnssUtils::RawDataType res = receiver_->addDataStream(msg.message_data); //std::cout << "res = " << (int) res << std::endl; diff --git a/src/subscriber_gnss_ublox.cpp b/src/subscriber_gnss_ublox.cpp index d4f43b3..53fb704 100644 --- a/src/subscriber_gnss_ublox.cpp +++ b/src/subscriber_gnss_ublox.cpp @@ -24,6 +24,8 @@ void SubscriberGnssUblox::initialize(ros::NodeHandle& nh, const std::string& top void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) { auto stamp = ros::Time::now(); + setLastStamp(stamp); + GnssUtils::RawDataType res = receiver_->addDataStream(msg.data); //std::cout << "res = " << (int) res << std::endl; -- GitLab From 8752017de648f1144bd0143ce41da25fb6396bb0 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Fri, 19 Feb 2021 16:25:01 +0100 Subject: [PATCH 64/86] bug fixed --- src/subscriber_gnss_novatel.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/subscriber_gnss_novatel.cpp b/src/subscriber_gnss_novatel.cpp index 118c1e1..bd70676 100644 --- a/src/subscriber_gnss_novatel.cpp +++ b/src/subscriber_gnss_novatel.cpp @@ -23,7 +23,7 @@ void SubscriberGnssNovatel::initialize(ros::NodeHandle& nh, const std::string& t void SubscriberGnssNovatel::callback(const novatel_oem7_msgs::Oem7RawMsg& msg) { - setLastStamp(msg->header.stamp); + setLastStamp(msg.header.stamp); GnssUtils::RawDataType res = receiver_->addDataStream(msg.message_data); -- GitLab From 8abbdcf7f8d65583b1af6259b953c688dcab0ec6 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Tue, 13 Apr 2021 10:00:21 +0200 Subject: [PATCH 65/86] wip --- include/subscriber_gnss_ublox.h | 3 +++ src/subscriber_gnss_novatel.cpp | 2 +- src/subscriber_gnss_ublox.cpp | 11 +++++++++-- 3 files changed, 13 insertions(+), 3 deletions(-) diff --git a/include/subscriber_gnss_ublox.h b/include/subscriber_gnss_ublox.h index 8f5f677..6be1861 100644 --- a/include/subscriber_gnss_ublox.h +++ b/include/subscriber_gnss_ublox.h @@ -39,11 +39,14 @@ class SubscriberGnssUblox : public SubscriberGnssReceiver const ParamsServer& _server, const SensorBasePtr _sensor_ptr); WOLF_SUBSCRIBER_CREATE(SubscriberGnssUblox); + virtual ~SubscriberGnssUblox(); virtual void initialize(ros::NodeHandle& nh, const std::string& topic); void callback(const std_msgs::UInt8MultiArray& msg); + protected: + long unsigned int n_msgs_; }; WOLF_REGISTER_SUBSCRIBER(SubscriberGnssUblox); diff --git a/src/subscriber_gnss_novatel.cpp b/src/subscriber_gnss_novatel.cpp index bd70676..5743089 100644 --- a/src/subscriber_gnss_novatel.cpp +++ b/src/subscriber_gnss_novatel.cpp @@ -18,7 +18,7 @@ void SubscriberGnssNovatel::initialize(ros::NodeHandle& nh, const std::string& t { SubscriberGnssReceiver::initialize(nh, topic); - sub_ = nh.subscribe(topic, 100, &SubscriberGnssNovatel::callback, this); + sub_ = nh.subscribe(topic, 10000, &SubscriberGnssNovatel::callback, this); } void SubscriberGnssNovatel::callback(const novatel_oem7_msgs::Oem7RawMsg& msg) diff --git a/src/subscriber_gnss_ublox.cpp b/src/subscriber_gnss_ublox.cpp index 53fb704..fedcec5 100644 --- a/src/subscriber_gnss_ublox.cpp +++ b/src/subscriber_gnss_ublox.cpp @@ -10,21 +10,28 @@ SubscriberGnssUblox::SubscriberGnssUblox(const std::string& _unique_name, SubscriberGnssReceiver(_unique_name, _server, _sensor_ptr, - std::make_shared()) + std::make_shared()), + n_msgs_(0) { } +SubscriberGnssUblox::~SubscriberGnssUblox() +{ + WOLF_INFO("SubscriberGnssUblox destructor: n_msgs_ = ", n_msgs_); +} + void SubscriberGnssUblox::initialize(ros::NodeHandle& nh, const std::string& topic) { SubscriberGnssReceiver::initialize(nh, topic); - sub_ = nh.subscribe(topic, 100, &SubscriberGnssUblox::callback, this); + sub_ = nh.subscribe(topic, 10000, &SubscriberGnssUblox::callback, this); } void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) { auto stamp = ros::Time::now(); setLastStamp(stamp); + n_msgs_++; GnssUtils::RawDataType res = receiver_->addDataStream(msg.data); -- GitLab From 64e1ca13d7a9d080eddbdcecf5028a14cf34a071 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Tue, 13 Apr 2021 11:16:30 +0200 Subject: [PATCH 66/86] bugfix: elmin in rads --- src/subscriber_gnss_receiver.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index 140e072..adf00c1 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -120,7 +120,7 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, }catch(...){std::cout << "default sbascorr" << std::endl;} try{compute_pos_opt_.raim = _server.getParam (prefix_ + "/gnss_options/raim"); // RAIM enabled }catch(...){std::cout << "default raim" << std::endl;} - try{compute_pos_opt_.elmin = D2R * _server.getParam(prefix_ + "/gnss_options/elmin"); // min elevation (degrees) + try{compute_pos_opt_.elmin = _server.getParam(prefix_ + "/gnss_options/elmin"); // min elevation (rad) }catch(...){std::cout << "default elmin" << std::endl;} try{compute_pos_opt_.maxgdop = _server.getParam(prefix_ + "/gnss_options/maxgdop"); // maxgdop: reject threshold of gdop }catch(...){std::cout << "default maxgdop" << std::endl;} -- GitLab From bbbe0de36240b18af13e6375372ffc5760e0fa97 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Wed, 12 May 2021 16:52:58 +0200 Subject: [PATCH 67/86] optionally reseting driver --- include/subscriber_gnss_ublox.h | 5 +++++ src/subscriber_gnss_ublox.cpp | 28 ++++++++++++++++++++++++++++ 2 files changed, 33 insertions(+) diff --git a/include/subscriber_gnss_ublox.h b/include/subscriber_gnss_ublox.h index 6be1861..eb902a5 100644 --- a/include/subscriber_gnss_ublox.h +++ b/include/subscriber_gnss_ublox.h @@ -45,8 +45,13 @@ class SubscriberGnssUblox : public SubscriberGnssReceiver void callback(const std_msgs::UInt8MultiArray& msg); + double secondsSinceLastCallback() override; + protected: long unsigned int n_msgs_; + ros::Time reseted_stamp_; + bool reset_driver_node_; + double max_topic_delay_, reset_duration_; }; WOLF_REGISTER_SUBSCRIBER(SubscriberGnssUblox); diff --git a/src/subscriber_gnss_ublox.cpp b/src/subscriber_gnss_ublox.cpp index fedcec5..5ea8745 100644 --- a/src/subscriber_gnss_ublox.cpp +++ b/src/subscriber_gnss_ublox.cpp @@ -13,6 +13,12 @@ SubscriberGnssUblox::SubscriberGnssUblox(const std::string& _unique_name, std::make_shared()), n_msgs_(0) { + reset_driver_node_ = _server.getParam(prefix_ + "/reset_receiver"); + if (reset_driver_node_) + { + max_topic_delay_ = _server.getParam(prefix_ + "/reset_duration"); + reset_duration_ = _server.getParam(prefix_ + "/reset_duration"); + } } SubscriberGnssUblox::~SubscriberGnssUblox() @@ -29,6 +35,8 @@ void SubscriberGnssUblox::initialize(ros::NodeHandle& nh, const std::string& top void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) { + ROS_DEBUG("SubscriberGnssUblox::callback message received!"); + auto stamp = ros::Time::now(); setLastStamp(stamp); n_msgs_++; @@ -45,4 +53,24 @@ void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) } } +double SubscriberGnssUblox::secondsSinceLastCallback() +{ + if (last_stamp_ == ros::Time(0)) + return 0; + + double seconds = (ros::Time::now() - last_stamp_).toSec(); + + if (reset_driver_node_ and + seconds > max_topic_delay_ and + (ros::Time::now() - reseted_stamp_).toSec() > reset_duration_) + { + ROS_WARN("SubscriberGnssUblox: not received raw data for more than %fs and reseted more than %fs ago, reseting ublox diver...", max_topic_delay_, reset_duration_); + + system("rosnode kill ublox_gps"); + reseted_stamp_ = ros::Time::now(); + } + + return seconds; +} + } -- GitLab From 1849e4c86463355e5167c609aa9a23b60840f9bc Mon Sep 17 00:00:00 2001 From: joanvallve Date: Wed, 12 May 2021 16:55:45 +0200 Subject: [PATCH 68/86] fixed param name --- src/subscriber_gnss_ublox.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/subscriber_gnss_ublox.cpp b/src/subscriber_gnss_ublox.cpp index 5ea8745..330b46d 100644 --- a/src/subscriber_gnss_ublox.cpp +++ b/src/subscriber_gnss_ublox.cpp @@ -16,7 +16,7 @@ SubscriberGnssUblox::SubscriberGnssUblox(const std::string& _unique_name, reset_driver_node_ = _server.getParam(prefix_ + "/reset_receiver"); if (reset_driver_node_) { - max_topic_delay_ = _server.getParam(prefix_ + "/reset_duration"); + max_topic_delay_ = _server.getParam(prefix_ + "/reset_max_topic_delay"); reset_duration_ = _server.getParam(prefix_ + "/reset_duration"); } } -- GitLab From ce61c2df3d5bcaafa6d7869de316598acb1936ea Mon Sep 17 00:00:00 2001 From: joanvallve Date: Fri, 10 Sep 2021 12:33:34 +0200 Subject: [PATCH 69/86] max points published and paramWithDefault --- include/subscriber_gnss_fix_publisher_ecef.h | 3 +- src/subscriber_gnss_fix_publisher_ecef.cpp | 57 +++++--- src/subscriber_gnss_receiver.cpp | 143 +++++++++---------- 3 files changed, 113 insertions(+), 90 deletions(-) diff --git a/include/subscriber_gnss_fix_publisher_ecef.h b/include/subscriber_gnss_fix_publisher_ecef.h index 73588e5..825ce34 100644 --- a/include/subscriber_gnss_fix_publisher_ecef.h +++ b/include/subscriber_gnss_fix_publisher_ecef.h @@ -37,7 +37,8 @@ class SubscriberGnssFixPublisherEcef : public Subscriber // publisher ros::Time last_publish_stamp_; - double period_; + double period_, line_size_; + int max_points_; bool pose_array_, pose_, marker_; geometry_msgs::PoseArray pose_array_msg_; geometry_msgs::PoseStamped pose_msg_; diff --git a/src/subscriber_gnss_fix_publisher_ecef.cpp b/src/subscriber_gnss_fix_publisher_ecef.cpp index afa3316..979d709 100644 --- a/src/subscriber_gnss_fix_publisher_ecef.cpp +++ b/src/subscriber_gnss_fix_publisher_ecef.cpp @@ -16,22 +16,20 @@ SubscriberGnssFixPublisherEcef::SubscriberGnssFixPublisherEcef(const std::string period_ = _server.getParam(prefix_ + "/period"); // marker color - try{ - std::cout << "SubscriberGnssFixPublisherEcef: taking user defined marker color...\n"; - Eigen::Vector4d col = _server.getParam(prefix_ + "/marker_color"); - marker_color_.r = col(0); - marker_color_.g = col(1); - marker_color_.b = col(2); - marker_color_.a = col(3); - } - catch(...) - { - std::cout << "SubscriberGnssFixPublisherEcef: using default marker color: BLUE\n"; - marker_color_.r = 0; - marker_color_.g = 0; - marker_color_.b = 1; - marker_color_.a = 1; - } + Eigen::Vector4d color = getParamWithDefault(_server, + prefix_ + "/marker_color", + (Eigen::Vector4d() << 0, 0, 1, 1).finished()); // blue + marker_color_.r = color(0); + marker_color_.g = color(1); + marker_color_.b = color(2); + marker_color_.a = color(3); + + max_points_ = getParamWithDefault(_server, + prefix_ + "/max_points", + 1e3); + line_size_ = getParamWithDefault(_server, + prefix_ + "/line_size", + 0.1); } void SubscriberGnssFixPublisherEcef::initialize(ros::NodeHandle& nh, const std::string& topic) @@ -49,7 +47,7 @@ void SubscriberGnssFixPublisherEcef::initialize(ros::NodeHandle& nh, const std:: marker_msg_.type = visualization_msgs::Marker::LINE_STRIP; marker_msg_.action = visualization_msgs::Marker::ADD; marker_msg_.ns = "trajectory"; - marker_msg_.scale.x = 0.1; + marker_msg_.scale.x = line_size_; marker_msg_.color = marker_color_; marker_msg_.pose.orientation = tf::createQuaternionMsgFromYaw(0); @@ -119,6 +117,19 @@ void SubscriberGnssFixPublisherEcef::publishPose(const geometry_msgs::Pose pose, if (pub_pose_array_.getNumSubscribers() != 0) { pose_array_msg_.header.stamp = stamp; + + if (max_points_ >= 0 and pose_array_msg_.poses.size() >= max_points_) + { + int i = 1; + while (i < pose_array_msg_.poses.size()) + { + pose_array_msg_.poses.erase(pose_array_msg_.poses.begin()+i); + i++; + } + //pose_array_msg_.poses.erase(pose_array_msg_.poses.begin(), + // pose_array_msg_.poses.begin() + max_points_/2); + } + pose_array_msg_.poses.push_back(pose); pub_pose_array_.publish(pose_array_msg_); @@ -126,6 +137,18 @@ void SubscriberGnssFixPublisherEcef::publishPose(const geometry_msgs::Pose pose, if (pub_marker_.getNumSubscribers() != 0) { marker_msg_.header.stamp = stamp; + + if (max_points_ >= 0 and marker_msg_.points.size() >= max_points_) + { + int i = 1; + while (i < marker_msg_.points.size()) + { + marker_msg_.points.erase(marker_msg_.points.begin()+i); + i++; + } + //marker_msg_.points.erase(marker_msg_.points.begin(), + // marker_msg_.points.begin() + max_points_/2); + } marker_msg_.points.push_back(pose.position); pub_marker_.publish(marker_msg_); diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index adf00c1..30deb8f 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -57,47 +57,32 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, // params topic_fix_ = _server.getParam(prefix_ + "/publish_fix/topic"); - // marker color - try{ - std::cout << "SubscriberGnssReceiver: taking user defined marker color...\n"; - Eigen::Vector4d col = _server.getParam(prefix_ + "/publish_fix/marker_color"); - std_msgs::ColorRGBA marker_color; - marker_color.r = col(0); - marker_color.g = col(1); - marker_color.b = col(2); - marker_color.a = col(3); - for (auto comp : comp_options_) - { - marker_msgs_[comp] = visualization_msgs::Marker(); - marker_msgs_.at(comp).color = marker_color; - } - } - catch(...) + // markers colors + Eigen::MatrixXd default_colors(12,4); + default_colors << 1, 1, 1, 1, + 1, 1, 0, 1, + 1, 0, 1, 1, + 0, 1, 1, 1, + .5, .5, 1, 1, + .5, 1, .5, 1, + 1, .5, .5, 1, + .5, .5, .5, 1, + 0, .5, .5, 1, + .5, .5, 0, 1, + .5, 0, .5, 1, + 0, 0, .5, 1; + + for (auto id_comp = 0; id_comp < comp_options_.size(); id_comp++) { - std::cout << "SubscriberGnssReceiver: taking default marker colors...\n"; - Eigen::MatrixXd colors(12,4); - colors << 1, 1, 1, 1, - 1, 1, 0, 1, - 1, 0, 1, 1, - 0, 1, 1, 1, - .5, .5, 1, 1, - .5, 1, .5, 1, - 1, .5, .5, 1, - .5, .5, .5, 1, - 0, .5, .5, 1, - .5, .5, 0, 1, - .5, 0, .5, 1, - 0, 0, .5, 1; - - for (auto id_comp = 0; id_comp < comp_options_.size(); id_comp++) - { - auto comp = comp_options_[id_comp]; - marker_msgs_[comp] = visualization_msgs::Marker(); - marker_msgs_.at(comp).color.r = colors(id_comp,0); - marker_msgs_.at(comp).color.g = colors(id_comp,1); - marker_msgs_.at(comp).color.b = colors(id_comp,2); - marker_msgs_.at(comp).color.a = colors(id_comp,3);; - } + auto comp = comp_options_[id_comp]; + Eigen::Vector4d color = getParamWithDefault(_server, + prefix_ + "/publish_fix/marker_color_" + comp, + default_colors.row(id_comp)); + marker_msgs_[comp] = visualization_msgs::Marker(); + marker_msgs_.at(comp).color.r = color(0); + marker_msgs_.at(comp).color.g = color(1); + marker_msgs_.at(comp).color.b = color(2); + marker_msgs_.at(comp).color.a = color(3); } // last fix @@ -110,38 +95,52 @@ SubscriberGnssReceiver::SubscriberGnssReceiver(const std::string& _unique_name, // GNSS OPTIONS (see gnss_utils.h) compute_pos_opt_ = GnssUtils::default_options; - try{compute_pos_opt_.sateph = _server.getParam (prefix_ + "/gnss_options/sateph"); // satellite ephemeris/clock (0:broadcast ephemeris,1:precise ephemeris,2:broadcast + SBAS,3:ephemeris option: broadcast + SSR_APC,4:broadcast + SSR_COM,5: QZSS LEX ephemeris - }catch(...){std::cout << "default sateph" << std::endl;} - try{compute_pos_opt_.ionoopt = _server.getParam (prefix_ + "/gnss_options/ionoopt"); // ionosphere option (0:correction off,1:broadcast mode,2:SBAS model,3:L1/L2 or L1/L5,4:estimation,5:IONEX TEC model,6:QZSS broadcast,7:QZSS LEX ionosphere,8:SLANT TEC mode) - }catch(...){std::cout << "default ionoopt" << std::endl;} - try{compute_pos_opt_.tropopt = _server.getParam (prefix_ + "/gnss_options/tropopt"); // troposphere option: (0:correction off,1:Saastamoinen model,2:SBAS model,3:troposphere option: ZTD estimation,4:ZTD+grad estimation,5:ZTD correction,6:ZTD+grad correction) - }catch(...){std::cout << "default tropopt" << std::endl;} - try{compute_pos_opt_.sbascorr = _server.getParam (prefix_ + "/gnss_options/sbascorr");// SBAS option (1:long term correction,2:fast correction,4:ionosphere correction,8:ranging) - }catch(...){std::cout << "default sbascorr" << std::endl;} - try{compute_pos_opt_.raim = _server.getParam (prefix_ + "/gnss_options/raim"); // RAIM enabled - }catch(...){std::cout << "default raim" << std::endl;} - try{compute_pos_opt_.elmin = _server.getParam(prefix_ + "/gnss_options/elmin"); // min elevation (rad) - }catch(...){std::cout << "default elmin" << std::endl;} - try{compute_pos_opt_.maxgdop = _server.getParam(prefix_ + "/gnss_options/maxgdop"); // maxgdop: reject threshold of gdop - }catch(...){std::cout << "default maxgdop" << std::endl;} - - try{compute_pos_opt_.GPS = _server.getParam(prefix_ + "/gnss_options/constellations/GPS"); /* navigation system */ - }catch(...){std::cout << "default GPS" << std::endl;} - try{compute_pos_opt_.SBS = _server.getParam(prefix_ + "/gnss_options/constellations/SBS"); - }catch(...){std::cout << "default SBS" << std::endl;} - try{compute_pos_opt_.GLO = _server.getParam(prefix_ + "/gnss_options/constellations/GLO"); - }catch(...){std::cout << "default GLO" << std::endl;} - try{compute_pos_opt_.GAL = _server.getParam(prefix_ + "/gnss_options/constellations/GAL"); - }catch(...){std::cout << "default GAL" << std::endl;} - try{compute_pos_opt_.QZS = _server.getParam(prefix_ + "/gnss_options/constellations/QZS"); - }catch(...){std::cout << "default QZS" << std::endl;} - try{compute_pos_opt_.CMP = _server.getParam(prefix_ + "/gnss_options/constellations/CMP"); - }catch(...){std::cout << "default CMP" << std::endl;} - try{compute_pos_opt_.IRN = _server.getParam(prefix_ + "/gnss_options/constellations/IRN"); - }catch(...){std::cout << "default IRN" << std::endl;} - try{compute_pos_opt_.LEO = _server.getParam(prefix_ + "/gnss_options/constellations/LEO"); - }catch(...){std::cout << "default LEO" << std::endl;} - + compute_pos_opt_.sateph = getParamWithDefault (_server, + prefix_ + "/gnss_options/sateph", + compute_pos_opt_.sateph); // satellite ephemeris/clock (0:broadcast ephemeris,1:precise ephemeris,2:broadcast + SBAS,3:ephemeris option: broadcast + SSR_APC,4:broadcast + SSR_COM,5: QZSS LEX ephemeris + compute_pos_opt_.ionoopt = getParamWithDefault (_server, + prefix_ + "/gnss_options/ionoopt", + compute_pos_opt_.ionoopt); // ionosphere option (0:correction off,1:broadcast mode,2:SBAS model,3:L1/L2 or L1/L5,4:estimation,5:IONEX TEC model,6:QZSS broadcast,7:QZSS LEX ionosphere,8:SLANT TEC mode) + compute_pos_opt_.tropopt = getParamWithDefault (_server, + prefix_ + "/gnss_options/tropopt", + compute_pos_opt_.tropopt); // troposphere option: (0:correction off,1:Saastamoinen model,2:SBAS model,3:troposphere option: ZTD estimation,4:ZTD+grad estimation,5:ZTD correction,6:ZTD+grad correction) + compute_pos_opt_.sbascorr = getParamWithDefault (_server, + prefix_ + "/gnss_options/sbascorr", + compute_pos_opt_.sbascorr);// SBAS option (1:long term correction,2:fast correction,4:ionosphere correction,8:ranging) + compute_pos_opt_.raim = getParamWithDefault (_server, + prefix_ + "/gnss_options/raim", + compute_pos_opt_.raim); // RAIM enabled + compute_pos_opt_.elmin = getParamWithDefault(_server, + prefix_ + "/gnss_options/elmin", + compute_pos_opt_.elmin); // min elevation (rad) + compute_pos_opt_.maxgdop = getParamWithDefault(_server, + prefix_ + "/gnss_options/maxgdop", + compute_pos_opt_.maxgdop); // maxgdop: reject threshold of gdop + // Constellations + compute_pos_opt_.GPS = getParamWithDefault(_server, + prefix_ + "/gnss_options/constellations/GPS", + compute_pos_opt_.GPS); + compute_pos_opt_.SBS = getParamWithDefault(_server, + prefix_ + "/gnss_options/constellations/GPS", + compute_pos_opt_.SBS); + compute_pos_opt_.GLO = getParamWithDefault(_server, + prefix_ + "/gnss_options/constellations/GPS", + compute_pos_opt_.GLO); + compute_pos_opt_.GAL = getParamWithDefault(_server, + prefix_ + "/gnss_options/constellations/GPS", + compute_pos_opt_.GAL); + compute_pos_opt_.QZS = getParamWithDefault(_server, + prefix_ + "/gnss_options/constellations/GPS", + compute_pos_opt_.QZS); + compute_pos_opt_.CMP = getParamWithDefault(_server, + prefix_ + "/gnss_options/constellations/GPS", + compute_pos_opt_.CMP); + compute_pos_opt_.IRN = getParamWithDefault(_server, + prefix_ + "/gnss_options/constellations/GPS", + compute_pos_opt_.IRN); + compute_pos_opt_.LEO = getParamWithDefault(_server, + prefix_ + "/gnss_options/constellations/GPS", + compute_pos_opt_.LEO); // user print ROS_INFO("Waiting for satellites..."); } -- GitLab From 0a42088d58cfad7dada03691d81c85b375d1f6f6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Fri, 22 Oct 2021 10:47:46 +0200 Subject: [PATCH 70/86] try&catch process capture --- src/subscriber_gnss_receiver.cpp | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index 30deb8f..974df7a 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -219,7 +219,16 @@ void SubscriberGnssReceiver::createCaptureAndProcess(const ros::Time& _stamp) snapshot_ptr); //ROS_INFO("Capture GNSS created!"); - cap_gnss_ptr->process(); + try + { + cap_gnss_ptr->process(); + } + catch (std::exception& e) + { + WOLF_ERROR("SubscriberGnssReceiver: Error processing capture gnss"); + cap_gnss_ptr->print(1, false, false, false); + std::cerr << "Exception caught : " << e.what() << std::endl; + } //ROS_INFO("Capture GNSS processed!"); } -- GitLab From b2847d0205d373fa5dcc3dd4ef12c065b23a95b1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Wed, 1 Dec 2021 14:08:31 +0100 Subject: [PATCH 71/86] Add LICENSE --- LICENSE | 619 ++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 619 insertions(+) create mode 100644 LICENSE diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..281d399 --- /dev/null +++ b/LICENSE @@ -0,0 +1,619 @@ + GNU GENERAL PUBLIC LICENSE + Version 3, 29 June 2007 + + Copyright (C) 2007 Free Software Foundation, Inc. + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + Preamble + + The GNU General Public License is a free, copyleft license for +software and other kinds of works. + + The licenses for most software and other practical works are designed +to take away your freedom to share and change the works. By contrast, +the GNU General Public License is intended to guarantee your freedom to +share and change all versions of a program--to make sure it remains free +software for all its users. We, the Free Software Foundation, use the +GNU General Public License for most of our software; it applies also to +any other work released this way by its authors. You can apply it to +your programs, too. + + When we speak of free software, we are referring to freedom, not +price. Our General Public Licenses are designed to make sure that you +have the freedom to distribute copies of free software (and charge for +them if you wish), that you receive source code or can get it if you +want it, that you can change the software or use pieces of it in new +free programs, and that you know you can do these things. + + To protect your rights, we need to prevent others from denying you +these rights or asking you to surrender the rights. Therefore, you have +certain responsibilities if you distribute copies of the software, or if +you modify it: responsibilities to respect the freedom of others. + + For example, if you distribute copies of such a program, whether +gratis or for a fee, you must pass on to the recipients the same +freedoms that you received. You must make sure that they, too, receive +or can get the source code. And you must show them these terms so they +know their rights. + + Developers that use the GNU GPL protect your rights with two steps: +(1) assert copyright on the software, and (2) offer you this License +giving you legal permission to copy, distribute and/or modify it. + + For the developers' and authors' protection, the GPL clearly explains +that there is no warranty for this free software. For both users' and +authors' sake, the GPL requires that modified versions be marked as +changed, so that their problems will not be attributed erroneously to +authors of previous versions. + + Some devices are designed to deny users access to install or run +modified versions of the software inside them, although the manufacturer +can do so. This is fundamentally incompatible with the aim of +protecting users' freedom to change the software. The systematic +pattern of such abuse occurs in the area of products for individuals to +use, which is precisely where it is most unacceptable. Therefore, we +have designed this version of the GPL to prohibit the practice for those +products. If such problems arise substantially in other domains, we +stand ready to extend this provision to those domains in future versions +of the GPL, as needed to protect the freedom of users. + + Finally, every program is threatened constantly by software patents. +States should not allow patents to restrict development and use of +software on general-purpose computers, but in those that do, we wish to +avoid the special danger that patents applied to a free program could +make it effectively proprietary. To prevent this, the GPL assures that +patents cannot be used to render the program non-free. + + The precise terms and conditions for copying, distribution and +modification follow. + + TERMS AND CONDITIONS + + 0. Definitions. + + "This License" refers to version 3 of the GNU General Public License. + + "Copyright" also means copyright-like laws that apply to other kinds of +works, such as semiconductor masks. + + "The Program" refers to any copyrightable work licensed under this +License. Each licensee is addressed as "you". "Licensees" and +"recipients" may be individuals or organizations. + + To "modify" a work means to copy from or adapt all or part of the work +in a fashion requiring copyright permission, other than the making of an +exact copy. The resulting work is called a "modified version" of the +earlier work or a work "based on" the earlier work. + + A "covered work" means either the unmodified Program or a work based +on the Program. + + To "propagate" a work means to do anything with it that, without +permission, would make you directly or secondarily liable for +infringement under applicable copyright law, except executing it on a +computer or modifying a private copy. Propagation includes copying, +distribution (with or without modification), making available to the +public, and in some countries other activities as well. + + To "convey" a work means any kind of propagation that enables other +parties to make or receive copies. Mere interaction with a user through +a computer network, with no transfer of a copy, is not conveying. + + An interactive user interface displays "Appropriate Legal Notices" +to the extent that it includes a convenient and prominently visible +feature that (1) displays an appropriate copyright notice, and (2) +tells the user that there is no warranty for the work (except to the +extent that warranties are provided), that licensees may convey the +work under this License, and how to view a copy of this License. If +the interface presents a list of user commands or options, such as a +menu, a prominent item in the list meets this criterion. + + 1. Source Code. + + The "source code" for a work means the preferred form of the work +for making modifications to it. "Object code" means any non-source +form of a work. + + A "Standard Interface" means an interface that either is an official +standard defined by a recognized standards body, or, in the case of +interfaces specified for a particular programming language, one that +is widely used among developers working in that language. + + The "System Libraries" of an executable work include anything, other +than the work as a whole, that (a) is included in the normal form of +packaging a Major Component, but which is not part of that Major +Component, and (b) serves only to enable use of the work with that +Major Component, or to implement a Standard Interface for which an +implementation is available to the public in source code form. A +"Major Component", in this context, means a major essential component +(kernel, window system, and so on) of the specific operating system +(if any) on which the executable work runs, or a compiler used to +produce the work, or an object code interpreter used to run it. + + The "Corresponding Source" for a work in object code form means all +the source code needed to generate, install, and (for an executable +work) run the object code and to modify the work, including scripts to +control those activities. However, it does not include the work's +System Libraries, or general-purpose tools or generally available free +programs which are used unmodified in performing those activities but +which are not part of the work. For example, Corresponding Source +includes interface definition files associated with source files for +the work, and the source code for shared libraries and dynamically +linked subprograms that the work is specifically designed to require, +such as by intimate data communication or control flow between those +subprograms and other parts of the work. + + The Corresponding Source need not include anything that users +can regenerate automatically from other parts of the Corresponding +Source. + + The Corresponding Source for a work in source code form is that +same work. + + 2. Basic Permissions. + + All rights granted under this License are granted for the term of +copyright on the Program, and are irrevocable provided the stated +conditions are met. This License explicitly affirms your unlimited +permission to run the unmodified Program. The output from running a +covered work is covered by this License only if the output, given its +content, constitutes a covered work. This License acknowledges your +rights of fair use or other equivalent, as provided by copyright law. + + You may make, run and propagate covered works that you do not +convey, without conditions so long as your license otherwise remains +in force. You may convey covered works to others for the sole purpose +of having them make modifications exclusively for you, or provide you +with facilities for running those works, provided that you comply with +the terms of this License in conveying all material for which you do +not control copyright. Those thus making or running the covered works +for you must do so exclusively on your behalf, under your direction +and control, on terms that prohibit them from making any copies of +your copyrighted material outside their relationship with you. + + Conveying under any other circumstances is permitted solely under +the conditions stated below. Sublicensing is not allowed; section 10 +makes it unnecessary. + + 3. Protecting Users' Legal Rights From Anti-Circumvention Law. + + No covered work shall be deemed part of an effective technological +measure under any applicable law fulfilling obligations under article +11 of the WIPO copyright treaty adopted on 20 December 1996, or +similar laws prohibiting or restricting circumvention of such +measures. + + When you convey a covered work, you waive any legal power to forbid +circumvention of technological measures to the extent such circumvention +is effected by exercising rights under this License with respect to +the covered work, and you disclaim any intention to limit operation or +modification of the work as a means of enforcing, against the work's +users, your or third parties' legal rights to forbid circumvention of +technological measures. + + 4. Conveying Verbatim Copies. + + You may convey verbatim copies of the Program's source code as you +receive it, in any medium, provided that you conspicuously and +appropriately publish on each copy an appropriate copyright notice; +keep intact all notices stating that this License and any +non-permissive terms added in accord with section 7 apply to the code; +keep intact all notices of the absence of any warranty; and give all +recipients a copy of this License along with the Program. + + You may charge any price or no price for each copy that you convey, +and you may offer support or warranty protection for a fee. + + 5. Conveying Modified Source Versions. + + You may convey a work based on the Program, or the modifications to +produce it from the Program, in the form of source code under the +terms of section 4, provided that you also meet all of these conditions: + + a) The work must carry prominent notices stating that you modified + it, and giving a relevant date. + + b) The work must carry prominent notices stating that it is + released under this License and any conditions added under section + 7. This requirement modifies the requirement in section 4 to + "keep intact all notices". + + c) You must license the entire work, as a whole, under this + License to anyone who comes into possession of a copy. This + License will therefore apply, along with any applicable section 7 + additional terms, to the whole of the work, and all its parts, + regardless of how they are packaged. This License gives no + permission to license the work in any other way, but it does not + invalidate such permission if you have separately received it. + + d) If the work has interactive user interfaces, each must display + Appropriate Legal Notices; however, if the Program has interactive + interfaces that do not display Appropriate Legal Notices, your + work need not make them do so. + + A compilation of a covered work with other separate and independent +works, which are not by their nature extensions of the covered work, +and which are not combined with it such as to form a larger program, +in or on a volume of a storage or distribution medium, is called an +"aggregate" if the compilation and its resulting copyright are not +used to limit the access or legal rights of the compilation's users +beyond what the individual works permit. Inclusion of a covered work +in an aggregate does not cause this License to apply to the other +parts of the aggregate. + + 6. Conveying Non-Source Forms. + + You may convey a covered work in object code form under the terms +of sections 4 and 5, provided that you also convey the +machine-readable Corresponding Source under the terms of this License, +in one of these ways: + + a) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by the + Corresponding Source fixed on a durable physical medium + customarily used for software interchange. + + b) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by a + written offer, valid for at least three years and valid for as + long as you offer spare parts or customer support for that product + model, to give anyone who possesses the object code either (1) a + copy of the Corresponding Source for all the software in the + product that is covered by this License, on a durable physical + medium customarily used for software interchange, for a price no + more than your reasonable cost of physically performing this + conveying of source, or (2) access to copy the + Corresponding Source from a network server at no charge. + + c) Convey individual copies of the object code with a copy of the + written offer to provide the Corresponding Source. This + alternative is allowed only occasionally and noncommercially, and + only if you received the object code with such an offer, in accord + with subsection 6b. + + d) Convey the object code by offering access from a designated + place (gratis or for a charge), and offer equivalent access to the + Corresponding Source in the same way through the same place at no + further charge. You need not require recipients to copy the + Corresponding Source along with the object code. If the place to + copy the object code is a network server, the Corresponding Source + may be on a different server (operated by you or a third party) + that supports equivalent copying facilities, provided you maintain + clear directions next to the object code saying where to find the + Corresponding Source. Regardless of what server hosts the + Corresponding Source, you remain obligated to ensure that it is + available for as long as needed to satisfy these requirements. + + e) Convey the object code using peer-to-peer transmission, provided + you inform other peers where the object code and Corresponding + Source of the work are being offered to the general public at no + charge under subsection 6d. + + A separable portion of the object code, whose source code is excluded +from the Corresponding Source as a System Library, need not be +included in conveying the object code work. + + A "User Product" is either (1) a "consumer product", which means any +tangible personal property which is normally used for personal, family, +or household purposes, or (2) anything designed or sold for incorporation +into a dwelling. In determining whether a product is a consumer product, +doubtful cases shall be resolved in favor of coverage. For a particular +product received by a particular user, "normally used" refers to a +typical or common use of that class of product, regardless of the status +of the particular user or of the way in which the particular user +actually uses, or expects or is expected to use, the product. A product +is a consumer product regardless of whether the product has substantial +commercial, industrial or non-consumer uses, unless such uses represent +the only significant mode of use of the product. + + "Installation Information" for a User Product means any methods, +procedures, authorization keys, or other information required to install +and execute modified versions of a covered work in that User Product from +a modified version of its Corresponding Source. The information must +suffice to ensure that the continued functioning of the modified object +code is in no case prevented or interfered with solely because +modification has been made. + + If you convey an object code work under this section in, or with, or +specifically for use in, a User Product, and the conveying occurs as +part of a transaction in which the right of possession and use of the +User Product is transferred to the recipient in perpetuity or for a +fixed term (regardless of how the transaction is characterized), the +Corresponding Source conveyed under this section must be accompanied +by the Installation Information. But this requirement does not apply +if neither you nor any third party retains the ability to install +modified object code on the User Product (for example, the work has +been installed in ROM). + + The requirement to provide Installation Information does not include a +requirement to continue to provide support service, warranty, or updates +for a work that has been modified or installed by the recipient, or for +the User Product in which it has been modified or installed. Access to a +network may be denied when the modification itself materially and +adversely affects the operation of the network or violates the rules and +protocols for communication across the network. + + Corresponding Source conveyed, and Installation Information provided, +in accord with this section must be in a format that is publicly +documented (and with an implementation available to the public in +source code form), and must require no special password or key for +unpacking, reading or copying. + + 7. Additional Terms. + + "Additional permissions" are terms that supplement the terms of this +License by making exceptions from one or more of its conditions. +Additional permissions that are applicable to the entire Program shall +be treated as though they were included in this License, to the extent +that they are valid under applicable law. If additional permissions +apply only to part of the Program, that part may be used separately +under those permissions, but the entire Program remains governed by +this License without regard to the additional permissions. + + When you convey a copy of a covered work, you may at your option +remove any additional permissions from that copy, or from any part of +it. (Additional permissions may be written to require their own +removal in certain cases when you modify the work.) You may place +additional permissions on material, added by you to a covered work, +for which you have or can give appropriate copyright permission. + + Notwithstanding any other provision of this License, for material you +add to a covered work, you may (if authorized by the copyright holders of +that material) supplement the terms of this License with terms: + + a) Disclaiming warranty or limiting liability differently from the + terms of sections 15 and 16 of this License; or + + b) Requiring preservation of specified reasonable legal notices or + author attributions in that material or in the Appropriate Legal + Notices displayed by works containing it; or + + c) Prohibiting misrepresentation of the origin of that material, or + requiring that modified versions of such material be marked in + reasonable ways as different from the original version; or + + d) Limiting the use for publicity purposes of names of licensors or + authors of the material; or + + e) Declining to grant rights under trademark law for use of some + trade names, trademarks, or service marks; or + + f) Requiring indemnification of licensors and authors of that + material by anyone who conveys the material (or modified versions of + it) with contractual assumptions of liability to the recipient, for + any liability that these contractual assumptions directly impose on + those licensors and authors. + + All other non-permissive additional terms are considered "further +restrictions" within the meaning of section 10. If the Program as you +received it, or any part of it, contains a notice stating that it is +governed by this License along with a term that is a further +restriction, you may remove that term. If a license document contains +a further restriction but permits relicensing or conveying under this +License, you may add to a covered work material governed by the terms +of that license document, provided that the further restriction does +not survive such relicensing or conveying. + + If you add terms to a covered work in accord with this section, you +must place, in the relevant source files, a statement of the +additional terms that apply to those files, or a notice indicating +where to find the applicable terms. + + Additional terms, permissive or non-permissive, may be stated in the +form of a separately written license, or stated as exceptions; +the above requirements apply either way. + + 8. Termination. + + You may not propagate or modify a covered work except as expressly +provided under this License. Any attempt otherwise to propagate or +modify it is void, and will automatically terminate your rights under +this License (including any patent licenses granted under the third +paragraph of section 11). + + However, if you cease all violation of this License, then your +license from a particular copyright holder is reinstated (a) +provisionally, unless and until the copyright holder explicitly and +finally terminates your license, and (b) permanently, if the copyright +holder fails to notify you of the violation by some reasonable means +prior to 60 days after the cessation. + + Moreover, your license from a particular copyright holder is +reinstated permanently if the copyright holder notifies you of the +violation by some reasonable means, this is the first time you have +received notice of violation of this License (for any work) from that +copyright holder, and you cure the violation prior to 30 days after +your receipt of the notice. + + Termination of your rights under this section does not terminate the +licenses of parties who have received copies or rights from you under +this License. If your rights have been terminated and not permanently +reinstated, you do not qualify to receive new licenses for the same +material under section 10. + + 9. Acceptance Not Required for Having Copies. + + You are not required to accept this License in order to receive or +run a copy of the Program. Ancillary propagation of a covered work +occurring solely as a consequence of using peer-to-peer transmission +to receive a copy likewise does not require acceptance. However, +nothing other than this License grants you permission to propagate or +modify any covered work. These actions infringe copyright if you do +not accept this License. Therefore, by modifying or propagating a +covered work, you indicate your acceptance of this License to do so. + + 10. Automatic Licensing of Downstream Recipients. + + Each time you convey a covered work, the recipient automatically +receives a license from the original licensors, to run, modify and +propagate that work, subject to this License. You are not responsible +for enforcing compliance by third parties with this License. + + An "entity transaction" is a transaction transferring control of an +organization, or substantially all assets of one, or subdividing an +organization, or merging organizations. If propagation of a covered +work results from an entity transaction, each party to that +transaction who receives a copy of the work also receives whatever +licenses to the work the party's predecessor in interest had or could +give under the previous paragraph, plus a right to possession of the +Corresponding Source of the work from the predecessor in interest, if +the predecessor has it or can get it with reasonable efforts. + + You may not impose any further restrictions on the exercise of the +rights granted or affirmed under this License. For example, you may +not impose a license fee, royalty, or other charge for exercise of +rights granted under this License, and you may not initiate litigation +(including a cross-claim or counterclaim in a lawsuit) alleging that +any patent claim is infringed by making, using, selling, offering for +sale, or importing the Program or any portion of it. + + 11. Patents. + + A "contributor" is a copyright holder who authorizes use under this +License of the Program or a work on which the Program is based. The +work thus licensed is called the contributor's "contributor version". + + A contributor's "essential patent claims" are all patent claims +owned or controlled by the contributor, whether already acquired or +hereafter acquired, that would be infringed by some manner, permitted +by this License, of making, using, or selling its contributor version, +but do not include claims that would be infringed only as a +consequence of further modification of the contributor version. For +purposes of this definition, "control" includes the right to grant +patent sublicenses in a manner consistent with the requirements of +this License. + + Each contributor grants you a non-exclusive, worldwide, royalty-free +patent license under the contributor's essential patent claims, to +make, use, sell, offer for sale, import and otherwise run, modify and +propagate the contents of its contributor version. + + In the following three paragraphs, a "patent license" is any express +agreement or commitment, however denominated, not to enforce a patent +(such as an express permission to practice a patent or covenant not to +sue for patent infringement). To "grant" such a patent license to a +party means to make such an agreement or commitment not to enforce a +patent against the party. + + If you convey a covered work, knowingly relying on a patent license, +and the Corresponding Source of the work is not available for anyone +to copy, free of charge and under the terms of this License, through a +publicly available network server or other readily accessible means, +then you must either (1) cause the Corresponding Source to be so +available, or (2) arrange to deprive yourself of the benefit of the +patent license for this particular work, or (3) arrange, in a manner +consistent with the requirements of this License, to extend the patent +license to downstream recipients. "Knowingly relying" means you have +actual knowledge that, but for the patent license, your conveying the +covered work in a country, or your recipient's use of the covered work +in a country, would infringe one or more identifiable patents in that +country that you have reason to believe are valid. + + If, pursuant to or in connection with a single transaction or +arrangement, you convey, or propagate by procuring conveyance of, a +covered work, and grant a patent license to some of the parties +receiving the covered work authorizing them to use, propagate, modify +or convey a specific copy of the covered work, then the patent license +you grant is automatically extended to all recipients of the covered +work and works based on it. + + A patent license is "discriminatory" if it does not include within +the scope of its coverage, prohibits the exercise of, or is +conditioned on the non-exercise of one or more of the rights that are +specifically granted under this License. You may not convey a covered +work if you are a party to an arrangement with a third party that is +in the business of distributing software, under which you make payment +to the third party based on the extent of your activity of conveying +the work, and under which the third party grants, to any of the +parties who would receive the covered work from you, a discriminatory +patent license (a) in connection with copies of the covered work +conveyed by you (or copies made from those copies), or (b) primarily +for and in connection with specific products or compilations that +contain the covered work, unless you entered into that arrangement, +or that patent license was granted, prior to 28 March 2007. + + Nothing in this License shall be construed as excluding or limiting +any implied license or other defenses to infringement that may +otherwise be available to you under applicable patent law. + + 12. No Surrender of Others' Freedom. + + If conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot convey a +covered work so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you may +not convey it at all. For example, if you agree to terms that obligate you +to collect a royalty for further conveying from those to whom you convey +the Program, the only way you could satisfy both those terms and this +License would be to refrain entirely from conveying the Program. + + 13. Use with the GNU Affero General Public License. + + Notwithstanding any other provision of this License, you have +permission to link or combine any covered work with a work licensed +under version 3 of the GNU Affero General Public License into a single +combined work, and to convey the resulting work. The terms of this +License will continue to apply to the part which is the covered work, +but the special requirements of the GNU Affero General Public License, +section 13, concerning interaction through a network will apply to the +combination as such. + + 14. Revised Versions of this License. + + The Free Software Foundation may publish revised and/or new versions of +the GNU General Public License from time to time. Such new versions will +be similar in spirit to the present version, but may differ in detail to +address new problems or concerns. + + Each version is given a distinguishing version number. If the +Program specifies that a certain numbered version of the GNU General +Public License "or any later version" applies to it, you have the +option of following the terms and conditions either of that numbered +version or of any later version published by the Free Software +Foundation. If the Program does not specify a version number of the +GNU General Public License, you may choose any version ever published +by the Free Software Foundation. + + If the Program specifies that a proxy can decide which future +versions of the GNU General Public License can be used, that proxy's +public statement of acceptance of a version permanently authorizes you +to choose that version for the Program. + + Later license versions may give you additional or different +permissions. However, no additional obligations are imposed on any +author or copyright holder as a result of your choosing to follow a +later version. + + 15. Disclaimer of Warranty. + + THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY +APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT +HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY +OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, +THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM +IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF +ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. Limitation of Liability. + + IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING +WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS +THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY +GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE +USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF +DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD +PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), +EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF +SUCH DAMAGES. + + 17. Interpretation of Sections 15 and 16. + + If the disclaimer of warranty and limitation of liability provided +above cannot be given local legal effect according to their terms, +reviewing courts shall apply local law that most closely approximates +an absolute waiver of all civil liability in connection with the +Program, unless a warranty or assumption of liability accompanies a +copy of the Program in return for a fee. -- GitLab From ef51371cd31ce5586874d9aabce14ffbbd74f49b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Wed, 1 Dec 2021 14:23:45 +0100 Subject: [PATCH 72/86] Upload New File --- license_header_2021.txt | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) create mode 100644 license_header_2021.txt diff --git a/license_header_2021.txt b/license_header_2021.txt new file mode 100644 index 0000000..c75a6f2 --- /dev/null +++ b/license_header_2021.txt @@ -0,0 +1,17 @@ +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . -- GitLab From df8e1702ac1df79dc242b2a96ab122355a04fe84 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Thu, 2 Dec 2021 11:16:31 +0100 Subject: [PATCH 73/86] Update .gitlab-ci.yml file --- .gitlab-ci.yml | 194 +++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 194 insertions(+) create mode 100644 .gitlab-ci.yml diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml new file mode 100644 index 0000000..48accf2 --- /dev/null +++ b/.gitlab-ci.yml @@ -0,0 +1,194 @@ +stages: + - license + - build_and_test + - demos + +############ YAML ANCHORS ############ +.preliminaries_template: &preliminaries_definition + ## Install ssh-agent if not already installed, it is required by Docker. + ## (change apt-get to yum if you use an RPM-based image) + - 'which ssh-agent || ( apt-get update -y && apt-get install openssh-client -y )' + + ## Run ssh-agent (inside the build environment) + - eval $(ssh-agent -s) + + ## Add the SSH key stored in SSH_PRIVATE_KEY variable to the agent store + ## We're using tr to fix line endings which makes ed25519 keys work + ## without extra base64 encoding. + ## https://gitlab.com/gitlab-examples/ssh-private-key/issues/1#note_48526556 + - mkdir -p ~/.ssh + - chmod 700 ~/.ssh + - echo "$SSH_PRIVATE_KEY" | tr -d '\r' | ssh-add - > /dev/null + # - echo "$SSH_KNOWN_HOSTS" > $HOME/.ssh/known_hosts + - ssh-keyscan -H -p 2202 gitlab.iri.upc.edu >> $HOME/.ssh/known_hosts + + # update apt + - apt-get update + + # create ci_deps folder (if not exists) + - mkdir -pv ci_deps + +.license_header_template: &license_header_definition + - cd $CI_PROJECT_DIR + + # configure git + - export CI_NEW_BRANCH=ci_processing$RANDOM + - echo creating new temporary branch... $CI_NEW_BRANCH + - git config --global user.email "${CI_EMAIL}" + - git config --global user.name "${CI_USERNAME}" + - git checkout -b $CI_NEW_BRANCH # temporary branch + + # license headers + - export CURRENT_YEAR=$( date +'%Y' ) + - echo "current year:" ${CURRENT_YEAR} + - if [ -f license_header_${CURRENT_YEAR}.txt ]; then + # add license headers to new files + - echo "File license_header_${CURRENT_YEAR}.txt already exists. License headers are assumed to be updated. Adding headers to new files..." + - ./ci_deps/wolf/wolf_scripts/license_manager.sh --add --path=. --license-header=license_header_${CURRENT_YEAR}.txt --exclude=ci_deps + - else + # update license headers of all files + - export PREV_YEAR=$(( CURRENT_YEAR-1 )) + - echo "Creating new file license_header_${CURRENT_YEAR}.txt..." + - git mv license_header_${PREV_YEAR}.txt license_header_${CURRENT_YEAR}.txt + - sed -i "s/${PREV_YEAR}/${PREV_YEAR},${CURRENT_YEAR}/g" license_header_${CURRENT_YEAR}.txt + - ./ci_deps/wolf/wolf_scripts/license_manager.sh --update --path=. --license-header=license_header_${CURRENT_YEAR}.txt --exclude=ci_deps + - fi + + # push changes (if any) + - if git commit -a -m "[skip ci] license headers added or modified" ; then + - git remote set-url --push origin "ssh://git@gitlab.iri.upc.edu:2202/${CI_PROJECT_PATH}.git" + - git push origin $CI_NEW_BRANCH:${CI_COMMIT_REF_NAME} + - else + - echo "No changes, nothing to commit!" + - fi + +.install_wolf_template: &install_wolf_definition + - cd ${CI_PROJECT_DIR}/ci_deps + - if [ -d wolf ]; then + - echo "directory wolf exists" + - cd wolf + - git pull + - git checkout $WOLF_CORE_BRANCH + - else + - git clone ssh://git@gitlab.iri.upc.edu:2202/mobile_robotics/wolf_projects/wolf_lib/wolf.git + - cd wolf + - git checkout $WOLF_CORE_BRANCH + - fi + - mkdir -pv build + - cd build + - cmake -DCMAKE_BUILD_TYPE=release -DBUILD_EXAMPLES=ON -DBUILD_TESTS=ON .. + - make -j$(nproc) + - ctest -j$(nproc) + - make install + +.install_gnssutils_template: &install_gnssutils_definition + - cd ${CI_PROJECT_DIR}/ci_deps + - if [ -d gnss_utils ]; then + - echo "directory gnss_utils exists" + - cd gnss_utils + - git pull + - else + - git clone ssh://git@gitlab.iri.upc.edu:2202/mobile_robotics/gauss_project/gnss_utils.git + - cd gnss_utils + - git submodule update --init + - fi + - mkdir -pv build + - cd build + - cmake -DCMAKE_BUILD_TYPE=release -DBUILD_EXAMPLES=ON -DBUILD_TESTS=ON .. + - make -j$(nproc) + - ctest -j$(nproc) + - make install + +.install_wolfgnss_template: &install_wolfgnss_definition + - cd ${CI_PROJECT_DIR}/ci_deps + - if [ -d gnss ]; then + - echo "directory gnss exists" + - cd gnss + - git pull + - git checkout $WOLF_GNSS_BRANCH + - else + - git clone ssh://git@gitlab.iri.upc.edu:2202/mobile_robotics/wolf_projects/wolf_lib/gnss.git + - cd gnss + - git checkout $WOLF_GNSS_BRANCH + - fi + - mkdir -pv build + - cd build + - cmake -DCMAKE_BUILD_TYPE=release -DBUILD_EXAMPLES=ON -DBUILD_TESTS=ON .. + - make -j$(nproc) + - ctest -j$(nproc) + - make install + +.clone_wolfrosnode_template: &clone_wolfrosnode_definition + - echo "TODO clone wolf_ros_node branch ${WOLF_ROS_CORE_BRANCH}" + +.build_and_test_template: &build_and_test_definition + - echo "TODO" + +############ LICENSE HEADERS ############ +license_headers: + stage: license + image: labrobotica/wolf_deps:16.04 + cache: + - key: wolf-xenial + paths: + - ci_deps/wolf/ + except: + - master + before_script: + - *preliminaries_definition + - *install_wolf_definition + script: + - *license_header_definition + +############ UBUNTU 16.04 TEST ############ +build_and_test:xenial: + stage: build_and_test + image: labrobotica/wolf_deps:16.04 + cache: + - key: wolf-xenial + paths: + - ci_deps/wolf/ + - key: gnssutils-xenial + paths: + - ci_deps/gnss_utils/ + except: + - master + before_script: + - *preliminaries_definition + - *install_wolf_definition + - *install_wolfgnss_definition + - *clone_wolfrosnode_definition + script: + - *build_and_test_definition + +############ UBUNTU 18.04 TEST ############ +build_and_test:bionic: + stage: build_and_test + image: labrobotica/wolf_deps:18.04 + cache: + - key: wolf-bionic + paths: + - ci_deps/wolf/ + - key: gnssutils-bionic + paths: + - ci_deps/gnss_utils/ + except: + - master + before_script: + - *preliminaries_definition + - *install_wolf_definition + - *install_wolfgnss_definition + - *clone_wolfrosnode_definition + script: + - *build_and_test_definition + +############ RUN DEMOS ############ +demo_gnss: + stage: demos + variables: + WOLF_CORE_BRANCH: $WOLF_CORE_BRANCH + WOLF_GNSS_BRANCH: $WOLF_GNSS_BRANCH + WOLF_ROS_CORE_BRANCH: $WOLF_ROS_CORE_BRANCH + WOLF_ROS_GNSS_BRANCH: $CI_COMMIT_BRANCH + trigger: + project: mobile_robotics/wolf_projects/wolf_ros/demos/wolf_demo_gnss -- GitLab From 8468c357f5ebd4829477902a70dadfc6972f820c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Thu, 2 Dec 2021 11:21:39 +0100 Subject: [PATCH 74/86] Update .gitlab-ci.yml file --- .gitlab-ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index 48accf2..49994d0 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -107,7 +107,7 @@ stages: - git pull - git checkout $WOLF_GNSS_BRANCH - else - - git clone ssh://git@gitlab.iri.upc.edu:2202/mobile_robotics/wolf_projects/wolf_lib/gnss.git + - git clone ssh://git@gitlab.iri.upc.edu:2202/mobile_robotics/wolf_projects/wolf_lib/plugins/gnss.git - cd gnss - git checkout $WOLF_GNSS_BRANCH - fi -- GitLab From e4e082d300d33f4613d510708c471065b9141171 Mon Sep 17 00:00:00 2001 From: cont-integration Date: Thu, 2 Dec 2021 11:28:22 +0000 Subject: [PATCH 75/86] [skip ci] license headers added or modified --- include/publisher_gnss_accuracy.h | 21 +++++++++++++++++++ include/publisher_gnss_fix.h | 21 +++++++++++++++++++ include/publisher_gnss_tf.h | 21 +++++++++++++++++++ include/publisher_tracker_gnss_info.h | 21 +++++++++++++++++++ include/subscriber_gnss.h | 21 +++++++++++++++++++ include/subscriber_gnss_fix.h | 21 +++++++++++++++++++ ...bscriber_gnss_fix_novatel_publisher_ecef.h | 21 +++++++++++++++++++ include/subscriber_gnss_fix_publisher_ecef.h | 21 +++++++++++++++++++ include/subscriber_gnss_novatel.h | 21 +++++++++++++++++++ include/subscriber_gnss_receiver.h | 21 +++++++++++++++++++ include/subscriber_gnss_tdcp.h | 21 +++++++++++++++++++ include/subscriber_gnss_ublox.h | 21 +++++++++++++++++++ src/publisher_gnss_accuracy.cpp | 21 +++++++++++++++++++ src/publisher_gnss_fix.cpp | 21 +++++++++++++++++++ src/publisher_gnss_tf.cpp | 21 +++++++++++++++++++ src/publisher_tracker_gnss_info.cpp | 21 +++++++++++++++++++ src/subscriber_gnss.cpp | 21 +++++++++++++++++++ src/subscriber_gnss_fix.cpp | 21 +++++++++++++++++++ ...criber_gnss_fix_novatel_publisher_ecef.cpp | 21 +++++++++++++++++++ src/subscriber_gnss_fix_publisher_ecef.cpp | 21 +++++++++++++++++++ src/subscriber_gnss_novatel.cpp | 21 +++++++++++++++++++ src/subscriber_gnss_receiver.cpp | 21 +++++++++++++++++++ src/subscriber_gnss_tdcp.cpp | 21 +++++++++++++++++++ src/subscriber_gnss_ublox.cpp | 21 +++++++++++++++++++ 24 files changed, 504 insertions(+) diff --git a/include/publisher_gnss_accuracy.h b/include/publisher_gnss_accuracy.h index 598565d..52b0997 100644 --- a/include/publisher_gnss_accuracy.h +++ b/include/publisher_gnss_accuracy.h @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #ifndef PUBLISHER_GNSS_ACCURACY_H #define PUBLISHER_GNSS_ACCURACY_H diff --git a/include/publisher_gnss_fix.h b/include/publisher_gnss_fix.h index 5582f1d..d2137a0 100644 --- a/include/publisher_gnss_fix.h +++ b/include/publisher_gnss_fix.h @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #ifndef PUBLISHER_FIX_H #define PUBLISHER_FIX_H diff --git a/include/publisher_gnss_tf.h b/include/publisher_gnss_tf.h index b88c88b..5f41dc4 100644 --- a/include/publisher_gnss_tf.h +++ b/include/publisher_gnss_tf.h @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #ifndef PUBLISHER_GNSS_TF_H #define PUBLISHER_GNSS_TF_H diff --git a/include/publisher_tracker_gnss_info.h b/include/publisher_tracker_gnss_info.h index 0a2d815..df00125 100644 --- a/include/publisher_tracker_gnss_info.h +++ b/include/publisher_tracker_gnss_info.h @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #ifndef PUBLISHER_TRACKER_GNSS_INFO_H #define PUBLISHER_TRACKER_GNSS_INFO_H diff --git a/include/subscriber_gnss.h b/include/subscriber_gnss.h index 2df0762..815b623 100644 --- a/include/subscriber_gnss.h +++ b/include/subscriber_gnss.h @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #ifndef SUBSCRIBER_GNSS_H #define SUBSCRIBER_GNSS_H /************************** diff --git a/include/subscriber_gnss_fix.h b/include/subscriber_gnss_fix.h index ab5dcf2..c0aab03 100644 --- a/include/subscriber_gnss_fix.h +++ b/include/subscriber_gnss_fix.h @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #ifndef SUBSCRIBER_GNSS_FIX_H #define SUBSCRIBER_GNSS_FIX_H /************************** diff --git a/include/subscriber_gnss_fix_novatel_publisher_ecef.h b/include/subscriber_gnss_fix_novatel_publisher_ecef.h index 7d905ad..3cff7c5 100644 --- a/include/subscriber_gnss_fix_novatel_publisher_ecef.h +++ b/include/subscriber_gnss_fix_novatel_publisher_ecef.h @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #ifndef SUBSCRIBER_GNSS_FIX_NOVATEL_PUBLISHER_ECEF_H #define SUBSCRIBER_GNSS_FIX_NOVATEL_PUBLISHER_ECEF_H diff --git a/include/subscriber_gnss_fix_publisher_ecef.h b/include/subscriber_gnss_fix_publisher_ecef.h index 825ce34..585ca24 100644 --- a/include/subscriber_gnss_fix_publisher_ecef.h +++ b/include/subscriber_gnss_fix_publisher_ecef.h @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #ifndef SUBSCRIBER_GNSS_FIX_PUBLISHER_ECEF_H #define SUBSCRIBER_GNSS_FIX_PUBLISHER_ECEF_H diff --git a/include/subscriber_gnss_novatel.h b/include/subscriber_gnss_novatel.h index 9c68953..78616fa 100644 --- a/include/subscriber_gnss_novatel.h +++ b/include/subscriber_gnss_novatel.h @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #ifndef SUBSCRIBER_GNSS_NOVATEL_H #define SUBSCRIBER_GNSS_NOVATEL_H /************************** diff --git a/include/subscriber_gnss_receiver.h b/include/subscriber_gnss_receiver.h index 6d6e2ad..2b68124 100644 --- a/include/subscriber_gnss_receiver.h +++ b/include/subscriber_gnss_receiver.h @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #ifndef SUBSCRIBER_GNSS_RECEIVER_H #define SUBSCRIBER_GNSS_RECEIVER_H /************************** diff --git a/include/subscriber_gnss_tdcp.h b/include/subscriber_gnss_tdcp.h index f4ef78f..d688367 100644 --- a/include/subscriber_gnss_tdcp.h +++ b/include/subscriber_gnss_tdcp.h @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #ifndef SUBSCRIBER_GNSS_TDCP_H #define SUBSCRIBER_GNSS_TDCP_H /************************** diff --git a/include/subscriber_gnss_ublox.h b/include/subscriber_gnss_ublox.h index eb902a5..624113e 100644 --- a/include/subscriber_gnss_ublox.h +++ b/include/subscriber_gnss_ublox.h @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #ifndef SUBSCRIBER_GNSS_UBLOX_H #define SUBSCRIBER_GNSS_UBLOX_H /************************** diff --git a/src/publisher_gnss_accuracy.cpp b/src/publisher_gnss_accuracy.cpp index 6b4a625..5324cf6 100644 --- a/src/publisher_gnss_accuracy.cpp +++ b/src/publisher_gnss_accuracy.cpp @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #include "publisher_gnss_accuracy.h" /************************** diff --git a/src/publisher_gnss_fix.cpp b/src/publisher_gnss_fix.cpp index 0eae2ae..53e6d82 100644 --- a/src/publisher_gnss_fix.cpp +++ b/src/publisher_gnss_fix.cpp @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #include #include "tf/transform_datatypes.h" #include "tf_conversions/tf_eigen.h" diff --git a/src/publisher_gnss_tf.cpp b/src/publisher_gnss_tf.cpp index 3409718..c561aed 100644 --- a/src/publisher_gnss_tf.cpp +++ b/src/publisher_gnss_tf.cpp @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #include "publisher_gnss_tf.h" /************************** diff --git a/src/publisher_tracker_gnss_info.cpp b/src/publisher_tracker_gnss_info.cpp index 0057ce0..97872fc 100644 --- a/src/publisher_tracker_gnss_info.cpp +++ b/src/publisher_tracker_gnss_info.cpp @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #include "../include/publisher_tracker_gnss_info.h" #include "std_msgs/UInt16.h" diff --git a/src/subscriber_gnss.cpp b/src/subscriber_gnss.cpp index 3d4337f..5ac0abb 100644 --- a/src/subscriber_gnss.cpp +++ b/src/subscriber_gnss.cpp @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #include "../include/subscriber_gnss.h" namespace wolf diff --git a/src/subscriber_gnss_fix.cpp b/src/subscriber_gnss_fix.cpp index 29a69f5..7b4dc93 100644 --- a/src/subscriber_gnss_fix.cpp +++ b/src/subscriber_gnss_fix.cpp @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #include "../include/subscriber_gnss_fix.h" namespace wolf diff --git a/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp b/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp index 0d77429..a0e90d0 100644 --- a/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp +++ b/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #include "subscriber_gnss_fix_novatel_publisher_ecef.h" #include "gnss_utils/utils/transformations.h" #include "tf/transform_datatypes.h" diff --git a/src/subscriber_gnss_fix_publisher_ecef.cpp b/src/subscriber_gnss_fix_publisher_ecef.cpp index 979d709..8da4e48 100644 --- a/src/subscriber_gnss_fix_publisher_ecef.cpp +++ b/src/subscriber_gnss_fix_publisher_ecef.cpp @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #include "subscriber_gnss_fix_publisher_ecef.h" #include "gnss_utils/utils/transformations.h" #include "tf/transform_datatypes.h" diff --git a/src/subscriber_gnss_novatel.cpp b/src/subscriber_gnss_novatel.cpp index 5743089..7bca69d 100644 --- a/src/subscriber_gnss_novatel.cpp +++ b/src/subscriber_gnss_novatel.cpp @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #include "../include/subscriber_gnss_novatel.h" namespace wolf diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index 974df7a..b8d42f3 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #include "../include/subscriber_gnss_receiver.h" #include "tf/transform_datatypes.h" #include "tf_conversions/tf_eigen.h" diff --git a/src/subscriber_gnss_tdcp.cpp b/src/subscriber_gnss_tdcp.cpp index 43a1ad8..f3df322 100644 --- a/src/subscriber_gnss_tdcp.cpp +++ b/src/subscriber_gnss_tdcp.cpp @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #include "../include/subscriber_gnss_tdcp.h" namespace wolf diff --git a/src/subscriber_gnss_ublox.cpp b/src/subscriber_gnss_ublox.cpp index 330b46d..80feae9 100644 --- a/src/subscriber_gnss_ublox.cpp +++ b/src/subscriber_gnss_ublox.cpp @@ -1,3 +1,24 @@ +//--------LICENSE_START-------- +// +// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Authors: Joan Solà Ortega (jsola@iri.upc.edu) +// All rights reserved. +// +// This file is part of WOLF +// WOLF is free software: you can redistribute it and/or modify +// it under the terms of the GNU Lesser General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// at your option) any later version. +// +// This program is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU Lesser General Public License for more details. +// +// You should have received a copy of the GNU Lesser General Public License +// along with this program. If not, see . +// +//--------LICENSE_END-------- #include "../include/subscriber_gnss_ublox.h" namespace wolf -- GitLab From 40400de40dca31f84de2b7ac109e0c873838b3d3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Thu, 2 Dec 2021 13:01:36 +0100 Subject: [PATCH 76/86] Update .gitlab-ci.yml file --- .gitlab-ci.yml | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index 49994d0..784f1bd 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -151,11 +151,15 @@ build_and_test:xenial: - key: gnssutils-xenial paths: - ci_deps/gnss_utils/ + - key: gnss-xenial + paths: + - ci_deps/gnss/ except: - master before_script: - *preliminaries_definition - *install_wolf_definition + - *install_gnssutils_definition - *install_wolfgnss_definition - *clone_wolfrosnode_definition script: @@ -172,11 +176,15 @@ build_and_test:bionic: - key: gnssutils-bionic paths: - ci_deps/gnss_utils/ + - key: gnss-bionic + paths: + - ci_deps/gnss/ except: - master before_script: - *preliminaries_definition - *install_wolf_definition + - *install_gnssutils_definition - *install_wolfgnss_definition - *clone_wolfrosnode_definition script: -- GitLab From ac4d2bfbe8173a9852b4bdb0175e21e9c62ba484 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Thu, 2 Dec 2021 14:21:21 +0100 Subject: [PATCH 77/86] Update .gitlab-ci.yml file --- .gitlab-ci.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index 784f1bd..a97a627 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -162,6 +162,7 @@ build_and_test:xenial: - *install_gnssutils_definition - *install_wolfgnss_definition - *clone_wolfrosnode_definition + - ldconfig script: - *build_and_test_definition @@ -187,6 +188,7 @@ build_and_test:bionic: - *install_gnssutils_definition - *install_wolfgnss_definition - *clone_wolfrosnode_definition + - ldconfig script: - *build_and_test_definition -- GitLab From 3a0ebd41f6bc887982ff4af2e2b5e3bfc9a9717a Mon Sep 17 00:00:00 2001 From: joanvallve Date: Wed, 22 Dec 2021 16:25:32 +0100 Subject: [PATCH 78/86] fixing CI and c++14 --- .gitlab-ci.yml | 50 ++++++++++++++++++++++++++++++++++++++++++++++---- CMakeLists.txt | 2 +- 2 files changed, 47 insertions(+), 5 deletions(-) diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index a97a627..3f870b7 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -28,6 +28,10 @@ stages: # create ci_deps folder (if not exists) - mkdir -pv ci_deps + # manually source ros setup.bash + - source /root/catkin_ws/devel/setup.bash + - roscd # check that it works + .license_header_template: &license_header_definition - cd $CI_PROJECT_DIR @@ -67,6 +71,7 @@ stages: - if [ -d wolf ]; then - echo "directory wolf exists" - cd wolf + - git checkout devel - git pull - git checkout $WOLF_CORE_BRANCH - else @@ -104,6 +109,7 @@ stages: - if [ -d gnss ]; then - echo "directory gnss exists" - cd gnss + - git checkout devel - git pull - git checkout $WOLF_GNSS_BRANCH - else @@ -119,10 +125,20 @@ stages: - make install .clone_wolfrosnode_template: &clone_wolfrosnode_definition - - echo "TODO clone wolf_ros_node branch ${WOLF_ROS_CORE_BRANCH}" + - roscd + - cd ../src + - git clone ssh://git@gitlab.iri.upc.edu:2202/mobile_robotics/wolf_projects/wolf_ros/wolf_ros_node.git + - cd wolf_ros_node + - git checkout $WOLF_ROS_CORE_BRANCH .build_and_test_template: &build_and_test_definition - - echo "TODO" + - roscd + - cd ../src + - git clone ssh://git@gitlab.iri.upc.edu:2202/${CI_PROJECT_PATH}.git + - cd wolf_ros_gnss + - git checkout $CI_COMMIT_BRANCH + - cd ../.. + - catkin_make ############ LICENSE HEADERS ############ license_headers: @@ -143,7 +159,7 @@ license_headers: ############ UBUNTU 16.04 TEST ############ build_and_test:xenial: stage: build_and_test - image: labrobotica/wolf_deps:16.04 + image: labrobotica/wolf_deps_ros:16.04 cache: - key: wolf-xenial paths: @@ -169,7 +185,7 @@ build_and_test:xenial: ############ UBUNTU 18.04 TEST ############ build_and_test:bionic: stage: build_and_test - image: labrobotica/wolf_deps:18.04 + image: labrobotica/wolf_deps_ros:18.04 cache: - key: wolf-bionic paths: @@ -192,6 +208,32 @@ build_and_test:bionic: script: - *build_and_test_definition +############ UBUNTU 20.04 TEST ############ +build_and_test:focal: + stage: build_and_test + image: labrobotica/wolf_deps_ros:20.04 + cache: + - key: wolf-focal + paths: + - ci_deps/wolf/ + - key: gnssutils-focal + paths: + - ci_deps/gnss_utils/ + - key: gnss-focal + paths: + - ci_deps/gnss/ + except: + - master + before_script: + - *preliminaries_definition + - *install_wolf_definition + - *install_gnssutils_definition + - *install_wolfgnss_definition + - *clone_wolfrosnode_definition + - ldconfig + script: + - *build_and_test_definition + ############ RUN DEMOS ############ demo_gnss: stage: demos diff --git a/CMakeLists.txt b/CMakeLists.txt index 500b89f..3de46d0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 2.8.3) project(wolf_ros_gnss) ## Compile as C++11, supported in ROS Kinetic and newer -add_compile_options(-std=c++11) +add_compile_options(-std=c++14) # SET(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_SOURCE_DIR}/wolf_ros_wrapper/cmake_modules") ## Find catkin macros and libraries -- GitLab From 195fb93ad776ba4ac0a89200ff7af5f1cde97963 Mon Sep 17 00:00:00 2001 From: joan Date: Wed, 22 Dec 2021 16:34:56 +0100 Subject: [PATCH 79/86] CI: not building tests --- .gitlab-ci.yml | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index 3f870b7..7246614 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -81,9 +81,8 @@ stages: - fi - mkdir -pv build - cd build - - cmake -DCMAKE_BUILD_TYPE=release -DBUILD_EXAMPLES=ON -DBUILD_TESTS=ON .. + - cmake -DCMAKE_BUILD_TYPE=release -DBUILD_DEMOS=OFF -DBUILD_TESTS=OFF .. - make -j$(nproc) - - ctest -j$(nproc) - make install .install_gnssutils_template: &install_gnssutils_definition @@ -99,9 +98,8 @@ stages: - fi - mkdir -pv build - cd build - - cmake -DCMAKE_BUILD_TYPE=release -DBUILD_EXAMPLES=ON -DBUILD_TESTS=ON .. + - cmake -DCMAKE_BUILD_TYPE=release -DBUILD_TESTS=OFF .. - make -j$(nproc) - - ctest -j$(nproc) - make install .install_wolfgnss_template: &install_wolfgnss_definition @@ -119,9 +117,8 @@ stages: - fi - mkdir -pv build - cd build - - cmake -DCMAKE_BUILD_TYPE=release -DBUILD_EXAMPLES=ON -DBUILD_TESTS=ON .. + - cmake -DCMAKE_BUILD_TYPE=release -DBUILD_TESTS=OFF .. - make -j$(nproc) - - ctest -j$(nproc) - make install .clone_wolfrosnode_template: &clone_wolfrosnode_definition -- GitLab From a5ad2c6f4a2cb25ae32ad6cb0906edb3ca2ba4fb Mon Sep 17 00:00:00 2001 From: joan Date: Wed, 22 Dec 2021 16:49:54 +0100 Subject: [PATCH 80/86] CI:hotfix --- .gitlab-ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index 7246614..5030072 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -140,7 +140,7 @@ stages: ############ LICENSE HEADERS ############ license_headers: stage: license - image: labrobotica/wolf_deps:16.04 + image: labrobotica/wolf_deps_ros:16.04 cache: - key: wolf-xenial paths: -- GitLab From 04a0ce9ad624e8481c7617bbbf4cf69bf6676a60 Mon Sep 17 00:00:00 2001 From: joanvallve Date: Fri, 24 Dec 2021 12:19:47 +0100 Subject: [PATCH 81/86] adapted to new subscriber API --- src/subscriber_gnss.cpp | 2 +- src/subscriber_gnss_fix.cpp | 2 +- src/subscriber_gnss_fix_novatel_publisher_ecef.cpp | 2 +- src/subscriber_gnss_fix_publisher_ecef.cpp | 2 +- src/subscriber_gnss_novatel.cpp | 2 +- src/subscriber_gnss_ublox.cpp | 8 +++++--- 6 files changed, 10 insertions(+), 8 deletions(-) diff --git a/src/subscriber_gnss.cpp b/src/subscriber_gnss.cpp index 5ac0abb..af3d6f2 100644 --- a/src/subscriber_gnss.cpp +++ b/src/subscriber_gnss.cpp @@ -42,7 +42,7 @@ void SubscriberGnss::initialize(ros::NodeHandle& nh, const std::string& topic) void SubscriberGnss::callbackObservation(const iri_gnss_msgs::Observation::ConstPtr& msg) { - setLastStamp(msg->header.stamp); + updateLastHeader(msg->header); ROS_DEBUG("callbackObs!"); if (last_nav_ptr_==nullptr) diff --git a/src/subscriber_gnss_fix.cpp b/src/subscriber_gnss_fix.cpp index 7b4dc93..ba3d7ab 100644 --- a/src/subscriber_gnss_fix.cpp +++ b/src/subscriber_gnss_fix.cpp @@ -49,7 +49,7 @@ void SubscriberGnssFix::initialize(ros::NodeHandle& nh, const std::string& topic void SubscriberGnssFix::callback(const sensor_msgs::NavSatFix::ConstPtr& msg) { - setLastStamp(msg->header.stamp); + updateLastHeader(msg->header); if (cov_mode_ == "msg" or cov_mode_ == "factor") cov_ = cov_factor_ * Eigen::Map(msg->position_covariance.data()); diff --git a/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp b/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp index a0e90d0..77a4e3c 100644 --- a/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp +++ b/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp @@ -44,7 +44,7 @@ void SubscriberGnssFixNovatelPublisherEcef::initialize(ros::NodeHandle& nh, cons void SubscriberGnssFixNovatelPublisherEcef::callback(const novatel_oem7_msgs::BESTPOS::ConstPtr& _msg) { - setLastStamp(_msg->header.stamp); + updateLastHeader(_msg->header); computeAndPublish(Eigen::Vector3d(_msg->lat * M_PI / 180.0, _msg->lon * M_PI / 180.0, diff --git a/src/subscriber_gnss_fix_publisher_ecef.cpp b/src/subscriber_gnss_fix_publisher_ecef.cpp index 8da4e48..eebf9b6 100644 --- a/src/subscriber_gnss_fix_publisher_ecef.cpp +++ b/src/subscriber_gnss_fix_publisher_ecef.cpp @@ -77,7 +77,7 @@ void SubscriberGnssFixPublisherEcef::initialize(ros::NodeHandle& nh, const std:: void SubscriberGnssFixPublisherEcef::callback(const sensor_msgs::NavSatFix::ConstPtr& _msg) { - setLastStamp(_msg->header.stamp); + updateLastHeader(_msg->header); computeAndPublish(Eigen::Vector3d(_msg->latitude * M_PI / 180.0, _msg->longitude * M_PI / 180.0, diff --git a/src/subscriber_gnss_novatel.cpp b/src/subscriber_gnss_novatel.cpp index 7bca69d..4081c70 100644 --- a/src/subscriber_gnss_novatel.cpp +++ b/src/subscriber_gnss_novatel.cpp @@ -44,7 +44,7 @@ void SubscriberGnssNovatel::initialize(ros::NodeHandle& nh, const std::string& t void SubscriberGnssNovatel::callback(const novatel_oem7_msgs::Oem7RawMsg& msg) { - setLastStamp(msg.header.stamp); + updateLastHeader(msg.header); GnssUtils::RawDataType res = receiver_->addDataStream(msg.message_data); diff --git a/src/subscriber_gnss_ublox.cpp b/src/subscriber_gnss_ublox.cpp index 80feae9..97a15c5 100644 --- a/src/subscriber_gnss_ublox.cpp +++ b/src/subscriber_gnss_ublox.cpp @@ -58,9 +58,11 @@ void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) { ROS_DEBUG("SubscriberGnssUblox::callback message received!"); - auto stamp = ros::Time::now(); - setLastStamp(stamp); + std_msgs::Header header; + header.stamp = ros::Time::now(); n_msgs_++; + header.seq = n_msgs_; + updateLastHeader(header); GnssUtils::RawDataType res = receiver_->addDataStream(msg.data); @@ -70,7 +72,7 @@ void SubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) if (res == GnssUtils::OBS) { //ROS_INFO("Observation received!"); - createCaptureAndProcess(stamp); + createCaptureAndProcess(header.stamp); } } -- GitLab From 849d471253c6cad87772a4c235af20421fc0a2a4 Mon Sep 17 00:00:00 2001 From: cont-integration Date: Tue, 4 Jan 2022 14:00:19 +0000 Subject: [PATCH 82/86] [skip ci] license headers added or modified --- include/publisher_gnss_accuracy.h | 2 +- include/publisher_gnss_fix.h | 2 +- include/publisher_gnss_tf.h | 2 +- include/publisher_tracker_gnss_info.h | 2 +- include/subscriber_gnss.h | 2 +- include/subscriber_gnss_fix.h | 2 +- include/subscriber_gnss_fix_novatel_publisher_ecef.h | 2 +- include/subscriber_gnss_fix_publisher_ecef.h | 2 +- include/subscriber_gnss_novatel.h | 2 +- include/subscriber_gnss_receiver.h | 2 +- include/subscriber_gnss_tdcp.h | 2 +- include/subscriber_gnss_ublox.h | 2 +- license_header_2021.txt => license_header_2022.txt | 2 +- src/publisher_gnss_accuracy.cpp | 2 +- src/publisher_gnss_fix.cpp | 2 +- src/publisher_gnss_tf.cpp | 2 +- src/publisher_tracker_gnss_info.cpp | 2 +- src/subscriber_gnss.cpp | 2 +- src/subscriber_gnss_fix.cpp | 2 +- src/subscriber_gnss_fix_novatel_publisher_ecef.cpp | 2 +- src/subscriber_gnss_fix_publisher_ecef.cpp | 2 +- src/subscriber_gnss_novatel.cpp | 2 +- src/subscriber_gnss_receiver.cpp | 2 +- src/subscriber_gnss_tdcp.cpp | 2 +- src/subscriber_gnss_ublox.cpp | 2 +- 25 files changed, 25 insertions(+), 25 deletions(-) rename license_header_2021.txt => license_header_2022.txt (89%) diff --git a/include/publisher_gnss_accuracy.h b/include/publisher_gnss_accuracy.h index 52b0997..57ca6cf 100644 --- a/include/publisher_gnss_accuracy.h +++ b/include/publisher_gnss_accuracy.h @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/include/publisher_gnss_fix.h b/include/publisher_gnss_fix.h index d2137a0..a4f0caf 100644 --- a/include/publisher_gnss_fix.h +++ b/include/publisher_gnss_fix.h @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/include/publisher_gnss_tf.h b/include/publisher_gnss_tf.h index 5f41dc4..6779049 100644 --- a/include/publisher_gnss_tf.h +++ b/include/publisher_gnss_tf.h @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/include/publisher_tracker_gnss_info.h b/include/publisher_tracker_gnss_info.h index df00125..ce05728 100644 --- a/include/publisher_tracker_gnss_info.h +++ b/include/publisher_tracker_gnss_info.h @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/include/subscriber_gnss.h b/include/subscriber_gnss.h index 815b623..a1efaf4 100644 --- a/include/subscriber_gnss.h +++ b/include/subscriber_gnss.h @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/include/subscriber_gnss_fix.h b/include/subscriber_gnss_fix.h index c0aab03..b005546 100644 --- a/include/subscriber_gnss_fix.h +++ b/include/subscriber_gnss_fix.h @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/include/subscriber_gnss_fix_novatel_publisher_ecef.h b/include/subscriber_gnss_fix_novatel_publisher_ecef.h index 3cff7c5..d171317 100644 --- a/include/subscriber_gnss_fix_novatel_publisher_ecef.h +++ b/include/subscriber_gnss_fix_novatel_publisher_ecef.h @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/include/subscriber_gnss_fix_publisher_ecef.h b/include/subscriber_gnss_fix_publisher_ecef.h index 585ca24..4099db4 100644 --- a/include/subscriber_gnss_fix_publisher_ecef.h +++ b/include/subscriber_gnss_fix_publisher_ecef.h @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/include/subscriber_gnss_novatel.h b/include/subscriber_gnss_novatel.h index 78616fa..4bead29 100644 --- a/include/subscriber_gnss_novatel.h +++ b/include/subscriber_gnss_novatel.h @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/include/subscriber_gnss_receiver.h b/include/subscriber_gnss_receiver.h index 2b68124..b02880e 100644 --- a/include/subscriber_gnss_receiver.h +++ b/include/subscriber_gnss_receiver.h @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/include/subscriber_gnss_tdcp.h b/include/subscriber_gnss_tdcp.h index d688367..9b176ad 100644 --- a/include/subscriber_gnss_tdcp.h +++ b/include/subscriber_gnss_tdcp.h @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/include/subscriber_gnss_ublox.h b/include/subscriber_gnss_ublox.h index 624113e..c7c3801 100644 --- a/include/subscriber_gnss_ublox.h +++ b/include/subscriber_gnss_ublox.h @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/license_header_2021.txt b/license_header_2022.txt similarity index 89% rename from license_header_2021.txt rename to license_header_2022.txt index c75a6f2..0c98702 100644 --- a/license_header_2021.txt +++ b/license_header_2022.txt @@ -1,4 +1,4 @@ -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/src/publisher_gnss_accuracy.cpp b/src/publisher_gnss_accuracy.cpp index 5324cf6..a2ef3ca 100644 --- a/src/publisher_gnss_accuracy.cpp +++ b/src/publisher_gnss_accuracy.cpp @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/src/publisher_gnss_fix.cpp b/src/publisher_gnss_fix.cpp index 53e6d82..70f6e3f 100644 --- a/src/publisher_gnss_fix.cpp +++ b/src/publisher_gnss_fix.cpp @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/src/publisher_gnss_tf.cpp b/src/publisher_gnss_tf.cpp index c561aed..ed7ab47 100644 --- a/src/publisher_gnss_tf.cpp +++ b/src/publisher_gnss_tf.cpp @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/src/publisher_tracker_gnss_info.cpp b/src/publisher_tracker_gnss_info.cpp index 97872fc..1fc154f 100644 --- a/src/publisher_tracker_gnss_info.cpp +++ b/src/publisher_tracker_gnss_info.cpp @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/src/subscriber_gnss.cpp b/src/subscriber_gnss.cpp index af3d6f2..22d9e59 100644 --- a/src/subscriber_gnss.cpp +++ b/src/subscriber_gnss.cpp @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/src/subscriber_gnss_fix.cpp b/src/subscriber_gnss_fix.cpp index ba3d7ab..5ce3ca8 100644 --- a/src/subscriber_gnss_fix.cpp +++ b/src/subscriber_gnss_fix.cpp @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp b/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp index 77a4e3c..6123685 100644 --- a/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp +++ b/src/subscriber_gnss_fix_novatel_publisher_ecef.cpp @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/src/subscriber_gnss_fix_publisher_ecef.cpp b/src/subscriber_gnss_fix_publisher_ecef.cpp index eebf9b6..8faf1ec 100644 --- a/src/subscriber_gnss_fix_publisher_ecef.cpp +++ b/src/subscriber_gnss_fix_publisher_ecef.cpp @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/src/subscriber_gnss_novatel.cpp b/src/subscriber_gnss_novatel.cpp index 4081c70..0f13577 100644 --- a/src/subscriber_gnss_novatel.cpp +++ b/src/subscriber_gnss_novatel.cpp @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/src/subscriber_gnss_receiver.cpp b/src/subscriber_gnss_receiver.cpp index b8d42f3..87bc2c7 100644 --- a/src/subscriber_gnss_receiver.cpp +++ b/src/subscriber_gnss_receiver.cpp @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/src/subscriber_gnss_tdcp.cpp b/src/subscriber_gnss_tdcp.cpp index f3df322..63b1228 100644 --- a/src/subscriber_gnss_tdcp.cpp +++ b/src/subscriber_gnss_tdcp.cpp @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // diff --git a/src/subscriber_gnss_ublox.cpp b/src/subscriber_gnss_ublox.cpp index 97a15c5..ac170aa 100644 --- a/src/subscriber_gnss_ublox.cpp +++ b/src/subscriber_gnss_ublox.cpp @@ -1,6 +1,6 @@ //--------LICENSE_START-------- // -// Copyright (C) 2020,2021 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. +// Copyright (C) 2020,2021,2022 Institut de Robòtica i Informàtica Industrial, CSIC-UPC. // Authors: Joan Solà Ortega (jsola@iri.upc.edu) // All rights reserved. // -- GitLab From d96bdce1e7b0f2b1341d7e03443fd33c751006ff Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Wed, 19 Jan 2022 14:23:30 +0100 Subject: [PATCH 83/86] Update .gitlab-ci.yml file --- .gitlab-ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index 5030072..6c731fc 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -240,4 +240,4 @@ demo_gnss: WOLF_ROS_CORE_BRANCH: $WOLF_ROS_CORE_BRANCH WOLF_ROS_GNSS_BRANCH: $CI_COMMIT_BRANCH trigger: - project: mobile_robotics/wolf_projects/wolf_ros/demos/wolf_demo_gnss + project: mobile_robotics/wolf_projects/wolf_ros/demos/wolf_demo_gnss_imu -- GitLab From 48f676301bb0a012373623e5b635bbe290a40413 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Mon, 24 Jan 2022 09:21:37 +0100 Subject: [PATCH 84/86] [skip ci] Update .gitlab-ci.yml file --- .gitlab-ci.yml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index 6c731fc..e1ba502 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -74,10 +74,10 @@ stages: - git checkout devel - git pull - git checkout $WOLF_CORE_BRANCH + - git pull - else - - git clone ssh://git@gitlab.iri.upc.edu:2202/mobile_robotics/wolf_projects/wolf_lib/wolf.git + - git clone -b $WOLF_CORE_BRANCH ssh://git@gitlab.iri.upc.edu:2202/mobile_robotics/wolf_projects/wolf_lib/wolf.git - cd wolf - - git checkout $WOLF_CORE_BRANCH - fi - mkdir -pv build - cd build @@ -110,10 +110,10 @@ stages: - git checkout devel - git pull - git checkout $WOLF_GNSS_BRANCH + - git pull - else - - git clone ssh://git@gitlab.iri.upc.edu:2202/mobile_robotics/wolf_projects/wolf_lib/plugins/gnss.git + - git clone -b $WOLF_GNSS_BRANCH ssh://git@gitlab.iri.upc.edu:2202/mobile_robotics/wolf_projects/wolf_lib/plugins/gnss.git - cd gnss - - git checkout $WOLF_GNSS_BRANCH - fi - mkdir -pv build - cd build -- GitLab From 39003e0af6b428ce2daece33feb13c2d56648c43 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Mon, 31 Jan 2022 12:38:32 +0100 Subject: [PATCH 85/86] [skip ci] ci removed ubuntu 16.04 --- .gitlab-ci.yml | 33 ++------------------------------- 1 file changed, 2 insertions(+), 31 deletions(-) diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index e1ba502..2c4a200 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -140,11 +140,8 @@ stages: ############ LICENSE HEADERS ############ license_headers: stage: license - image: labrobotica/wolf_deps_ros:16.04 - cache: - - key: wolf-xenial - paths: - - ci_deps/wolf/ + image: labrobotica/wolf_deps_ros:20.04 + cache: [] except: - master before_script: @@ -153,32 +150,6 @@ license_headers: script: - *license_header_definition -############ UBUNTU 16.04 TEST ############ -build_and_test:xenial: - stage: build_and_test - image: labrobotica/wolf_deps_ros:16.04 - cache: - - key: wolf-xenial - paths: - - ci_deps/wolf/ - - key: gnssutils-xenial - paths: - - ci_deps/gnss_utils/ - - key: gnss-xenial - paths: - - ci_deps/gnss/ - except: - - master - before_script: - - *preliminaries_definition - - *install_wolf_definition - - *install_gnssutils_definition - - *install_wolfgnss_definition - - *clone_wolfrosnode_definition - - ldconfig - script: - - *build_and_test_definition - ############ UBUNTU 18.04 TEST ############ build_and_test:bionic: stage: build_and_test -- GitLab From 3347ca63ec704436ad9cb082c21284a2f59e54c5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Joan=20Vallv=C3=A9=20Navarro?= Date: Fri, 11 Feb 2022 09:33:34 +0100 Subject: [PATCH 86/86] ci: removed except master --- .gitlab-ci.yml | 6 ------ 1 file changed, 6 deletions(-) diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml index 2c4a200..3ae6df7 100644 --- a/.gitlab-ci.yml +++ b/.gitlab-ci.yml @@ -142,8 +142,6 @@ license_headers: stage: license image: labrobotica/wolf_deps_ros:20.04 cache: [] - except: - - master before_script: - *preliminaries_definition - *install_wolf_definition @@ -164,8 +162,6 @@ build_and_test:bionic: - key: gnss-bionic paths: - ci_deps/gnss/ - except: - - master before_script: - *preliminaries_definition - *install_wolf_definition @@ -190,8 +186,6 @@ build_and_test:focal: - key: gnss-focal paths: - ci_deps/gnss/ - except: - - master before_script: - *preliminaries_definition - *install_wolf_definition -- GitLab