Skip to content

Commit

Permalink
Merge branch 'devel'
Browse files Browse the repository at this point in the history
  • Loading branch information
DanHert committed Aug 15, 2024
2 parents 58df23d + 32ba532 commit 5ce93ab
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 7 deletions.
4 changes: 2 additions & 2 deletions include/mrs_uav_hw_api/publishers.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@

#include <sensor_msgs/Imu.h>
#include <sensor_msgs/NavSatFix.h>
#include <sensor_msgs/NavSatStatus.h>
#include <sensor_msgs/Range.h>
#include <sensor_msgs/BatteryState.h>
#include <sensor_msgs/MagneticField.h>
Expand All @@ -14,6 +13,7 @@
#include <mrs_msgs/HwApiRcChannels.h>
#include <mrs_msgs/RtkGps.h>
#include <mrs_msgs/RtkFixType.h>
#include <mrs_msgs/GpsInfo.h>

#include <mrs_msgs/HwApiAltitude.h>

Expand All @@ -29,7 +29,7 @@ namespace mrs_uav_hw_api
//}

typedef std::function<void(const sensor_msgs::NavSatFix &msg)> publishGNSS_t;
typedef std::function<void(const sensor_msgs::NavSatStatus &msg)> publishGNSSStatus_t;
typedef std::function<void(const mrs_msgs::GpsInfo &msg)> publishGNSSStatus_t;
typedef std::function<void(const mrs_msgs::RtkGps &msg)> publishRTK_t;
typedef std::function<void(const mrs_msgs::HwApiAltitude &msg)> publishAltitude_t;
typedef std::function<void(const mrs_msgs::Float64Stamped &msg)> publishMagnetometerHeading_t;
Expand Down
9 changes: 4 additions & 5 deletions src/hw_api_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
#include <geometry_msgs/QuaternionStamped.h>

#include <sensor_msgs/NavSatFix.h>
#include <sensor_msgs/NavSatStatus.h>
#include <sensor_msgs/Range.h>

#include <std_msgs/Float64.h>
Expand Down Expand Up @@ -105,7 +104,7 @@ class HwApiManager : public nodelet::Nodelet {
mrs_lib::PublisherHandler<mrs_msgs::HwApiCapabilities> ph_capabilities_;

mrs_lib::PublisherHandler<sensor_msgs::NavSatFix> ph_gnss_;
mrs_lib::PublisherHandler<sensor_msgs::NavSatStatus> ph_gnss_status_;
mrs_lib::PublisherHandler<mrs_msgs::GpsInfo> ph_gnss_status_;
mrs_lib::PublisherHandler<mrs_msgs::RtkGps> ph_rtk_;
mrs_lib::PublisherHandler<sensor_msgs::Imu> ph_imu_;
mrs_lib::PublisherHandler<sensor_msgs::Range> ph_distance_sensor_;
Expand All @@ -127,7 +126,7 @@ class HwApiManager : public nodelet::Nodelet {
std::string getWorldFrameName(void);

void publishGNSS(const sensor_msgs::NavSatFix& msg);
void publishGNSSStatus(const sensor_msgs::NavSatStatus& msg);
void publishGNSSStatus(const mrs_msgs::GpsInfo& msg);
void publishRTK(const mrs_msgs::RtkGps& msg);
void publishOdometry(const nav_msgs::Odometry& msg);
void publishGroundTruth(const nav_msgs::Odometry& msg);
Expand Down Expand Up @@ -246,7 +245,7 @@ void HwApiManager::onInit() {
ph_connected_ = mrs_lib::PublisherHandler<std_msgs::Empty>(nh_, "connected", 1);

ph_gnss_ = mrs_lib::PublisherHandler<sensor_msgs::NavSatFix>(nh_, "gnss", 1, false, 50);
ph_gnss_status_ = mrs_lib::PublisherHandler<sensor_msgs::NavSatStatus>(nh_, "gnss_status", 1, false, 10);
ph_gnss_status_ = mrs_lib::PublisherHandler<mrs_msgs::GpsInfo>(nh_, "gnss_status", 1, false, 10);
ph_rtk_ = mrs_lib::PublisherHandler<mrs_msgs::RtkGps>(nh_, "rtk", 1, false, 50);
ph_distance_sensor_ = mrs_lib::PublisherHandler<sensor_msgs::Range>(nh_, "distance_sensor", 1, false, 250);
ph_mag_heading_ = mrs_lib::PublisherHandler<mrs_msgs::Float64Stamped>(nh_, "mag_heading", 1, false, 100);
Expand Down Expand Up @@ -630,7 +629,7 @@ void HwApiManager::publishGNSS(const sensor_msgs::NavSatFix& msg) {

/* publishGNSSStatus() //{ */

void HwApiManager::publishGNSSStatus(const sensor_msgs::NavSatStatus& msg) {
void HwApiManager::publishGNSSStatus(const mrs_msgs::GpsInfo& msg) {

if (!is_initialized_) {
return;
Expand Down

0 comments on commit 5ce93ab

Please sign in to comment.