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

Merge branch 'devel' of

ssh://git@gitlab.iri.upc.edu:2202/mobile_robotics/wolf_projects/wolf_ros/wolf_ros_gnss.git
into devel

Conflicts:
	CMakeLists.txt
	src/wolf_subscriber_gnss_ublox.cpp
parents dbb779a3 db28e6ee
No related branches found
No related tags found
2 merge requests!3After cmake and const refactor,!1new release
......@@ -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,22 +164,22 @@ 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}
......
......@@ -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<WolfSubscriber> create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr);
static std::shared_ptr<Subscriber> create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr);
};
WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnss)
WOLF_REGISTER_SUBSCRIBER(SubscriberGnss)
......@@ -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<WolfSubscriber> create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr);
static std::shared_ptr<Subscriber> create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr);
};
WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnssTDCP)
WOLF_REGISTER_SUBSCRIBER(SubscriberGnssTdcp)
......@@ -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<WolfSubscriber> create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr);
static std::shared_ptr<Subscriber> create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr);
};
WOLF_REGISTER_SUBSCRIBER(WolfSubscriberGnssFix)
WOLF_REGISTER_SUBSCRIBER(SubscriberGnssFix)
......@@ -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<WolfSubscriber> create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr);
static std::shared_ptr<Subscriber> 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)
......@@ -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<WolfSubscriber> WolfSubscriberGnss::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
std::shared_ptr<Subscriber> SubscriberGnss::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
{
return std::make_shared<WolfSubscriberGnss>(_sensor_ptr);
return std::make_shared<SubscriberGnss>(_sensor_ptr);
}
#include "../include/wolf_subscriber_gnss_TDCP.h"
#include "../include/wolf_subscriber_gnss_Tdcp.h"
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
// 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)
return;
// TODO copied from TDCP_ros
// TODO copied from Tdcp_ros
// GNSSUtils::ObservationsPtr obs_ptr = std::make_shared<GNSSUtils::Observations>();
// GNSSUtils::fillObservation(*obs_ptr, msg);
......@@ -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!");
......@@ -41,10 +41,10 @@ void WolfSubscriberGnssTDCP::callbackNavigation(const iri_gnss_msgs::Navigation:
GNSSUtils::fillNavigation(*last_nav_ptr_, msg);
last_nav_ptr_->print();
// TODO copied from TDCP_ros
// TODO copied from Tdcp_ros
}
std::shared_ptr<WolfSubscriber> WolfSubscriberGnssTDCP::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
std::shared_ptr<Subscriber> SubscriberGnssTdcp::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
{
return std::make_shared<WolfSubscriberGnssTDCP>(_sensor_ptr);
return std::make_shared<SubscriberGnssTdcp>(_sensor_ptr);
}
......@@ -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<const Eigen::Matrix3d>(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<WolfSubscriber> WolfSubscriberGnssFix::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
std::shared_ptr<Subscriber> SubscriberGnssFix::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
{
return std::make_shared<WolfSubscriberGnssFix>(_sensor_ptr);
return std::make_shared<SubscriberGnssFix>(_sensor_ptr);
}
#include "../include/wolf_subscriber_gnss_ublox.h"
#include "../include/subscriber_gnss_ublox.h"
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, 100, &WolfSubscriberGnssUblox::callback, this);
sub_ = nh.subscribe(topic, 100, &SubscriberGnssUblox::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<WolfSubscriber> WolfSubscriberGnssUblox::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
std::shared_ptr<Subscriber> SubscriberGnssUblox::create(const std::string& _unique_name, const ParamsServer& _params, const SensorBasePtr _sensor_ptr)
{
return std::make_shared<WolfSubscriberGnssUblox>(_sensor_ptr);
return std::make_shared<SubscriberGnssUblox>(_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