Class MissionBase

Inheritance Relationships

Base Type

Class Documentation

class MissionBase : public mavros::plugin::Plugin

Mission protocol base plugin.

Public Functions

inline MissionBase(plugin::UASPtr uas_, const std::string &name_, MTYPE mission_type_ = MTYPE::MISSION, const char *log_prefix_ = "WP", const std::chrono::nanoseconds bootup_time_ = 15s)
inline virtual Subscriptions get_subscriptions() override

Return vector of MAVLink message subscriptions (handlers)

Protected Types

enum class WP

Values:

enumerator IDLE
enumerator RXLIST
enumerator RXWP
enumerator RXWPINT
enumerator TXLIST
enumerator TXPARTIAL
enumerator TXWP
enumerator TXWPINT
enumerator CLEAR
enumerator SET_CUR
using unique_lock = std::unique_lock<std::recursive_mutex>
using lock_guard = std::lock_guard<std::recursive_mutex>

Protected Functions

template<class MsgT>
inline bool filter_message(const MsgT &m)

filters messages not suitable for that plugin

template<class MsgT>
inline bool sequence_mismatch(const MsgT &m)

checks for a sequence mismatch between a MISSION_REQUEST(_INT) sequence and the current waypoint that should be sent.

Parameters:

seq – The seq member of a MISSION_REQUEST(_INT)

Returns:

True if there is a sequence mismatch

handle MISSION_ITEM mavlink msg handles and stores mission items when pulling waypoints

Parameters:
  • msg – Received Mavlink msg

  • wpi – WaypointItem from msg

handle MISSION_ITEM_INT mavlink msg handles and stores mission items when pulling waypoints

Parameters:
  • msg – Received Mavlink msg

  • wpi – WaypointItemInt from msg

handle MISSION_REQUEST mavlink msg handles and acts on misison request from FCU

Parameters:
  • msg – Received Mavlink msg

  • mreq – MISSION_REQUEST from msg

handle MISSION_REQUEST_INT mavlink msg handles and acts on misison request from FCU

Parameters:
  • msg – Received Mavlink msg

  • mreq – MISSION_REQUEST_INT from msg

handle MISSION_COUNT mavlink msg Handles a mission count from FCU in a Waypoint Pull Triggers a pull GCS seems to be requesting mission

Parameters:
  • msg – Received Mavlink msg

  • mcnt – MISSION_COUNT from msg

handle MISSION_ACK mavlink msg Handles a MISSION_ACK which marks the end of a push, or a failure

Parameters:
  • msg – Received Mavlink msg

  • mack – MISSION_ACK from msg

handle MISSION_CURRENT mavlink msg This confirms a SET_CUR action

Parameters:
  • msg – Received Mavlink msg

  • mcur – MISSION_CURRENT from msg

handle MISSION_ITEM_REACHED mavlink msg

Parameters:
  • msg – Received Mavlink msg

  • mitr – MISSION_ITEM_REACHED from msg

void timeout_cb()

Act on a timeout Resend the message that may have been lost.

inline void scheduled_pull_cb()

Callback for scheduled waypoint pull.

inline void request_mission_done(void)

Send ACK back to FCU after pull.

inline void go_idle(void)
inline void restart_timeout_timer(void)
inline void restart_timeout_timer_int(void)
inline void schedule_pull(const std::chrono::nanoseconds &dt)
template<class MsgT>
inline void send_waypoint(size_t seq)

send a single waypoint to FCU

inline bool wait_fetch_all()

wait until a waypoint pull is complete. Pull happens asynchronously, this function blocks until it is done.

inline bool wait_push_all()

wait until a waypoint push is complete. Push happens asynchronously, this function blocks until it is done.

inline void set_current_waypoint(size_t seq)

set the FCU current waypoint

virtual void publish_waypoints() = 0

publish the updated waypoint list after operation

virtual void publish_reached(const uint16_t seq) = 0

publish mission item reached seq

template<class MsgT>
inline void mission_send(MsgT &wpi)
void mission_request(const uint16_t seq)
void mission_request_int(const uint16_t seq)
void mission_set_current(const uint16_t seq)
void mission_request_list()
void mission_count(const uint16_t cnt)
void mission_write_partial_list(const uint16_t start_index, const uint16_t end_index)
void mission_clear_all()
void mission_ack(const MRES type)

Protected Attributes

std::recursive_mutex mutex
std::vector<MissionItem> waypoints
std::vector<MissionItem> send_waypoints
const MTYPE mission_type
const char *log_prefix
WP wp_state
size_t wp_count
size_t wp_start_id
size_t wp_end_id
size_t wp_cur_id
size_t wp_cur_active
size_t wp_set_active
size_t wp_retries
bool is_timedout
std::mutex recv_cond_mutex
std::mutex send_cond_mutex
std::condition_variable list_receiving
std::condition_variable list_sending
rclcpp::TimerBase::SharedPtr timeout_timer
rclcpp::TimerBase::SharedPtr schedule_timer
bool reschedule_pull
bool do_pull_after_gcs
bool enable_partial_push
bool use_mission_item_int
bool mission_item_int_support_confirmed
const std::chrono::nanoseconds BOOTUP_TIME
const std::chrono::nanoseconds LIST_TIMEOUT
const std::chrono::nanoseconds WP_TIMEOUT
const std::chrono::nanoseconds RESCHEDULE_TIME

Protected Static Attributes

static constexpr int RETRIES_COUNT = 3