PX4 Firmware
PX4 Autopilot Software http://px4.io
MavlinkMissionManager Class Reference

#include <mavlink_mission.h>

Collaboration diagram for MavlinkMissionManager:

Public Member Functions

 MavlinkMissionManager (Mavlink *mavlink)
 
 ~MavlinkMissionManager ()=default
 
void send (const hrt_abstime t)
 Handle sending of messages. More...
 
void handle_message (const mavlink_message_t *msg)
 
void check_active_mission (void)
 

Private Member Functions

uint16_t current_max_item_count ()
 get the maximum number of item count for the current _mission_type More...
 
uint16_t current_item_count ()
 get the number of item count for the current _mission_type More...
 
 MavlinkMissionManager (MavlinkMissionManager &)
 
MavlinkMissionManageroperator= (const MavlinkMissionManager &)
 
void init_offboard_mission ()
 
int update_active_mission (dm_item_t dataman_id, uint16_t count, int32_t seq)
 Publish mission topic to notify navigator about changes. More...
 
int update_geofence_count (unsigned count)
 store the geofence count to dataman More...
 
int update_safepoint_count (unsigned count)
 store the safepoint count to dataman More...
 
int load_geofence_stats ()
 load geofence stats from dataman More...
 
int load_safepoint_stats ()
 load safe point stats from dataman More...
 
void send_mission_ack (uint8_t sysid, uint8_t compid, uint8_t type)
 Sends an waypoint ack message. More...
 
void send_mission_current (uint16_t seq)
 Broadcasts the new target waypoint and directs the MAV to fly there. More...
 
void send_mission_count (uint8_t sysid, uint8_t compid, uint16_t count, MAV_MISSION_TYPE mission_type)
 
void send_mission_item (uint8_t sysid, uint8_t compid, uint16_t seq)
 
void send_mission_request (uint8_t sysid, uint8_t compid, uint16_t seq)
 
void send_mission_item_reached (uint16_t seq)
 emits a message that a waypoint reached More...
 
void handle_mission_ack (const mavlink_message_t *msg)
 
void handle_mission_set_current (const mavlink_message_t *msg)
 
void handle_mission_request_list (const mavlink_message_t *msg)
 
void handle_mission_request (const mavlink_message_t *msg)
 
void handle_mission_request_int (const mavlink_message_t *msg)
 
void handle_mission_request_both (const mavlink_message_t *msg)
 
void handle_mission_count (const mavlink_message_t *msg)
 
void handle_mission_item (const mavlink_message_t *msg)
 
void handle_mission_item_int (const mavlink_message_t *msg)
 
void handle_mission_item_both (const mavlink_message_t *msg)
 
void handle_mission_clear_all (const mavlink_message_t *msg)
 
int parse_mavlink_mission_item (const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item)
 Parse mavlink MISSION_ITEM message to get mission_item_s. More...
 
int format_mavlink_mission_item (const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item)
 Format mission_item_s as mavlink MISSION_ITEM(_INT) message. More...
 
void switch_to_idle_state ()
 set _state to idle (and do necessary cleanup) More...
 

Private Attributes

uint64_t _time_last_recv {0}
 
uint64_t _time_last_sent {0}
 
uint8_t _reached_sent_count {0}
 last time when the vehicle reached a waypoint More...
 
bool _int_mode {false}
 Use accurate int32 instead of float. More...
 
unsigned _filesystem_errcount {0}
 File system error count. More...
 
dm_item_t _my_dataman_id {DM_KEY_WAYPOINTS_OFFBOARD_0}
 class Dataman storage ID More...
 
int32_t _last_reached {-1}
 Last reached waypoint in active mission (-1 means nothing reached) More...
 
dm_item_t _transfer_dataman_id {DM_KEY_WAYPOINTS_OFFBOARD_1}
 Dataman storage ID for current transmission. More...
 
uint16_t _transfer_count {0}
 Items count in current transmission. More...
 
uint16_t _transfer_seq {0}
 Item sequence in current transmission. More...
 
int32_t _transfer_current_seq {-1}
 Current item ID for current transmission (-1 means not initialized) More...
 
uint8_t _transfer_partner_sysid {0}
 Partner system ID for current transmission. More...
 
uint8_t _transfer_partner_compid {0}
 Partner component ID for current transmission. More...
 
uORB::Subscription _mission_result_sub {ORB_ID(mission_result)}
 
