32 #pragma GCC diagnostic push
33 #pragma GCC diagnostic ignored "-Wswitch-default"
34 #include "mavlink/paparazzi/mavlink.h"
35 #pragma GCC diagnostic pop
38 #include "generated/flight_plan.h"
44 MAVLINK_DEBUG(
"Sent BLOCK_COUNT message: count %i\n", NB_BLOCK);
50 static const char *blocks[] = FP_BLOCKS;
52 strncpy(block_name, blocks[seq], 49);
58 MAVLINK_DEBUG(
"Sent BLOCK_ITEM message: seq %i, name %s\n", seq, block_name);
68 case MAVLINK_MSG_ID_SCRIPT_REQUEST_LIST: {
70 mavlink_script_request_list_t block_request_list_msg;
71 mavlink_msg_script_request_list_decode(msg, &block_request_list_msg);
72 if (block_request_list_msg.target_system ==
mavlink_system.sysid) {
96 case MAVLINK_MSG_ID_SCRIPT_REQUEST: {
98 mavlink_script_request_t block_request_msg;
99 mavlink_msg_script_request_decode(msg, &block_request_msg);
128 case MAVLINK_MSG_ID_SCRIPT_ITEM: {
130 mavlink_script_item_t block_item_msg;
131 mavlink_msg_script_item_decode(msg, &block_item_msg);
Basic MAVLink datalink implementation.
void mavlink_send_block(uint16_t seq)
Common functions used within the mission library, blocks and waypoints cannot be send simultaneously ...
mavlink_system_t mavlink_system
#define MAVLINK_DEBUG(...)
static void mavlink_send_block_count(void)
#define MAVLinkSendMessage()
void mavlink_block_message_handler(const mavlink_message_t *msg)
void mavlink_mission_cancel_timer(void)
void mavlink_mission_set_timer(void)
Common flight_plan functions shared between fixedwing and rotorcraft.
enum MAVLINK_MISSION_MGR_STATES state
mavlink_mission_mgr mission_mgr
PPRZ specific mission block implementation.
void nav_goto_block(uint8_t b)
uint8_t msg[10]
Buffer used for general comunication over SPI (out buffer)