Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

global: Change the IF statement to a SWITCH statement #23061

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
14 changes: 10 additions & 4 deletions src/modules/mavlink/mavlink_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -765,13 +765,14 @@ void Mavlink::send_finish()
int ret = -1;

// send message to UART
if (get_protocol() == Protocol::SERIAL) {
switch (get_protocol()) {
case Protocol::SERIAL:
ret = ::write(_uart_fd, _buf, _buf_fill);
}
break;

#if defined(MAVLINK_UDP)

else if (get_protocol() == Protocol::UDP) {
case Protocol::UDP:

# if defined(CONFIG_NET)

Expand Down Expand Up @@ -805,10 +806,15 @@ void Mavlink::send_finish()
}
}
}
}

break;

#endif // MAVLINK_UDP

default:
break;
}

if (ret == (int)_buf_fill) {
_tstatus.tx_message_count++;
count_txbytes(_buf_fill);
Expand Down
46 changes: 32 additions & 14 deletions src/modules/navigator/geofence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -406,17 +406,25 @@ bool Geofence::checkPointAgainstPolygonCircle(const PolygonInfo &polygon, double
{
bool checksPass = true;

if (polygon.fence_type == NAV_CMD_FENCE_CIRCLE_INCLUSION) {
switch (polygon.fence_type) {
case NAV_CMD_FENCE_CIRCLE_INCLUSION:
checksPass &= insideCircle(polygon, lat, lon, altitude);
break;

} else if (polygon.fence_type == NAV_CMD_FENCE_CIRCLE_EXCLUSION) {
case NAV_CMD_FENCE_CIRCLE_EXCLUSION:
checksPass &= !insideCircle(polygon, lat, lon, altitude);
break;

} else if (polygon.fence_type == NAV_CMD_FENCE_POLYGON_VERTEX_INCLUSION) {
case NAV_CMD_FENCE_POLYGON_VERTEX_INCLUSION:
checksPass &= insidePolygon(polygon, lat, lon, altitude);
break;

} else if (polygon.fence_type == NAV_CMD_FENCE_POLYGON_VERTEX_EXCLUSION) {
case NAV_CMD_FENCE_POLYGON_VERTEX_EXCLUSION:
checksPass &= !insidePolygon(polygon, lat, lon, altitude);
break;

default:
break;
}

return checksPass;
Expand Down Expand Up @@ -482,9 +490,14 @@ bool Geofence::insideCircle(const PolygonInfo &polygon, double lat, double lon,
return false;
}

if (circle_point.frame != NAV_FRAME_GLOBAL && circle_point.frame != NAV_FRAME_GLOBAL_INT
&& circle_point.frame != NAV_FRAME_GLOBAL_RELATIVE_ALT
&& circle_point.frame != NAV_FRAME_GLOBAL_RELATIVE_ALT_INT) {
switch (circle_point.nav_cmd) {
case NAV_FRAME_GLOBAL:
case NAV_FRAME_GLOBAL_INT:
case NAV_FRAME_GLOBAL_RELATIVE_ALT:
case NAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
break;

default:
// TODO: handle different frames
PX4_ERR("Frame type %i not supported", (int)circle_point.frame);
return false;
Expand Down Expand Up @@ -675,20 +688,25 @@ void Geofence::printStatus()
for (int i = 0; i < _num_polygons; ++i) {
total_num_vertices += _polygons[i].vertex_count;

if (_polygons[i].fence_type == NAV_CMD_FENCE_POLYGON_VERTEX_INCLUSION) {
switch (_polygons[i].fence_type) {
case NAV_CMD_FENCE_POLYGON_VERTEX_INCLUSION:
++num_inclusion_polygons;
}
break;

if (_polygons[i].fence_type == NAV_CMD_FENCE_POLYGON_VERTEX_EXCLUSION) {
case NAV_CMD_FENCE_POLYGON_VERTEX_EXCLUSION:
++num_exclusion_polygons;
}
break;

if (_polygons[i].fence_type == NAV_CMD_FENCE_CIRCLE_INCLUSION) {
case NAV_CMD_FENCE_CIRCLE_INCLUSION:
++num_inclusion_circles;
}
break;

if (_polygons[i].fence_type == NAV_CMD_FENCE_CIRCLE_EXCLUSION) {
case NAV_CMD_FENCE_CIRCLE_EXCLUSION:
++num_exclusion_circles;
break;

default:
break;
}
}

Expand Down