Report some memory bugs

Dear all,

While I manually look into source code, I notice some memory bugs. Just in case, I would like to share the issues in here!

  1. null pointer dereference
    Path: libraries/AC_Avoidance/AP_OADijkstra.cpp, line 255, 345

bool AP_OADijkstra::create_inclusion_polygon_with_margin(float margin_cm, AP_OADijkstra_Error &err_id)
{
const AC_Fence *fence = AC_Fence::get_singleton();

// skip unnecessary retry to build inclusion polygon if previous fence points have not changed 
if (_inclusion_polygon_update_ms == fence->polyfence().get_inclusion_polygon_update_ms()) {
    return false;
}
// *[ERROR] 'fence' null pointer dereference*
_inclusion_polygon_update_ms = fence->polyfence().get_inclusion_polygon_update_ms();  

if (fence == nullptr) {
    err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_FENCE_DISABLED;
    return false;
}
  1. null pointer dereference
    Path: libraries/AC_Module/AP_Module.cpp, line 63
        // found a hook in this module, add it to the list
        struct hook_list *h = new hook_list;
        if (h == nullptr) {
            AP_HAL::panic("Failed to allocate hook for %s", hook_names[i]);
        }
        h->next = hooks[i]; // *[ERROR] 'h' null pointer dereference*
        h->symbol = s;	
        hooks[i] = h;
        found_hooks++;
    }
}
  1. Resource leak
    Path: libraries/Tools/UDP_Proxy/udpproxy.c, 60 line

res = socket(AF_INET, SOCK_DGRAM, 0);
if (res == -1) {
fprintf(stderr, “socket failed\n”); return -1;
return -1;
}

setsockopt(res,SOL_SOCKET,SO_REUSEADDR,(char *)&one,sizeof(one));

if (bind(res, (struct sockaddr *)&sock, sizeof(sock)) < 0) {
return(-1); // [ERROR] ‘res’ memory leak
}

  1. This is not a memory bug. But, the ‘if’ statement is always true branch.
const AP_GPS &gps = AP::gps();
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS)) {

    // Any failure messages from GPS backends
    if ((checks_to_perform & ARMING_CHECK_ALL) || 
        (checks_to_perform & ARMING_CHECK_GPS)) { // [ERROR] this inner 'if' statement is always true
        char failure_msg[50] = {};

It would be nice if there issues will be fixed! Thanks!

While I manually look into source code, I notice some memory bugs. Just in case, I would like to share the issues in here!

  1. null pointer dereference
    Path: libraries/AC_Avoidance/AP_OADijkstra.cpp, line 255, 345

    bool AP_OADijkstra::create_inclusion_polygon_with_margin(float margin_cm, AP_OADijkstra_Error &err_id)
    {
    const AC_Fence *fence = AC_Fence::get_singleton();

Technically we really ought to be checking.

We could burn bytes to catch these - but fence is a prereq for avoidance
and if fence is compiled the pointer is never nullptr.

I don’t feel a burning desire to make a PR for these cases unless the
nullptr deref can happen with our existing code.

  1. null pointer dereference
    Path: libraries/AC_Module/AP_Module.cpp, line 63

    // found a hook in this module, add it to the list
    struct hook_list *h = new hook_list;
    if (h == nullptr) {
        AP_HAL::panic("Failed to allocate hook for %s", hook_names[i]);
    }
    h->next = hooks[i]; // *[ERROR] 'h' null pointer dereference*
    

The nullptr check is right there :slight_smile:

My guess is that the analysis tool you’re using is not understanding the
“does not return” attribute we have on AP_HAL::panic()

  1. Resource leak
    Path: libraries/Tools/UDP_Proxy/udpproxy.c, 60 line

    res = socket(AF_INET, SOCK_DGRAM, 0);
    if (res == -1) {
    fprintf(stderr, “socket failed\n”); return -1;
    return -1;
    }

    setsockopt(res,SOL_SOCKET,SO_REUSEADDR,(char *)&one,sizeof(one));

    if (bind(res, (struct sockaddr *)&sock, sizeof(sock)) < 0) {
    return(-1); // [ERROR] ‘res’ memory leak
    }

Yeah, maybe, but we’re going to due soon. Should probably be fixed
anyway, but not by me today :slight_smile:

  1. This is not a memory bug. But, the ‘if’ statement is always true branch.

const AP_GPS &gps = AP::gps();
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_GPS)) {

// Any failure messages from GPS backends
if ((checks_to_perform & ARMING_CHECK_ALL) ||
    (checks_to_perform & ARMING_CHECK_GPS)) { // [ERROR] this inner 'if' statement is always true
    char failure_msg[50] = {};

Created a PR for that one.

Thanks for chasing this sort of thing up!

1 Like

@peterbarker
Thanks for your work!

@KimHyungSub,

Thanks for sharing and pointing this out. For the first one we merged a fix just last week. https://github.com/ArduPilot/ardupilot/pull/18277. This is not included in Copter/Rove-4.1 but hopefully it isn’t critical so it can wait for a point release or 4.2

I think PeterB’s answered most of the others. txs again

1 Like

@rmackay9
I have just checked the pull request!
Thanks for you guys work :slight_smile: