void MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t seq) { dm_item_t dm_item = DM_KEY_WAYPOINTS_OFFBOARD(_dataman_id); struct mission_item_s mission_item; if (dm_read(dm_item, seq, &mission_item, sizeof(struct mission_item_s)) == sizeof(struct mission_item_s)) { _time_last_sent = hrt_absolute_time(); if (_int_mode) { mavlink_mission_item_int_t wp; format_mavlink_mission_item(&mission_item, reinterpret_cast<mavlink_mission_item_t *>(&wp)); wp.target_system = sysid; wp.target_component = compid; wp.seq = seq; wp.current = (_current_seq == seq) ? 1 : 0; mavlink_msg_mission_item_int_send_struct(_mavlink->get_channel(), &wp); if (_verbose) { PX4_INFO("WPM: Send MISSION_ITEM_INT seq %u to ID %u", wp.seq, wp.target_system); } } else { mavlink_mission_item_t wp; format_mavlink_mission_item(&mission_item, &wp); wp.target_system = sysid; wp.target_component = compid; wp.seq = seq; wp.current = (_current_seq == seq) ? 1 : 0; mavlink_msg_mission_item_send_struct(_mavlink->get_channel(), &wp); if (_verbose) { PX4_INFO("WPM: Send MISSION_ITEM seq %u to ID %u", wp.seq, wp.target_system); } } } else { send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); if (_filesystem_errcount++ < FILESYSTEM_ERRCOUNT_NOTIFY_LIMIT) { _mavlink->send_statustext_critical("Mission storage: Unable to read from microSD"); } if (_verbose) { warnx("WPM: Send MISSION_ITEM ERROR: could not read seq %u from dataman ID %i", seq, _dataman_id); } } }
void MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t seq) { dm_item_t dm_item = DM_KEY_WAYPOINTS_OFFBOARD(_dataman_id); struct mission_item_s mission_item; if (dm_read(dm_item, seq, &mission_item, sizeof(struct mission_item_s)) == sizeof(struct mission_item_s)) { _time_last_sent = hrt_absolute_time(); /* create mission_item_s from mavlink_mission_item_t */ mavlink_mission_item_t wp; format_mavlink_mission_item(&mission_item, &wp); wp.target_system = sysid; wp.target_component = compid; wp.seq = seq; wp.current = (_current_seq == seq) ? 1 : 0; _mavlink->send_message(MAVLINK_MSG_ID_MISSION_ITEM, &wp); if (_verbose) { warnx("WPM: Send MISSION_ITEM seq %u to ID %u", wp.seq, wp.target_system); } } else { send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); _mavlink->send_statustext_critical("Unable to read from micro SD"); if (_verbose) { warnx("WPM: Send MISSION_ITEM ERROR: could not read seq %u from dataman ID %i", seq, _dataman_id); } } }