uORB::Publication< mission_s_offboard_mission_pub {ORB_ID(mission)}
 
bool _geofence_locked {false}
 if true, we currently hold the dm_lock for the geofence (transaction in progress) More...
 
MavlinkRateLimiter _slow_rate_limiter {100 * 1000}
 Rate limit sending of the current WP sequence to 10 Hz. More...
 
Mavlink_mavlink
 

Static Private Attributes

static dm_item_t _dataman_id = DM_KEY_WAYPOINTS_OFFBOARD_0
 Global Dataman storage ID for active mission. More...
 
static bool _dataman_init = false
 Dataman initialized. More...
 
static uint16_t _count [3] = { 0, 0, 0 }
 Count of items in (active) mission for each MAV_MISSION_TYPE. More...
 
static int32_t _current_seq = 0
 Current item sequence in active mission. More...
 
static bool _transfer_in_progress = false
 Global variable checking for current transmission. More...
 
static uint16_t _geofence_update_counter = 0
 
static uint16_t _safepoint_update_counter = 0
 
static constexpr unsigned int FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT
 Error count limit before stopping to report FS errors. More...
 
static constexpr uint16_t MAX_COUNT []
 Maximum number of mission items for each type (fence & safe points use the first item for the stats) More...
 

Detailed Description

Definition at line 77 of file mavlink_mission.h.

Constructor & Destructor Documentation

◆ MavlinkMissionManager() [1/2]

MavlinkMissionManager::MavlinkMissionManager ( Mavlink mavlink)
explicit

Definition at line 73 of file mavlink_mission.cpp.

References init_offboard_mission().

Here is the call graph for this function:

◆ ~MavlinkMissionManager()

MavlinkMissionManager::~MavlinkMissionManager ( )
default

◆ MavlinkMissionManager() [2/2]

MavlinkMissionManager::MavlinkMissionManager ( MavlinkMissionManager )
private

Member Function Documentation

◆ check_active_mission()

void MavlinkMissionManager::check_active_mission ( void  )

Definition at line 1646 of file mavlink_mission.cpp.

References _count, _dataman_id, _mavlink, _my_dataman_id, _transfer_partner_compid, _transfer_partner_sysid, Mavlink::get_mode(), Mavlink::MAVLINK_MODE_IRIDIUM, and send_mission_count().

Referenced by MavlinkReceiver::Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ current_item_count()

uint16_t MavlinkMissionManager::current_item_count ( )
private

get the number of item count for the current _mission_type

Definition at line 409 of file mavlink_mission.cpp.

References _count.

Referenced by handle_mission_ack(), handle_mission_request_both(), and handle_mission_request_list().

Here is the caller graph for this function:

◆ current_max_item_count()

uint16_t MavlinkMissionManager::current_max_item_count ( )
private

get the maximum number of item count for the current _mission_type

Definition at line 398 of file mavlink_mission.cpp.

References MAX_COUNT.

Referenced by handle_mission_count(), and send_mission_request().

Here is the caller graph for this function:

◆ format_mavlink_mission_item()

int MavlinkMissionManager::format_mavlink_mission_item ( const struct mission_item_s mission_item,
mavlink_mission_item_t *  mavlink_mission_item 
)
private

Format mission_item_s as mavlink MISSION_ITEM(_INT) message.

Parameters
mission_itempointer to the existing mission item
mavlink_mission_itempointer to mavlink_mission_item_t or mavlink_mission_item_int_t depending on _int_mode.

Definition at line 1494 of file mavlink_mission.cpp.

