Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
/*
2
  compatibility header during transition to MAVLink 1.0
3
 */
4
 
5
#ifdef MAVLINK10
6
// in MAVLink 1.0 'waypoint' becomes 'mission'. We can remove these
7
// mappings once we are not trying to support both protocols
8
 
9
#define MAVLINK_MSG_ID_WAYPOINT_CURRENT MAVLINK_MSG_ID_MISSION_CURRENT
10
#define MAVLINK_MSG_ID_WAYPOINT_CURRENT_LEN MAVLINK_MSG_ID_MISSION_CURRENT_LEN
11
#define mavlink_msg_waypoint_current_send mavlink_msg_mission_current_send
12
#define mavlink_msg_waypoint_current_decode mavlink_msg_mission_current_decode
13
 
14
#define MAVLINK_MSG_ID_WAYPOINT_COUNT MAVLINK_MSG_ID_MISSION_COUNT
15
#define MAVLINK_MSG_ID_WAYPOINT_COUNT_LEN MAVLINK_MSG_ID_MISSION_COUNT_LEN
16
#define mavlink_msg_waypoint_count_send mavlink_msg_mission_count_send
17
#define mavlink_msg_waypoint_count_decode mavlink_msg_mission_count_decode
18
#define mavlink_waypoint_count_t mavlink_mission_count_t
19
 
20
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST MAVLINK_MSG_ID_MISSION_REQUEST
21
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LEN MAVLINK_MSG_ID_MISSION_REQUEST_LEN
22
#define mavlink_msg_waypoint_request_send mavlink_msg_mission_request_send
23
#define mavlink_msg_waypoint_request_decode mavlink_msg_mission_request_decode
24
#define mavlink_waypoint_request_t mavlink_mission_request_t
25
 
26
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST MAVLINK_MSG_ID_MISSION_REQUEST_LIST
27
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST_LEN MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN
28
#define mavlink_msg_waypoint_request_list_send mavlink_msg_mission_request_list_send
29
#define mavlink_msg_waypoint_request_list_decode mavlink_msg_mission_request_list_decode
30
#define mavlink_waypoint_request_list_t mavlink_mission_request_list_t
31
 
32
#define MAVLINK_MSG_ID_WAYPOINT MAVLINK_MSG_ID_MISSION_ITEM
33
#define MAVLINK_MSG_ID_WAYPOINT_LEN MAVLINK_MSG_ID_MISSION_ITEM_LEN
34
#define mavlink_msg_waypoint_send mavlink_msg_mission_item_send
35
#define mavlink_msg_waypoint_decode mavlink_msg_mission_item_decode
36
#define mavlink_waypoint_t mavlink_mission_item_t
37
 
38
#define MAVLINK_MSG_ID_WAYPOINT_ACK MAVLINK_MSG_ID_MISSION_ACK
39
#define MAVLINK_MSG_ID_WAYPOINT_ACK_LEN MAVLINK_MSG_ID_MISSION_ACK_LEN
40
#define mavlink_msg_waypoint_ack_send mavlink_msg_mission_ack_send
41
#define mavlink_msg_waypoint_ack_decode mavlink_msg_mission_ack_decode
42
#define mavlink_waypoint_ack_t mavlink_mission_ack_t
43
 
44
#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL MAVLINK_MSG_ID_MISSION_CLEAR_ALL
45
#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL_LEN MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN
46
#define mavlink_msg_waypoint_clear_all_send mavlink_msg_mission_clear_all_send
47
#define mavlink_msg_waypoint_clear_all_decode mavlink_msg_mission_clear_all_decode
48
#define mavlink_waypoint_clear_all_t mavlink_mission_clear_all_t
49
 
50
#define MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT MAVLINK_MSG_ID_MISSION_SET_CURRENT
51
#define MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT_LEN MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN
52
#define mavlink_msg_waypoint_set_current_send mavlink_msg_mission_set_current_send
53
#define mavlink_msg_waypoint_set_current_decode mavlink_msg_mission_set_current_decode
54
#define mavlink_waypoint_set_current_t mavlink_mission_set_current_t
55
 
56
#define MAV_CMD_DO_SET_ROI MAV_CMD_NAV_ROI
57
 
58
static uint8_t mav_var_type(enum ap_var_type t)
59
{
60
    if (t == AP_PARAM_INT8) {
61
        return MAV_VAR_INT8;
62
    }
63
    if (t == AP_PARAM_INT16) {
64
        return MAV_VAR_INT16;
65
    }
66
    if (t == AP_PARAM_INT32) {
67
        return MAV_VAR_INT32;
68
    }
69
    // treat any others as float
70
    return MAV_VAR_FLOAT;
71
}
72
 
73
#define MAV_FIXED_WING MAV_TYPE_FIXED_WING
74
 
75
#else // MAVLINK10
76
 
77
static uint8_t mav_var_type(enum ap_var_type t)
78
{
79
        return 0;
80
}
81
 
82
#define MAV_MISSION_ACCEPTED 0
83
#define MAV_MISSION_UNSUPPORTED       1
84
#define MAV_MISSION_UNSUPPORTED_FRAME 1
85
#define MAV_MISSION_ERROR             1
86
#define MAV_MISSION_INVALID_SEQUENCE  1
87
 
88
/*
89
  some functions have some extra params in MAVLink 1.0
90
 */
91
 
92
static void mavlink_msg_global_position_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon,
93
                                                 int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy,
94
                                                 int16_t vz, uint16_t hdg)
95
{
96
        mavlink_msg_global_position_int_send(
97
                chan,
98
                lat,
99
                lon,
100
                alt,
101
                vx, vy, vz);
102
}
103
 
104
static void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port,
105
                                                int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled,
106
                                                int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled,
107
                                                int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
108
{
109
    mavlink_msg_rc_channels_scaled_send(
110
        chan,
111
        chan1_scaled,
112
        chan2_scaled,
113
        chan3_scaled,
114
        chan4_scaled,
115
        chan5_scaled,
116
        chan6_scaled,
117
        chan7_scaled,
118
        chan8_scaled,
119
        rssi);
120
}
121
 
122
static void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port,
123
                                             uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw,
124
                                             uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw,
125
                                             uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
126
{
127
        mavlink_msg_rc_channels_raw_send(
128
                chan,
129
                chan1_raw,
130
                chan2_raw,
131
                chan3_raw,
132
                chan4_raw,
133
                chan5_raw,
134
                chan6_raw,
135
                chan7_raw,
136
                chan8_raw,
137
                rssi);
138
}
139
 
140
 
141
static void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint32_t time_usec, uint8_t port,
142
                                              uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw,
143
                                              uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw,
144
                                              uint16_t servo7_raw, uint16_t servo8_raw)
145
{
146
        mavlink_msg_servo_output_raw_send(
147
                chan,
148
                servo1_raw,
149
                servo2_raw,
150
                servo3_raw,
151
                servo4_raw,
152
                servo5_raw,
153
                servo6_raw,
154
                servo7_raw,
155
                servo8_raw);
156
}
157
 
158
static void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const char *text)
159
{
160
        mavlink_msg_statustext_send(chan, severity, (const int8_t*) text);
161
}
162
 
163
static void mavlink_msg_param_value_send(mavlink_channel_t chan, const char *param_id,
164
                                         float param_value, uint8_t param_type,
165
                                         uint16_t param_count, uint16_t param_index)
166
{
167
        mavlink_msg_param_value_send(
168
                chan,
169
                (int8_t *)param_id,
170
                param_value,
171
                param_count,
172
                param_index);
173
}
174
#endif // MAVLINK10