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

adapted to new subscriber API

parent a5ad2c6f
No related branches found
No related tags found
2 merge requests!3After cmake and const refactor,!1new release
......@@ -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)
......
......@@ -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<const Eigen::Matrix3d>(msg->position_covariance.data());
......
......@@ -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,
......
......@@ -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,
......
......@@ -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);
......
......@@ -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);
}
}
......
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