Skip to content
Snippets Groups Projects
Commit 84417724 authored by Joan Vallvé Navarro's avatar Joan Vallvé Navarro
Browse files

subscriber ublox implemented compiling

parent 48780bc0
No related branches found
No related tags found
2 merge requests!3After cmake and const refactor,!1new release
......@@ -5,7 +5,7 @@
#include <core/common/wolf.h>
#include <core/problem/problem.h>
#include <core/utils/params_server.hpp>
#include <gnss/capture/capture_gnss_fix.h>
#include <gnss/capture/capture_gnss.h>
#include <gnss/sensor/sensor_gnss.h>
/**************************
......@@ -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<WolfSubscriber> 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)
......@@ -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<GNSSUtils::Observations>(ublox_raw_.getObservations());
GNSSUtils::NavigationPtr nav_ptr = std::make_shared<GNSSUtils::Navigation>(ublox_raw_.getNavigation());
ros::Time now = ros::Time::now();
// cap_gnss_ptr->process();
auto cap_gnss_ptr = std::make_shared<CaptureGnss>(TimeStamp(now.sec, now.nsec),
sensor_ptr_,
obs_ptr,
nav_ptr);
cap_gnss_ptr->process();
}
}
std::shared_ptr<WolfSubscriber> WolfSubscriberGnssUblox::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
{
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment