96 enum MAV_MISSION_TYPE _mission_type {MAV_MISSION_TYPE_MISSION};
192 void send_mission_count(uint8_t sysid, uint8_t compid, uint16_t count, MAV_MISSION_TYPE mission_type);
242 mavlink_mission_item_t *mavlink_mission_item);
int update_geofence_count(unsigned count)
store the geofence count to dataman
Global position setpoint in WGS84 coordinates.
void handle_mission_request(const mavlink_message_t *msg)
bool _int_mode
Use accurate int32 instead of float.
static uint16_t _count[3]
Count of items in (active) mission for each MAV_MISSION_TYPE.
uint8_t _transfer_partner_sysid
Partner system ID for current transmission.
static bool _dataman_init
Dataman initialized.
MavlinkMissionManager & operator=(const MavlinkMissionManager &)
void check_active_mission(void)
uint16_t _transfer_count
Items count in current transmission.
static constexpr uint64_t MAVLINK_MISSION_PROTOCOL_TIMEOUT_DEFAULT
Protocol action timeout in us.
void send_mission_count(uint8_t sysid, uint8_t compid, uint16_t count, MAV_MISSION_TYPE mission_type)
uint8_t _transfer_partner_compid
Partner component ID for current transmission.
void send_mission_item(uint8_t sysid, uint8_t compid, uint16_t seq)
void handle_mission_request_int(const mavlink_message_t *msg)
Message rate limiter definition.
int load_geofence_stats()
load geofence stats from dataman
static int32_t _current_seq
Current item sequence in active mission.
void send_mission_current(uint16_t seq)
Broadcasts the new target waypoint and directs the MAV to fly there.
dm_item_t
Types of items that the data manager can store.
uORB::Publication< mission_s > _offboard_mission_pub
void handle_mission_set_current(const mavlink_message_t *msg)
void init_offboard_mission()
uint16_t current_max_item_count()
get the maximum number of item count for the current _mission_type
static dm_item_t _dataman_id
Global Dataman storage ID for active mission.
static char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
uORB::Subscription _mission_result_sub
static uint16_t _geofence_update_counter
MavlinkRateLimiter _slow_rate_limiter
Rate limit sending of the current WP sequence to 10 Hz.
uint16_t _transfer_seq
Item sequence in current transmission.
void handle_mission_clear_all(const mavlink_message_t *msg)
dm_item_t _my_dataman_id
class Dataman storage ID
static constexpr uint64_t MAVLINK_MISSION_RETRY_TIMEOUT_DEFAULT
Protocol retry timeout in us.
void handle_mission_request_both(const mavlink_message_t *msg)
void handle_message(const mavlink_message_t *msg)
void handle_mission_request_list(const mavlink_message_t *msg)
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.
MavlinkMissionManager(Mavlink *mavlink)
int update_safepoint_count(unsigned count)
store the safepoint count to dataman
static uint16_t _safepoint_update_counter
uint8_t _reached_sent_count
last time when the vehicle reached a waypoint
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
void handle_mission_item(const mavlink_message_t *msg)
static bool _transfer_in_progress
Global variable checking for current transmission.
void handle_mission_item_int(const mavlink_message_t *msg)
void send_mission_ack(uint8_t sysid, uint8_t compid, uint8_t type)
Sends an waypoint ack message.
void send_mission_request(uint8_t sysid, uint8_t compid, uint16_t seq)
uint16_t current_item_count()
get the number of item count for the current _mission_type
void send_mission_item_reached(uint16_t seq)
emits a message that a waypoint reached
void send(const hrt_abstime t)
Handle sending of messages.
void switch_to_idle_state()
set _state to idle (and do necessary cleanup)
static constexpr unsigned int FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT
Error count limit before stopping to report FS errors.
void handle_mission_count(const mavlink_message_t *msg)
void handle_mission_item_both(const mavlink_message_t *msg)
int update_active_mission(dm_item_t dataman_id, uint16_t count, int32_t seq)
Publish mission topic to notify navigator about changes.
bool _geofence_locked
if true, we currently hold the dm_lock for the geofence (transaction in progress) ...
void handle_mission_ack(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.
~MavlinkMissionManager()=default
static constexpr uint16_t MAX_COUNT[]
Maximum number of mission items for each type (fence & safe points use the first item for the stats) ...
unsigned _filesystem_errcount
File system error count.
dm_item_t _transfer_dataman_id
Dataman storage ID for current transmission.
int load_safepoint_stats()
load safe point stats from dataman
int32_t _transfer_current_seq
Current item ID for current transmission (-1 means not initialized)
int32_t _last_reached
Last reached waypoint in active mission (-1 means nothing reached)