15 #include <unordered_map>
26 typedef std::unordered_map<uint32_t, const std::string>
cmode_map;
47 { 16,
"INITIALISING" },
79 { 20,
"GUIDED_NOGPS" }
98 { 16,
"INITIALISING" }
158 auto it = cmap.find(custom_mode);
159 if (it != cmap.end())
182 return type == UAS::MAV_TYPE::QUADROTOR ||
183 type == UAS::MAV_TYPE::HEXAROTOR ||
184 type == UAS::MAV_TYPE::OCTOROTOR ||
185 type == UAS::MAV_TYPE::TRICOPTER ||
186 type == UAS::MAV_TYPE::COAXIAL;
196 if (MAV_AUTOPILOT::ARDUPILOTMEGA == ap) {
199 else if (
type == MAV_TYPE::FIXED_WING)
201 else if (
type == MAV_TYPE::GROUND_ROVER)
203 else if (
type == MAV_TYPE::SURFACE_BOAT)
205 else if (
type == MAV_TYPE::SUBMARINE)
212 else if (MAV_AUTOPILOT::PX4 == ap)
226 for (
auto &mode : cmap) {
227 if (mode.second == cmode_str) {
236 cmode = std::stoi(cmode_str, 0, 0);
239 catch (std::invalid_argument &ex) {
244 std::ostringstream os;
245 for (
auto &mode : cmap)
246 os <<
" " << mode.second;
257 std::transform(cmode_str.begin(), cmode_str.end(), cmode_str.begin(), std::ref(toupper));
261 if (MAV_AUTOPILOT::ARDUPILOTMEGA == ap) {
264 else if (
type == MAV_TYPE::FIXED_WING)
266 else if (
type == MAV_TYPE::GROUND_ROVER)
268 else if (
type == MAV_TYPE::SURFACE_BOAT)
270 else if (
type == MAV_TYPE::SUBMARINE)
273 else if (MAV_AUTOPILOT::PX4 == ap)