• Home
  • Features
  • Pricing
  • Docs
  • Announcements
  • Sign In

mavlink / MAVSDK / 11452150858

22 Oct 2024 02:32AM UTC coverage: 37.403% (+0.02%) from 37.381%
11452150858

push

github

web-flow
camera_server: prevent double ack+message (#2430)

It turns out we were sending the ack and message for storage information
as well as capture status twice, once directly in the request handler
callback, and once the MAVSDK user would call the respond function.

We should only call it in the respond function, not in the callback.

11105 of 29690 relevant lines covered (37.4%)

255.6 hits per line

Source File
Press 'n' to go to next uncovered line, 'b' for previous

0.0
/src/mavsdk/core/flight_mode.cpp
1

2
#include "autopilot.h"
3
#include "flight_mode.h"
4
#include "mavlink_include.h"
5
#include "ardupilot_custom_mode.h"
6
#include "px4_custom_mode.h"
7
#include "mavlink_command_sender.h"
8

9
namespace mavsdk {
10

11
FlightMode
12
to_flight_mode_from_custom_mode(Autopilot autopilot, MAV_TYPE mav_type, uint32_t custom_mode)
×
13
{
14
    if (autopilot == Autopilot::ArduPilot) {
×
15
        switch (mav_type) {
×
16
            case MAV_TYPE::MAV_TYPE_SURFACE_BOAT:
×
17
            case MAV_TYPE::MAV_TYPE_GROUND_ROVER:
18
                return to_flight_mode_from_ardupilot_rover_mode(custom_mode);
×
19
            case MAV_TYPE::MAV_TYPE_FIXED_WING:
×
20
                return to_flight_mode_from_ardupilot_plane_mode(custom_mode);
×
21
            default:
×
22
                return to_flight_mode_from_ardupilot_copter_mode(custom_mode);
×
23
        }
24
    } else {
25
        return to_flight_mode_from_px4_mode(custom_mode);
×
26
    }
27
}
28

29
FlightMode to_flight_mode_from_ardupilot_rover_mode(uint32_t custom_mode)
×
30
{
31
    switch (static_cast<ardupilot::RoverMode>(custom_mode)) {
×
32
        case ardupilot::RoverMode::Auto:
×
33
            return FlightMode::Mission;
×
34
        case ardupilot::RoverMode::Acro:
×
35
            return FlightMode::Acro;
×
36
        case ardupilot::RoverMode::Hold:
×
37
            return FlightMode::Hold;
×
38
        case ardupilot::RoverMode::RTL:
×
39
            return FlightMode::ReturnToLaunch;
×
40
        case ardupilot::RoverMode::Manual:
×
41
            return FlightMode::Manual;
×
42
        case ardupilot::RoverMode::Follow:
×
43
            return FlightMode::FollowMe;
×
44
        case ardupilot::RoverMode::Guided:
×
45
            return FlightMode::Offboard;
×
46
        default:
×
47
            return FlightMode::Unknown;
×
48
    }
49
}
50
FlightMode to_flight_mode_from_ardupilot_copter_mode(uint32_t custom_mode)
×
51
{
52
    switch (static_cast<ardupilot::CopterMode>(custom_mode)) {
×
53
        case ardupilot::CopterMode::Auto:
×
54
            return FlightMode::Mission;
×
55
        case ardupilot::CopterMode::Acro:
×
56
            return FlightMode::Acro;
×
57
        case ardupilot::CopterMode::AltHold:
×
58
            return FlightMode::Altctl;
×
59
        case ardupilot::CopterMode::PosHold:
×
60
            return FlightMode::Posctl;
×
61
        case ardupilot::CopterMode::FlowHold:
×
62
        case ardupilot::CopterMode::Loiter:
63
            return FlightMode::Hold;
×
64
        case ardupilot::CopterMode::Rtl:
×
65
        case ardupilot::CopterMode::AutoRtl:
66
            return FlightMode::ReturnToLaunch;
×
67
        case ardupilot::CopterMode::Land:
×
68
            return FlightMode::Land;
×
69
        case ardupilot::CopterMode::Follow:
×
70
            return FlightMode::FollowMe;
×
71
        case ardupilot::CopterMode::Guided:
×
72
            return FlightMode::Offboard;
×
73
        case ardupilot::CopterMode::Stabilize:
×
74
            return FlightMode::Stabilized;
×
75
        case ardupilot::CopterMode::Unknown:
×
76
            return FlightMode::Unknown;
×
77
        default:
×
78
            return FlightMode::Unknown;
×
79
    }
80
}
81
FlightMode to_flight_mode_from_ardupilot_plane_mode(uint32_t custom_mode)
×
82
{
83
    switch (static_cast<ardupilot::PlaneMode>(custom_mode)) {
×
84
        case ardupilot::PlaneMode::Manual:
×
85
            return FlightMode::Manual;
×
86
        case ardupilot::PlaneMode::Auto:
×
87
            return FlightMode::Mission;
×
88
        case ardupilot::PlaneMode::Acro:
×
89
            return FlightMode::Acro;
×
90
        case ardupilot::PlaneMode::Autotune:
×
91
            return FlightMode::Altctl;
×
92
        case ardupilot::PlaneMode::Fbwa:
×
93
            return FlightMode::FBWA;
×
94
        case ardupilot::PlaneMode::Guided:
×
95
            return FlightMode::Guided;
×
96
        case ardupilot::PlaneMode::Loiter:
×
97
            return FlightMode::Hold;
×
98
        case ardupilot::PlaneMode::Rtl:
×
99
            return FlightMode::ReturnToLaunch;
×
100
        case ardupilot::PlaneMode::Stabilize:
×
101
            return FlightMode::Stabilized;
×
102
        case ardupilot::PlaneMode::Unknown:
×
103
            return FlightMode::Unknown;
×
104
        default:
×
105
            return FlightMode::Unknown;
×
106
    }
107
}
108

109
FlightMode to_flight_mode_from_px4_mode(uint32_t custom_mode)
×
110
{
111
    px4::px4_custom_mode px4_custom_mode;
112
    px4_custom_mode.data = custom_mode;
×
113

114
    switch (px4_custom_mode.main_mode) {
×
115
        case px4::PX4_CUSTOM_MAIN_MODE_OFFBOARD:
×
116
            return FlightMode::Offboard;
×
117
        case px4::PX4_CUSTOM_MAIN_MODE_MANUAL:
×
118
            return FlightMode::Manual;
×
119
        case px4::PX4_CUSTOM_MAIN_MODE_POSCTL:
×
120
            return FlightMode::Posctl;
×
121
        case px4::PX4_CUSTOM_MAIN_MODE_ALTCTL:
×
122
            return FlightMode::Altctl;
×
123
        case px4::PX4_CUSTOM_MAIN_MODE_RATTITUDE:
×
124
            return FlightMode::Rattitude;
×
125
        case px4::PX4_CUSTOM_MAIN_MODE_ACRO:
×
126
            return FlightMode::Acro;
×
127
        case px4::PX4_CUSTOM_MAIN_MODE_STABILIZED:
×
128
            return FlightMode::Stabilized;
×
129
        case px4::PX4_CUSTOM_MAIN_MODE_AUTO:
×
130
            switch (px4_custom_mode.sub_mode) {
×
131
                case px4::PX4_CUSTOM_SUB_MODE_AUTO_READY:
×
132
                    return FlightMode::Ready;
×
133
                case px4::PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF:
×
134
                    return FlightMode::Takeoff;
×
135
                case px4::PX4_CUSTOM_SUB_MODE_AUTO_LOITER:
×
136
                    return FlightMode::Hold;
×
137
                case px4::PX4_CUSTOM_SUB_MODE_AUTO_MISSION:
×
138
                    return FlightMode::Mission;
×
139
                case px4::PX4_CUSTOM_SUB_MODE_AUTO_RTL:
×
140
                    return FlightMode::ReturnToLaunch;
×
141
                case px4::PX4_CUSTOM_SUB_MODE_AUTO_LAND:
×
142
                    return FlightMode::Land;
×
143
                case px4::PX4_CUSTOM_SUB_MODE_AUTO_FOLLOW_TARGET:
×
144
                    return FlightMode::FollowMe;
×
145
                default:
×
146
                    return FlightMode::Unknown;
×
147
            }
148
        default:
×
149
            return FlightMode::Unknown;
×
150
    }
151
}
152

153
} // namespace mavsdk
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2026 Coveralls, Inc