References _int_mode, mission_item_s::acceptance_radius, mission_item_s::altitude, mission_item_s::altitude_is_relative, mission_item_s::autocontinue, mission_item_s::circle_radius, math::degrees(), mission_item_s::do_jump_mission_index, mission_item_s::do_jump_repeat_count, mission_item_s::force_heading, mission_item_s::frame, mission_item_s::land_precision, mission_item_s::lat, mission_item_s::loiter_exit_xtrack, mission_item_s::loiter_radius, mission_item_s::lon, mission_item_s::nav_cmd, NAV_CMD_DO_CHANGE_SPEED, NAV_CMD_DO_DIGICAM_CONTROL, NAV_CMD_DO_JUMP, NAV_CMD_DO_LAND_START, NAV_CMD_DO_MOUNT_CONFIGURE, NAV_CMD_DO_MOUNT_CONTROL, NAV_CMD_DO_SET_CAM_TRIGG_DIST, NAV_CMD_DO_SET_CAM_TRIGG_INTERVAL, NAV_CMD_DO_SET_HOME, NAV_CMD_DO_SET_ROI, NAV_CMD_DO_SET_SERVO, NAV_CMD_DO_TRIGGER_CONTROL, NAV_CMD_DO_VTOL_TRANSITION, NAV_CMD_IMAGE_START_CAPTURE, NAV_CMD_IMAGE_STOP_CAPTURE, NAV_CMD_LAND, NAV_CMD_LOITER_TIME_LIMIT, NAV_CMD_LOITER_TO_ALT, NAV_CMD_LOITER_UNLIMITED, NAV_CMD_SET_CAMERA_MODE, NAV_CMD_TAKEOFF, NAV_CMD_VIDEO_START_CAPTURE, NAV_CMD_VIDEO_STOP_CAPTURE, NAV_CMD_WAYPOINT, mission_item_s::params, mission_item_s::pitch_min, mission_item_s::time_inside, mission_item_s::vertex_count, and mission_item_s::yaw.

Referenced by send_mission_item().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_message()

void MavlinkMissionManager::handle_message ( const mavlink_message_t *  msg)

Definition at line 550 of file mavlink_mission.cpp.

References handle_mission_ack(), handle_mission_clear_all(), handle_mission_count(), handle_mission_item(), handle_mission_item_int(), handle_mission_request(), handle_mission_request_int(), handle_mission_request_list(), and handle_mission_set_current().

Referenced by MavlinkReceiver::Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_mission_ack()

void MavlinkMissionManager::handle_mission_ack ( const mavlink_message_t *  msg)
private

Definition at line 596 of file mavlink_mission.cpp.

References _int_mode, _mavlink, _time_last_recv, _transfer_partner_compid, _transfer_partner_sysid, _transfer_seq, CHECK_SYSID_COMPID_MISSION, current_item_count(), hrt_absolute_time(), MAVLINK_WPM_STATE_GETLIST, MAVLINK_WPM_STATE_SENDLIST, send_mission_request(), Mavlink::send_statustext_critical(), and switch_to_idle_state().

Referenced by handle_message().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_mission_clear_all()

void MavlinkMissionManager::handle_mission_clear_all ( const mavlink_message_t *  msg)
private

Definition at line 1205 of file mavlink_mission.cpp.

References _dataman_id, _mavlink, _time_last_recv, _transfer_partner_compid, _transfer_partner_sysid, CHECK_SYSID_COMPID_MISSION, DM_KEY_WAYPOINTS_OFFBOARD_0, DM_KEY_WAYPOINTS_OFFBOARD_1, hrt_absolute_time(), MAVLINK_WPM_STATE_IDLE, send_mission_ack(), Mavlink::send_statustext_critical(), update_active_mission(), update_geofence_count(), and update_safepoint_count().

Referenced by handle_message().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_mission_count()

void MavlinkMissionManager::handle_mission_count ( const mavlink_message_t *  msg)
private

Definition at line 838 of file mavlink_mission.cpp.

References _dataman_id, _geofence_locked, _mavlink, _time_last_recv, _transfer_count, _transfer_current_seq, _transfer_dataman_id, _transfer_in_progress, _transfer_partner_compid, _transfer_partner_sysid, _transfer_seq, CHECK_SYSID_COMPID_MISSION, current_max_item_count(), DM_KEY_FENCE_POINTS, DM_KEY_WAYPOINTS_OFFBOARD_0, DM_KEY_WAYPOINTS_OFFBOARD_1, dm_lock(), hrt_absolute_time(), MAVLINK_WPM_STATE_GETLIST, MAVLINK_WPM_STATE_IDLE, send_mission_ack(), send_mission_request(), Mavlink::send_statustext_critical(), update_active_mission(), update_geofence_count(), and update_safepoint_count().

Referenced by handle_message().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_mission_item()

void MavlinkMissionManager::handle_mission_item ( const mavlink_message_t *  msg)
private

Definition at line 969 of file mavlink_mission.cpp.

References _int_mode, and handle_mission_item_both().

Referenced by handle_message().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_mission_item_both()

void MavlinkMissionManager::handle_mission_item_both ( const mavlink_message_t *  msg)
private

