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

working

parent 788296d5
No related branches found
No related tags found
2 merge requests!3After cmake and const refactor,!1new release
...@@ -11,25 +11,24 @@ WolfSubscriberGnssUblox::WolfSubscriberGnssUblox(const SensorBasePtr& sensor_ptr ...@@ -11,25 +11,24 @@ WolfSubscriberGnssUblox::WolfSubscriberGnssUblox(const SensorBasePtr& sensor_ptr
void WolfSubscriberGnssUblox::initSubscriber(ros::NodeHandle& nh, const std::string& topic) 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) void WolfSubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg)
{ {
ROS_INFO("Ublox data stream callback!");
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 // only create capture if observation is received
if (res == GNSSUtils::OBS) if (res == GNSSUtils::OBS)
{ {
ROS_INFO("Observation received!"); //ROS_INFO("Observation received!");
GNSSUtils::ObservationsPtr obs_ptr = std::make_shared<GNSSUtils::Observations>(ublox_raw_.getObservations()); GNSSUtils::ObservationsPtr obs_ptr = std::make_shared<GNSSUtils::Observations>(ublox_raw_.getObservations());
ROS_INFO("Observations copied!"); //ROS_INFO("Observations copied!");
GNSSUtils::NavigationPtr nav_ptr = std::make_shared<GNSSUtils::Navigation>(ublox_raw_.getNavigation()); GNSSUtils::NavigationPtr nav_ptr = std::make_shared<GNSSUtils::Navigation>(ublox_raw_.getNavigation());
ROS_INFO("Navigation copied!"); //ROS_INFO("Navigation copied!");
ros::Time now = ros::Time::now(); ros::Time now = ros::Time::now();
...@@ -38,9 +37,9 @@ void WolfSubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg) ...@@ -38,9 +37,9 @@ void WolfSubscriberGnssUblox::callback(const std_msgs::UInt8MultiArray& msg)
obs_ptr, obs_ptr,
nav_ptr); nav_ptr);
ROS_INFO("Capture GNSS created!"); //ROS_INFO("Capture GNSS created!");
cap_gnss_ptr->process(); cap_gnss_ptr->process();
ROS_INFO("Capture GNSS processed!"); //ROS_INFO("Capture GNSS processed!");
} }
} }
std::shared_ptr<WolfSubscriber> WolfSubscriberGnssUblox::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr) 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