Browse Source

mavlink: update orb_publish to uORB::Publication<>

sbg
Daniel Agar 6 years ago committed by GitHub
parent
commit
f280977ed0
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 12
      src/modules/mavlink/mavlink_mission.cpp
  2. 5
      src/modules/mavlink/mavlink_mission.h
  3. 9
      src/modules/mavlink/mavlink_parameters.cpp
  4. 3
      src/modules/mavlink/mavlink_parameters.h
  5. 18
      src/modules/mavlink/mavlink_timesync.cpp
  6. 6
      src/modules/mavlink/mavlink_timesync.h
  7. 10
      src/modules/mavlink/mavlink_ulog.cpp
  8. 3
      src/modules/mavlink/mavlink_ulog.h

12
src/modules/mavlink/mavlink_mission.cpp

@ -76,11 +76,6 @@ MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) : @@ -76,11 +76,6 @@ MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) :
init_offboard_mission();
}
MavlinkMissionManager::~MavlinkMissionManager()
{
orb_unadvertise(_offboard_mission_pub);
}
void
MavlinkMissionManager::init_offboard_mission()
{
@ -185,12 +180,7 @@ MavlinkMissionManager::update_active_mission(dm_item_t dataman_id, uint16_t coun @@ -185,12 +180,7 @@ MavlinkMissionManager::update_active_mission(dm_item_t dataman_id, uint16_t coun
_my_dataman_id = _dataman_id;
/* mission state saved successfully, publish offboard_mission topic */
if (_offboard_mission_pub == nullptr) {
_offboard_mission_pub = orb_advertise(ORB_ID(mission), &mission);
} else {
orb_publish(ORB_ID(mission), _offboard_mission_pub, &mission);
}
_offboard_mission_pub.publish(mission);
return PX4_OK;

5
src/modules/mavlink/mavlink_mission.h

@ -46,6 +46,7 @@ @@ -46,6 +46,7 @@
#pragma once
#include <dataman/dataman.h>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/mission_result.h>
@ -78,7 +79,7 @@ class MavlinkMissionManager @@ -78,7 +79,7 @@ class MavlinkMissionManager
public:
explicit MavlinkMissionManager(Mavlink *mavlink);
~MavlinkMissionManager();
~MavlinkMissionManager() = default;
/**
* Handle sending of messages. Call this regularly at a fixed frequency.
@ -127,7 +128,7 @@ private: @@ -127,7 +128,7 @@ private:
uORB::Subscription _mission_result_sub{ORB_ID(mission_result)};
orb_advert_t _offboard_mission_pub{nullptr};
uORB::Publication<mission_s> _offboard_mission_pub{ORB_ID(mission)};
static uint16_t _geofence_update_counter;
static uint16_t _safepoint_update_counter;

9
src/modules/mavlink/mavlink_parameters.cpp

@ -256,14 +256,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg) @@ -256,14 +256,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
}
_rc_param_map.timestamp = hrt_absolute_time();
if (_rc_param_map_pub == nullptr) {
_rc_param_map_pub = orb_advertise(ORB_ID(rc_parameter_map), &_rc_param_map);
} else {
orb_publish(ORB_ID(rc_parameter_map), _rc_param_map_pub, &_rc_param_map);
}
_rc_param_map_pub.publish(_rc_param_map);
}
break;

3
src/modules/mavlink/mavlink_parameters.h

@ -45,6 +45,7 @@ @@ -45,6 +45,7 @@
#include <parameters/param.h>
#include "mavlink_bridge_header.h"
#include <uORB/Publication.hpp>
#include <uORB/PublicationQueued.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/rc_parameter_map.h>
@ -125,7 +126,7 @@ protected: @@ -125,7 +126,7 @@ protected:
bool _uavcan_waiting_for_request_response{false}; ///< We have reqested a parameter and wait for the response
uint16_t _uavcan_queued_request_items{0}; ///< Number of stored parameter requests currently in the list
orb_advert_t _rc_param_map_pub{nullptr};
uORB::Publication<rc_parameter_map_s> _rc_param_map_pub{ORB_ID(rc_parameter_map)};
rc_parameter_map_s _rc_param_map{};
uORB::PublicationQueued<uavcan_parameter_request_s> _uavcan_parameter_request_pub{ORB_ID(uavcan_parameter_request)};

18
src/modules/mavlink/mavlink_timesync.cpp

@ -48,13 +48,6 @@ MavlinkTimesync::MavlinkTimesync(Mavlink *mavlink) : @@ -48,13 +48,6 @@ MavlinkTimesync::MavlinkTimesync(Mavlink *mavlink) :
{
}
MavlinkTimesync::~MavlinkTimesync()
{
if (_timesync_status_pub) {
orb_unadvertise(_timesync_status_pub);
}
}
void
MavlinkTimesync::handle_message(const mavlink_message_t *msg)
{
@ -145,7 +138,7 @@ MavlinkTimesync::handle_message(const mavlink_message_t *msg) @@ -145,7 +138,7 @@ MavlinkTimesync::handle_message(const mavlink_message_t *msg)
}
// Publish status message
struct timesync_status_s tsync_status = {};
timesync_status_s tsync_status{};
tsync_status.timestamp = hrt_absolute_time();
tsync_status.remote_timestamp = tsync.tc1 / 1000ULL;
@ -153,14 +146,7 @@ MavlinkTimesync::handle_message(const mavlink_message_t *msg) @@ -153,14 +146,7 @@ MavlinkTimesync::handle_message(const mavlink_message_t *msg)
tsync_status.estimated_offset = (int64_t)_time_offset;
tsync_status.round_trip_time = rtt_us;
if (_timesync_status_pub == nullptr) {
int instance;
_timesync_status_pub = orb_advertise_multi(ORB_ID(timesync_status), &tsync_status, &instance, ORB_PRIO_DEFAULT);
} else {
orb_publish(ORB_ID(timesync_status), _timesync_status_pub, &tsync_status);
}
_timesync_status_pub.publish(tsync_status);
}
break;

6
src/modules/mavlink/mavlink_timesync.h

@ -42,7 +42,7 @@ @@ -42,7 +42,7 @@
#include "mavlink_bridge_header.h"
#include <uORB/uORB.h>
#include <uORB/PublicationMulti.hpp>
#include <uORB/topics/timesync_status.h>
#include <drivers/drv_hrt.h>
@ -98,7 +98,7 @@ class MavlinkTimesync @@ -98,7 +98,7 @@ class MavlinkTimesync
{
public:
explicit MavlinkTimesync(Mavlink *mavlink);
~MavlinkTimesync();
~MavlinkTimesync() = default;
void handle_message(const mavlink_message_t *msg);
@ -132,7 +132,7 @@ protected: @@ -132,7 +132,7 @@ protected:
*/
void reset_filter();
orb_advert_t _timesync_status_pub{nullptr};
uORB::PublicationMulti<timesync_status_s> _timesync_status_pub{ORB_ID(timesync_status)};
uint32_t _sequence{0};

10
src/modules/mavlink/mavlink_ulog.cpp

@ -68,9 +68,6 @@ MavlinkULog::MavlinkULog(int datarate, float max_rate_factor, uint8_t target_sys @@ -68,9 +68,6 @@ MavlinkULog::MavlinkULog(int datarate, float max_rate_factor, uint8_t target_sys
MavlinkULog::~MavlinkULog()
{
if (_ulog_stream_ack_pub) {
orb_unadvertise(_ulog_stream_ack_pub);
}
}
void MavlinkULog::start_ack_received()
@ -257,10 +254,5 @@ void MavlinkULog::publish_ack(uint16_t sequence) @@ -257,10 +254,5 @@ void MavlinkULog::publish_ack(uint16_t sequence)
ack.timestamp = hrt_absolute_time();
ack.sequence = sequence;
if (_ulog_stream_ack_pub == nullptr) {
_ulog_stream_ack_pub = orb_advertise(ORB_ID(ulog_stream_ack), &ack);
} else {
orb_publish(ORB_ID(ulog_stream_ack), _ulog_stream_ack_pub, &ack);
}
_ulog_stream_ack_pub.publish(ack);
}

3
src/modules/mavlink/mavlink_ulog.h

@ -46,6 +46,7 @@ @@ -46,6 +46,7 @@
#include <px4_sem.h>
#include <drivers/drv_hrt.h>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/ulog_stream.h>
#include <uORB/topics/ulog_stream_ack.h>
@ -121,7 +122,7 @@ private: @@ -121,7 +122,7 @@ private:
static const float _rate_calculation_delta_t; ///< rate update interval
uORB::SubscriptionData<ulog_stream_s> _ulog_stream_sub{ORB_ID(ulog_stream)};
orb_advert_t _ulog_stream_ack_pub = nullptr;
uORB::Publication<ulog_stream_ack_s> _ulog_stream_ack_pub{ORB_ID(ulog_stream_ack)};
uint16_t _wait_for_ack_sequence;
uint8_t _sent_tries = 0;
volatile bool _ack_received = false; ///< set to true if a matching ack received

Loading…
Cancel
Save