◆ handle_mission_item_int()

void MavlinkMissionManager::handle_mission_item_int ( const mavlink_message_t *  msg)
private

Definition at line 980 of file mavlink_mission.cpp.

References _int_mode, and handle_mission_item_both().

Referenced by handle_message().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_mission_request()

void MavlinkMissionManager::handle_mission_request ( const mavlink_message_t *  msg)
private

Definition at line 732 of file mavlink_mission.cpp.

References _int_mode, and handle_mission_request_both().

Referenced by handle_message().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_mission_request_both()

void MavlinkMissionManager::handle_mission_request_both ( const mavlink_message_t *  msg)
private

Definition at line 754 of file mavlink_mission.cpp.

References _mavlink, _time_last_recv, _transfer_count, _transfer_partner_compid, _transfer_partner_sysid, _transfer_seq, CHECK_SYSID_COMPID_MISSION, current_item_count(), hrt_absolute_time(), MAVLINK_WPM_STATE_IDLE, MAVLINK_WPM_STATE_SENDLIST, send_mission_ack(), send_mission_item(), Mavlink::send_statustext_critical(), and switch_to_idle_state().

Referenced by handle_mission_request(), and handle_mission_request_int().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_mission_request_int()

void MavlinkMissionManager::handle_mission_request_int ( const mavlink_message_t *  msg)
private

Definition at line 743 of file mavlink_mission.cpp.

References _int_mode, and handle_mission_request_both().

Referenced by handle_message().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_mission_request_list()

void MavlinkMissionManager::handle_mission_request_list ( const mavlink_message_t *  msg)
private

Definition at line 681 of file mavlink_mission.cpp.

References _mavlink, _time_last_recv, _transfer_count, _transfer_partner_compid, _transfer_partner_sysid, _transfer_seq, CHECK_SYSID_COMPID_MISSION, current_item_count(), hrt_absolute_time(), load_geofence_stats(), load_safepoint_stats(), MAVLINK_WPM_STATE_IDLE, MAVLINK_WPM_STATE_SENDLIST, send_mission_count(), and Mavlink::send_statustext_critical().

Referenced by handle_message().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_mission_set_current()

void MavlinkMissionManager::handle_mission_set_current ( const mavlink_message_t *  msg)
private

Definition at line 646 of file mavlink_mission.cpp.

References _count, _dataman_id, _mavlink, _time_last_recv, CHECK_SYSID_COMPID_MISSION, hrt_absolute_time(), MAVLINK_WPM_STATE_IDLE, Mavlink::send_statustext_critical(), and update_active_mission().

Referenced by handle_message().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ init_offboard_mission()

void MavlinkMissionManager::init_offboard_mission ( )
private

Definition at line 80 of file mavlink_mission.cpp.

References _count, _current_seq, _dataman_id, _dataman_init, _my_dataman_id, mission_s::count, mission_s::current_seq, mission_s::dataman_id, DM_KEY_MISSION_STATE, dm_lock(), dm_read(), dm_unlock(), load_geofence_stats(), and load_safepoint_stats().

Referenced by MavlinkMissionManager().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ load_geofence_stats()

int MavlinkMissionManager::load_geofence_stats ( )
private

load geofence stats from dataman

Definition at line 118 of file mavlink_mission.cpp.

References _count, _geofence_update_counter, DM_KEY_FENCE_POINTS, dm_read(), mission_stats_entry_s::num_items, and mission_stats_entry_s::update_counter.

Referenced by handle_mission_request_list(), and init_offboard_mission().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ load_safepoint_stats()

int MavlinkMissionManager::load_safepoint_stats ( )
private

load safe point stats from dataman

Definition at line 133 of file mavlink_mission.cpp.

References _count, DM_KEY_SAFE_POINTS, dm_read(), and mission_stats_entry_s::num_items.

Referenced by handle_mission_request_list(), and init_offboard_mission().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ operator=()

MavlinkMissionManager& MavlinkMissionManager::operator= ( const MavlinkMissionManager )
private

◆ parse_mavlink_mission_item()

int MavlinkMissionManager::parse_mavlink_mission_item ( const mavlink_mission_item_t *  mavlink_mission_item,
struct mission_item_s mission_item 
)
private

Parse mavlink MISSION_ITEM message to get mission_item_s.

Parameters
mavlink_mission_itempointer to mavlink_mission_item_t or mavlink_mission_item_int_t depending on _int_mode
mission_itempointer to mission_item to construct

