Skip to content

Commit

Permalink
AP_Radar: Corrections and fixes
Browse files Browse the repository at this point in the history
- Fix arrow directions if using BTFL fonts
- Fix Radar panel item group IDx conflict with prior parameter (which caused FC lockup on boot)
- Fix peers array indexing, avoiding 0x800 internal error if all 6 peers are visible
- Fix peer persistence on OSD after signal loss
  • Loading branch information
rmaia3d committed Apr 2, 2024
1 parent 0ce2244 commit b1fdf82
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 8 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_OSD/AP_OSD_Screen.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1039,6 +1039,7 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
// @Range: 0 15
AP_SUBGROUPINFO(rrpm, "RPM", 62, AP_OSD_Screen, AP_OSD_Setting),
#endif

// @Param: RADAR_EN
// @DisplayName: RADAR_EN
// @Description: Displays iNav Radar info for peer aircraft
Expand Down Expand Up @@ -1711,12 +1712,11 @@ void AP_OSD_Screen::draw_radar(uint8_t x, uint8_t y)
vertical_distance = 0.0f;
}
int32_t angle = wrap_360_cd(loc.get_bearing_to(peer_loc) - ahrs.yaw_sensor);
int32_t interval = 36000 / SYMBOL(SYM_ARROW_COUNT);
if (distance < 2.0f) {
//avoid fast rotating arrow at small distances
angle = 0;
}
char arrow = SYMBOL(SYM_ARROW_START) + ((angle + interval / 2) / interval) % SYMBOL(SYM_ARROW_COUNT);
char arrow = get_arrow_font_index(angle);
backend->write(x, y, false, "%c%c", id + 65, arrow);
draw_distance(x+2, y, distance);
draw_vdistance(x+1, y+1, vertical_distance);
Expand Down
12 changes: 7 additions & 5 deletions libraries/AP_Radar/AP_Radar.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ void AP_Radar::update(void)
}

// only healthy if the data is less than 3s old
_flags.healthy = (AP_HAL::millis() - _last_update_ms < RADAR_PEER_FRESH_TIME_MS);
_flags.healthy = ((AP_HAL::millis() - _last_update_ms) < RADAR_PEER_FRESH_TIME_MS);
}

void AP_Radar::handle_msg(const mavlink_message_t &msg)
Expand Down Expand Up @@ -107,16 +107,18 @@ radar_peer_t AP_Radar::get_peer(uint8_t id)
bool AP_Radar::get_peer_healthy(uint8_t id)
{
return _state.peers[id].last_update > (AP_HAL::millis() - 3000) &&
!_state.peers[id].location.is_zero();
!_state.peers[id].location.is_zero() && _state.peers[id].lq > 0;
}

uint8_t AP_Radar::get_next_healthy_peer(uint8_t current_id)
{
// Try all available slots
for (uint8_t i = 1; i < RADAR_MAX_PEERS; i++) {
uint8_t next_peer = (current_id + i) % RADAR_MAX_PEERS;
if (get_peer_healthy(next_peer)) {
return next_peer;
uint8_t next_id = current_id + i;
uint8_t next_peer = next_id >= RADAR_MAX_PEERS ? next_id - RADAR_MAX_PEERS : next_id;
if (get_peer_healthy(next_peer))
{
return next_peer;
}
}
return current_id;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Radar/AP_Radar_MSP.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ void AP_Radar_MSP::update(void)
void AP_Radar_MSP::handle_msp(const MSP::msp_radar_pos_message_t &pkt)
{
// record peer state
uint8_t id = pkt.radar_no;
uint8_t id = pkt.radar_no - 1U;
peers[id].radar_no = pkt.radar_no;
peers[id].state = pkt.state;
peers[id].location = Location(pkt.lat, pkt.lon, pkt.alt, Location::AltFrame::ABSOLUTE);
Expand Down

0 comments on commit b1fdf82

Please sign in to comment.