Definition at line 1263 of file mavlink_mission.cpp.

References _int_mode, mission_item_s::acceptance_radius, mission_item_s::altitude, mission_item_s::altitude_is_relative, mission_item_s::autocontinue, mission_item_s::circle_radius, mission_item_s::do_jump_current_count, mission_item_s::do_jump_mission_index, mission_item_s::do_jump_repeat_count, mission_item_s::force_heading, mission_item_s::frame, mission_item_s::land_precision, mission_item_s::lat, mission_item_s::loiter_exit_xtrack, mission_item_s::loiter_radius, mission_item_s::lon, mission_item_s::nav_cmd, NAV_CMD_DO_JUMP, NAV_CMD_DO_SET_ROI, NAV_CMD_DO_SET_ROI_LOCATION, NAV_CMD_INVALID, NAV_CMD_LAND, NAV_CMD_LOITER_TIME_LIMIT, NAV_CMD_LOITER_TO_ALT, NAV_CMD_LOITER_UNLIMITED, NAV_CMD_TAKEOFF, NAV_CMD_WAYPOINT, mission_item_s::origin, ORIGIN_MAVLINK, mission_item_s::params, mission_item_s::pitch_min, math::radians(), mission_item_s::time_inside, mission_item_s::vertex_count, matrix::wrap_2pi(), and mission_item_s::yaw.

Referenced by handle_mission_item_both().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ send()

void MavlinkMissionManager::send ( const hrt_abstime  t)

Handle sending of messages.

Call this regularly at a fixed frequency.

Parameters
tcurrent time

Definition at line 470 of file mavlink_mission.cpp.

References _current_seq, _last_reached, _mavlink, _mission_result_sub, _reached_sent_count, _slow_rate_limiter, _time_last_recv, _time_last_sent, _transfer_in_progress, _transfer_partner_compid, _transfer_partner_sysid, _transfer_seq, MavlinkRateLimiter::check(), Mavlink::get_mode(), hrt_elapsed_time(), MAVLINK_MISSION_PROTOCOL_TIMEOUT_DEFAULT, MAVLINK_MISSION_RETRY_TIMEOUT_DEFAULT, Mavlink::MAVLINK_MODE_IRIDIUM, MAVLINK_WPM_STATE_GETLIST, MAVLINK_WPM_STATE_IDLE, send_mission_current(), send_mission_item(), send_mission_item_reached(), send_mission_request(), Mavlink::send_statustext_critical(), switch_to_idle_state(), and uORB::Subscription::update().

Referenced by MavlinkReceiver::Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ send_mission_ack()

void MavlinkMissionManager::send_mission_ack ( uint8_t  sysid,
uint8_t  compid,
uint8_t  type 
)
private

Sends an waypoint ack message.

Definition at line 249 of file mavlink_mission.cpp.

References _mavlink, and Mavlink::get_channel().

Referenced by handle_mission_clear_all(), handle_mission_count(), handle_mission_item_both(), handle_mission_request_both(), and send_mission_item().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ send_mission_count()

void MavlinkMissionManager::send_mission_count ( uint8_t  sysid,
uint8_t  compid,
uint16_t  count,
MAV_MISSION_TYPE  mission_type 
)
private

Definition at line 287 of file mavlink_mission.cpp.

References _mavlink, _time_last_sent, Mavlink::get_channel(), and hrt_absolute_time().

Referenced by check_active_mission(), and handle_mission_request_list().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ send_mission_current()

void MavlinkMissionManager::send_mission_current ( uint16_t  seq)
private

Broadcasts the new target waypoint and directs the MAV to fly there.

This function broadcasts its new active waypoint sequence number and sends a message to the controller, advising it to fly to the coordinates of the waypoint with a given orientation

Parameters
seqThe waypoint sequence number the MAV should fly to.

Definition at line 264 of file mavlink_mission.cpp.

References _count, _mavlink, Mavlink::get_channel(), and Mavlink::send_statustext_critical().

Referenced by send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ send_mission_item()

◆ send_mission_item_reached()

void MavlinkMissionManager::send_mission_item_reached ( uint16_t  seq)
private

emits a message that a waypoint reached

This function broadcasts a message that a waypoint is reached.

Parameters
seqThe waypoint sequence number the MAV has reached.

Definition at line 457 of file mavlink_mission.cpp.

References _mavlink, and Mavlink::get_channel().

Referenced by send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ send_mission_request()

void MavlinkMissionManager::send_mission_request ( uint8_t  sysid,
uint8_t  compid,
uint16_t  seq 
)
private

Definition at line 420 of file mavlink_mission.cpp.

References _int_mode, _mavlink, _time_last_sent, current_max_item_count(), Mavlink::get_channel(), hrt_absolute_time(), and Mavlink::send_statustext_critical().

Referenced by handle_mission_ack(), handle_mission_count(), handle_mission_item_both(), and send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ switch_to_idle_state()

void MavlinkMissionManager::switch_to_idle_state ( )
private

set _state to idle (and do necessary cleanup)

Definition at line 953 of file mavlink_mission.cpp.

References _geofence_locked, DM_KEY_FENCE_POINTS, dm_unlock(), and MAVLINK_WPM_STATE_IDLE.

Referenced by handle_mission_ack(), handle_mission_item_both(), handle_mission_request_both(), and send().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_active_mission()

int MavlinkMissionManager::update_active_mission ( dm_item_t  dataman_id,
uint16_t  count,
int32_t  seq 
)
private

Publish mission topic to notify navigator about changes.

Definition at line 150 of file mavlink_mission.cpp.

References _count, _current_seq, _dataman_id, _filesystem_errcount, _mavlink, _my_dataman_id, _offboard_mission_pub, DM_KEY_MISSION_STATE, dm_lock(), DM_PERSIST_POWER_ON_RESET, dm_unlock(), dm_write(), FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT, hrt_absolute_time(), uORB::Publication< T >::publish(), Mavlink::send_statustext_critical(), and mission_s::timestamp.

Referenced by handle_mission_clear_all(), handle_mission_count(), handle_mission_item_both(), and handle_mission_set_current().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_geofence_count()

int MavlinkMissionManager::update_geofence_count ( unsigned  count)
private

store the geofence count to dataman

Definition at line 198 of file mavlink_mission.cpp.

References _count, _filesystem_errcount, _geofence_update_counter, _mavlink, DM_KEY_FENCE_POINTS, DM_PERSIST_POWER_ON_RESET, dm_write(), FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT, mission_stats_entry_s::num_items, Mavlink::send_statustext_critical(), and mission_stats_entry_s::update_counter.

Referenced by handle_mission_clear_all(), handle_mission_count(), and handle_mission_item_both().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_safepoint_count()

int MavlinkMissionManager::update_safepoint_count ( unsigned  count)
private

store the safepoint count to dataman

Definition at line 224 of file mavlink_mission.cpp.

References _count, _filesystem_errcount, _mavlink, _safepoint_update_counter, DM_KEY_SAFE_POINTS, DM_PERSIST_POWER_ON_RESET, dm_write(), FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT, mission_stats_entry_s::num_items, Mavlink::send_statustext_critical(), and mission_stats_entry_s::update_counter.

Referenced by handle_mission_clear_all(), handle_mission_count(), and handle_mission_item_both().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _count

uint16_t MavlinkMissionManager::_count = { 0, 0, 0 }
staticprivate

◆ _current_seq

int32_t MavlinkMissionManager::_current_seq = 0
staticprivate

Current item sequence in active mission.

Definition at line 113 of file mavlink_mission.h.

Referenced by init_offboard_mission(), send(), send_mission_item(), and update_active_mission().

◆ _dataman_id

dm_item_t MavlinkMissionManager::_dataman_id = DM_KEY_WAYPOINTS_OFFBOARD_0
staticprivate

◆ _dataman_init

bool MavlinkMissionManager::_dataman_init = false
staticprivate

Dataman initialized.

Definition at line 110 of file mavlink_mission.h.

Referenced by init_offboard_mission().

◆ _filesystem_errcount

unsigned MavlinkMissionManager::_filesystem_errcount {0}
private

File system error count.

Definition at line 105 of file mavlink_mission.h.

Referenced by send_mission_item(), update_active_mission(), update_geofence_count(), and update_safepoint_count().

◆ _geofence_locked

bool MavlinkMissionManager::_geofence_locked {false}
private

if true, we currently hold the dm_lock for the geofence (transaction in progress)

Definition at line 135 of file mavlink_mission.h.

Referenced by handle_mission_count(), and switch_to_idle_state().

◆ _geofence_update_counter

uint16_t MavlinkMissionManager::_geofence_update_counter = 0
staticprivate

Definition at line 133 of file mavlink_mission.h.

Referenced by load_geofence_stats(), and update_geofence_count().

◆ _int_mode

bool MavlinkMissionManager::_int_mode {false}
private

◆ _last_reached

int32_t MavlinkMissionManager::_last_reached {-1}
private

Last reached waypoint in active mission (-1 means nothing reached)

Definition at line 115 of file mavlink_mission.h.

Referenced by send().

◆ _mavlink

◆ _mission_result_sub

uORB::Subscription MavlinkMissionManager::_mission_result_sub {ORB_ID(mission_result)}
private

Definition at line 129 of file mavlink_mission.h.

Referenced by send().

◆ _my_dataman_id

dm_item_t MavlinkMissionManager::_my_dataman_id {DM_KEY_WAYPOINTS_OFFBOARD_0}
private

class Dataman storage ID

Definition at line 108 of file mavlink_mission.h.

Referenced by check_active_mission(), init_offboard_mission(), and update_active_mission().

◆ _offboard_mission_pub

uORB::Publication<mission_s> MavlinkMissionManager::_offboard_mission_pub {ORB_ID(mission)}
private

Definition at line 131 of file mavlink_mission.h.

Referenced by update_active_mission().

◆ _reached_sent_count

uint8_t MavlinkMissionManager::_reached_sent_count {0}
private

last time when the vehicle reached a waypoint

Definition at line 101 of file mavlink_mission.h.

Referenced by send().

◆ _safepoint_update_counter

uint16_t MavlinkMissionManager::_safepoint_update_counter = 0
staticprivate

Definition at line 134 of file mavlink_mission.h.

Referenced by update_safepoint_count().

◆ _slow_rate_limiter

MavlinkRateLimiter MavlinkMissionManager::_slow_rate_limiter {100 * 1000}
private

Rate limit sending of the current WP sequence to 10 Hz.

Definition at line 137 of file mavlink_mission.h.

Referenced by send().

◆ _time_last_recv

◆ _time_last_sent

uint64_t MavlinkMissionManager::_time_last_sent {0}
private

◆ _transfer_count

uint16_t MavlinkMissionManager::_transfer_count {0}
private

Items count in current transmission.

Definition at line 119 of file mavlink_mission.h.

Referenced by handle_mission_count(), handle_mission_item_both(), handle_mission_request_both(), and handle_mission_request_list().

◆ _transfer_current_seq

int32_t MavlinkMissionManager::_transfer_current_seq {-1}
private

Current item ID for current transmission (-1 means not initialized)

Definition at line 122 of file mavlink_mission.h.

Referenced by handle_mission_count(), and handle_mission_item_both().

◆ _transfer_dataman_id

dm_item_t MavlinkMissionManager::_transfer_dataman_id {DM_KEY_WAYPOINTS_OFFBOARD_1}
private

Dataman storage ID for current transmission.

Definition at line 117 of file mavlink_mission.h.

Referenced by handle_mission_count(), and handle_mission_item_both().

◆ _transfer_in_progress

bool MavlinkMissionManager::_transfer_in_progress = false
staticprivate

Global variable checking for current transmission.

Definition at line 127 of file mavlink_mission.h.

Referenced by handle_mission_count(), handle_mission_item_both(), and send().

◆ _transfer_partner_compid

uint8_t MavlinkMissionManager::_transfer_partner_compid {0}
private

◆ _transfer_partner_sysid

uint8_t MavlinkMissionManager::_transfer_partner_sysid {0}
private

◆ _transfer_seq

uint16_t MavlinkMissionManager::_transfer_seq {0}
private

◆ FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT

constexpr unsigned int MavlinkMissionManager::FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT
staticprivate
Initial value:
=
2

Error count limit before stopping to report FS errors.

Definition at line 141 of file mavlink_mission.h.

Referenced by send_mission_item(), update_active_mission(), update_geofence_count(), and update_safepoint_count().

◆ MAX_COUNT

constexpr uint16_t MavlinkMissionManager::MAX_COUNT
staticprivate
Initial value:

Maximum number of mission items for each type (fence & safe points use the first item for the stats)

Definition at line 143 of file mavlink_mission.h.

Referenced by current_max_item_count().


The documentation for this class was generated from the following files: