forked from Archive/PX4-Autopilot
Merge remote-tracking branch 'upstream/master' into attitude_filter_improvement
This commit is contained in:
commit
6fe5291147
|
@ -23,7 +23,8 @@ ROMFS_FSSPEC := $(SRCROOT)/scripts/rcS~init.d/rcS \
|
|||
$(SRCROOT)/scripts/rc.PX4IOAR~init.d/rc.PX4IOAR \
|
||||
$(SRCROOT)/scripts/rc.FMU_quad_x~init.d/rc.FMU_quad_x \
|
||||
$(SRCROOT)/mixers/FMU_pass.mix~mixers/FMU_pass.mix \
|
||||
$(SRCROOT)/mixers/FMU_delta.mix~mixers/FMU_delta.mix \
|
||||
$(SRCROOT)/mixers/FMU_Q.mix~mixers/FMU_Q.mix \
|
||||
$(SRCROOT)/mixers/FMU_X5.mix~mixers/FMU_X5.mix \
|
||||
$(SRCROOT)/mixers/FMU_AERT.mix~mixers/FMU_AERT.mix \
|
||||
$(SRCROOT)/mixers/FMU_AET.mix~mixers/FMU_AET.mix \
|
||||
$(SRCROOT)/mixers/FMU_RET.mix~mixers/FMU_ERT.mix \
|
||||
|
|
|
@ -0,0 +1,52 @@
|
|||
Delta-wing mixer for PX4FMU
|
||||
===========================
|
||||
|
||||
Designed for Bormatec Camflyer Q
|
||||
|
||||
This file defines mixers suitable for controlling a delta wing aircraft using
|
||||
PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU
|
||||
servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is
|
||||
assumed to be unused.
|
||||
|
||||
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
|
||||
(roll), 1 (pitch) and 3 (thrust).
|
||||
|
||||
See the README for more information on the scaler format.
|
||||
|
||||
Elevon mixers
|
||||
-------------
|
||||
Three scalers total (output, roll, pitch).
|
||||
|
||||
On the assumption that the two elevon servos are physically reversed, the pitch
|
||||
input is inverted between the two servos.
|
||||
|
||||
The scaling factor for roll inputs is adjusted to implement differential travel
|
||||
for the elevons.
|
||||
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 -5000 -8000 0 -10000 10000
|
||||
S: 0 1 -8000 -8000 0 -10000 10000
|
||||
|
||||
M: 2
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 -8000 -5000 0 -10000 10000
|
||||
S: 0 1 8000 8000 0 -10000 10000
|
||||
|
||||
Output 2
|
||||
--------
|
||||
This mixer is empty.
|
||||
|
||||
Z:
|
||||
|
||||
Motor speed mixer
|
||||
-----------------
|
||||
Two scalers total (output, thrust).
|
||||
|
||||
This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
|
||||
range. Inputs below zero are treated as zero.
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 3 0 20000 -10000 -10000 10000
|
||||
|
|
@ -126,7 +126,7 @@ static const int LED_NOBLINK = 0;
|
|||
class BlinkM : public device::I2C
|
||||
{
|
||||
public:
|
||||
BlinkM(int bus);
|
||||
BlinkM(int bus, int blinkm);
|
||||
~BlinkM();
|
||||
|
||||
|
||||
|
@ -245,8 +245,8 @@ const char *BlinkM::script_names[] = {
|
|||
|
||||
extern "C" __EXPORT int blinkm_main(int argc, char *argv[]);
|
||||
|
||||
BlinkM::BlinkM(int bus) :
|
||||
I2C("blinkm", BLINKM_DEVICE_PATH, bus, 0x09, 100000),
|
||||
BlinkM::BlinkM(int bus, int blinkm) :
|
||||
I2C("blinkm", BLINKM_DEVICE_PATH, bus, blinkm, 100000),
|
||||
led_color_1(LED_OFF),
|
||||
led_color_2(LED_OFF),
|
||||
led_color_3(LED_OFF),
|
||||
|
@ -830,14 +830,42 @@ BlinkM::get_firmware_version(uint8_t version[2])
|
|||
return transfer(&msg, sizeof(msg), version, sizeof(version));
|
||||
}
|
||||
|
||||
void blinkm_usage() {
|
||||
fprintf(stderr, "missing command: try 'start', 'systemstate', 'ledoff', 'list' or a script name {options}\n");
|
||||
fprintf(stderr, "options:\n");
|
||||
fprintf(stderr, "\t-b --bus i2cbus (3)\n");
|
||||
fprintf(stderr, "\t-a --blinkmaddr blinkmaddr (9)\n");
|
||||
}
|
||||
|
||||
int
|
||||
blinkm_main(int argc, char *argv[])
|
||||
{
|
||||
|
||||
int i2cdevice = 3;
|
||||
int blinkmadr = 9;
|
||||
|
||||
int x;
|
||||
|
||||
for (x = 1; x < argc; x++) {
|
||||
if (strcmp(argv[x], "-b") == 0 || strcmp(argv[x], "--bus") == 0) {
|
||||
if (argc > x + 1) {
|
||||
i2cdevice = atoi(argv[x + 1]);
|
||||
}
|
||||
}
|
||||
|
||||
if (strcmp(argv[x], "-a") == 0 || strcmp(argv[x], "--blinkmaddr") == 0) {
|
||||
if (argc > x + 1) {
|
||||
blinkmadr = atoi(argv[x + 1]);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
if (g_blinkm != nullptr)
|
||||
errx(1, "already started");
|
||||
|
||||
g_blinkm = new BlinkM(3);
|
||||
g_blinkm = new BlinkM(i2cdevice, blinkmadr);
|
||||
|
||||
if (g_blinkm == nullptr)
|
||||
errx(1, "new failed");
|
||||
|
@ -852,8 +880,11 @@ blinkm_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
|
||||
if (g_blinkm == nullptr)
|
||||
errx(1, "not started");
|
||||
if (g_blinkm == nullptr) {
|
||||
fprintf(stderr, "not started\n");
|
||||
blinkm_usage();
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "systemstate")) {
|
||||
g_blinkm->setMode(1);
|
||||
|
@ -882,5 +913,6 @@ blinkm_main(int argc, char *argv[])
|
|||
if (ioctl(fd, BLINKM_PLAY_SCRIPT_NAMED, (unsigned long)argv[1]) == OK)
|
||||
exit(0);
|
||||
|
||||
errx(1, "missing command, try 'start', 'systemstate', 'ledoff', 'list' or a script name.");
|
||||
blinkm_usage();
|
||||
exit(0);
|
||||
}
|
||||
|
|
|
@ -48,6 +48,7 @@
|
|||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
#include <sys/stat.h>
|
||||
|
||||
#include "uploader.h"
|
||||
|
||||
|
@ -109,6 +110,8 @@ int
|
|||
PX4IO_Uploader::upload(const char *filenames[])
|
||||
{
|
||||
int ret;
|
||||
const char *filename = NULL;
|
||||
size_t fw_size;
|
||||
|
||||
_io_fd = open("/dev/ttyS2", O_RDWR);
|
||||
|
||||
|
@ -135,9 +138,22 @@ PX4IO_Uploader::upload(const char *filenames[])
|
|||
}
|
||||
|
||||
log("using firmware from %s", filenames[i]);
|
||||
filename = filenames[i];
|
||||
break;
|
||||
}
|
||||
|
||||
if (filename == NULL) {
|
||||
log("no firmware found");
|
||||
return -ENOENT;
|
||||
}
|
||||
|
||||
struct stat st;
|
||||
if (stat(filename, &st) != 0) {
|
||||
log("Failed to stat %s - %d\n", filename, (int)errno);
|
||||
return -errno;
|
||||
}
|
||||
fw_size = st.st_size;
|
||||
|
||||
if (_fw_fd == -1)
|
||||
return -ENOENT;
|
||||
|
||||
|
@ -172,7 +188,7 @@ PX4IO_Uploader::upload(const char *filenames[])
|
|||
continue;
|
||||
}
|
||||
|
||||
ret = program();
|
||||
ret = program(fw_size);
|
||||
|
||||
if (ret != OK) {
|
||||
log("program failed");
|
||||
|
@ -180,9 +196,9 @@ PX4IO_Uploader::upload(const char *filenames[])
|
|||
}
|
||||
|
||||
if (bl_rev <= 2)
|
||||
ret = verify_rev2();
|
||||
ret = verify_rev2(fw_size);
|
||||
else if(bl_rev == 3) {
|
||||
ret = verify_rev3();
|
||||
ret = verify_rev3(fw_size);
|
||||
}
|
||||
|
||||
if (ret != OK) {
|
||||
|
@ -219,7 +235,7 @@ PX4IO_Uploader::recv(uint8_t &c, unsigned timeout)
|
|||
int ret = ::poll(&fds[0], 1, timeout);
|
||||
|
||||
if (ret < 1) {
|
||||
//log("poll timeout %d", ret);
|
||||
log("poll timeout %d", ret);
|
||||
return -ETIMEDOUT;
|
||||
}
|
||||
|
||||
|
@ -232,7 +248,7 @@ int
|
|||
PX4IO_Uploader::recv(uint8_t *p, unsigned count)
|
||||
{
|
||||
while (count--) {
|
||||
int ret = recv(*p++);
|
||||
int ret = recv(*p++, 5000);
|
||||
|
||||
if (ret != OK)
|
||||
return ret;
|
||||
|
@ -248,7 +264,7 @@ PX4IO_Uploader::drain()
|
|||
int ret;
|
||||
|
||||
do {
|
||||
ret = recv(c, 250);
|
||||
ret = recv(c, 1000);
|
||||
|
||||
if (ret == OK) {
|
||||
//log("discard 0x%02x", c);
|
||||
|
@ -343,24 +359,55 @@ PX4IO_Uploader::erase()
|
|||
return get_sync(10000); /* allow 10s timeout */
|
||||
}
|
||||
|
||||
|
||||
static int read_with_retry(int fd, void *buf, size_t n)
|
||||
{
|
||||
int ret;
|
||||
uint8_t retries = 0;
|
||||
do {
|
||||
ret = read(fd, buf, n);
|
||||
} while (ret == -1 && retries++ < 100);
|
||||
if (retries != 0) {
|
||||
printf("read of %u bytes needed %u retries\n",
|
||||
(unsigned)n,
|
||||
(unsigned)retries);
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
PX4IO_Uploader::program()
|
||||
PX4IO_Uploader::program(size_t fw_size)
|
||||
{
|
||||
uint8_t file_buf[PROG_MULTI_MAX];
|
||||
ssize_t count;
|
||||
int ret;
|
||||
size_t sent = 0;
|
||||
|
||||
log("program...");
|
||||
lseek(_fw_fd, 0, SEEK_SET);
|
||||
log("programming %u bytes...", (unsigned)fw_size);
|
||||
|
||||
while (true) {
|
||||
ret = lseek(_fw_fd, 0, SEEK_SET);
|
||||
|
||||
while (sent < fw_size) {
|
||||
/* get more bytes to program */
|
||||
//log(" %d", (int)lseek(_fw_fd, 0, SEEK_CUR));
|
||||
count = read(_fw_fd, file_buf, sizeof(file_buf));
|
||||
size_t n = fw_size - sent;
|
||||
if (n > sizeof(file_buf)) {
|
||||
n = sizeof(file_buf);
|
||||
}
|
||||
count = read_with_retry(_fw_fd, file_buf, n);
|
||||
|
||||
if (count != (ssize_t)n) {
|
||||
log("firmware read of %u bytes at %u failed -> %d errno %d",
|
||||
(unsigned)n,
|
||||
(unsigned)sent,
|
||||
(int)count,
|
||||
(int)errno);
|
||||
}
|
||||
|
||||
if (count == 0)
|
||||
return OK;
|
||||
|
||||
sent += count;
|
||||
|
||||
if (count < 0)
|
||||
return -errno;
|
||||
|
||||
|
@ -376,14 +423,16 @@ PX4IO_Uploader::program()
|
|||
if (ret != OK)
|
||||
return ret;
|
||||
}
|
||||
return OK;
|
||||
}
|
||||
|
||||
int
|
||||
PX4IO_Uploader::verify_rev2()
|
||||
PX4IO_Uploader::verify_rev2(size_t fw_size)
|
||||
{
|
||||
uint8_t file_buf[PROG_MULTI_MAX];
|
||||
uint8_t file_buf[4];
|
||||
ssize_t count;
|
||||
int ret;
|
||||
size_t sent = 0;
|
||||
|
||||
log("verify...");
|
||||
lseek(_fw_fd, 0, SEEK_SET);
|
||||
|
@ -395,14 +444,27 @@ PX4IO_Uploader::verify_rev2()
|
|||
if (ret != OK)
|
||||
return ret;
|
||||
|
||||
while (true) {
|
||||
while (sent < fw_size) {
|
||||
/* get more bytes to verify */
|
||||
int base = (int)lseek(_fw_fd, 0, SEEK_CUR);
|
||||
count = read(_fw_fd, file_buf, sizeof(file_buf));
|
||||
size_t n = fw_size - sent;
|
||||
if (n > sizeof(file_buf)) {
|
||||
n = sizeof(file_buf);
|
||||
}
|
||||
count = read_with_retry(_fw_fd, file_buf, n);
|
||||
|
||||
if (count != (ssize_t)n) {
|
||||
log("firmware read of %u bytes at %u failed -> %d errno %d",
|
||||
(unsigned)n,
|
||||
(unsigned)sent,
|
||||
(int)count,
|
||||
(int)errno);
|
||||
}
|
||||
|
||||
if (count == 0)
|
||||
break;
|
||||
|
||||
sent += count;
|
||||
|
||||
if (count < 0)
|
||||
return -errno;
|
||||
|
||||
|
@ -415,15 +477,15 @@ PX4IO_Uploader::verify_rev2()
|
|||
for (ssize_t i = 0; i < count; i++) {
|
||||
uint8_t c;
|
||||
|
||||
ret = recv(c);
|
||||
ret = recv(c, 5000);
|
||||
|
||||
if (ret != OK) {
|
||||
log("%d: got %d waiting for bytes", base + i, ret);
|
||||
log("%d: got %d waiting for bytes", sent + i, ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
if (c != file_buf[i]) {
|
||||
log("%d: got 0x%02x expected 0x%02x", base + i, c, file_buf[i]);
|
||||
log("%d: got 0x%02x expected 0x%02x", sent + i, c, file_buf[i]);
|
||||
return -EINVAL;
|
||||
}
|
||||
}
|
||||
|
@ -440,21 +502,21 @@ PX4IO_Uploader::verify_rev2()
|
|||
}
|
||||
|
||||
int
|
||||
PX4IO_Uploader::verify_rev3()
|
||||
PX4IO_Uploader::verify_rev3(size_t fw_size_local)
|
||||
{
|
||||
int ret;
|
||||
uint8_t file_buf[4];
|
||||
ssize_t count;
|
||||
uint32_t sum = 0;
|
||||
uint32_t bytes_read = 0;
|
||||
uint32_t fw_size = 0;
|
||||
uint32_t crc = 0;
|
||||
uint32_t fw_size_remote;
|
||||
uint8_t fill_blank = 0xff;
|
||||
|
||||
log("verify...");
|
||||
lseek(_fw_fd, 0, SEEK_SET);
|
||||
|
||||
ret = get_info(INFO_FLASH_SIZE, fw_size);
|
||||
ret = get_info(INFO_FLASH_SIZE, fw_size_remote);
|
||||
send(PROTO_EOC);
|
||||
|
||||
if (ret != OK) {
|
||||
|
@ -463,9 +525,20 @@ PX4IO_Uploader::verify_rev3()
|
|||
}
|
||||
|
||||
/* read through the firmware file again and calculate the checksum*/
|
||||
while (true) {
|
||||
lseek(_fw_fd, 0, SEEK_CUR);
|
||||
count = read(_fw_fd, file_buf, sizeof(file_buf));
|
||||
while (bytes_read < fw_size_local) {
|
||||
size_t n = fw_size_local - bytes_read;
|
||||
if (n > sizeof(file_buf)) {
|
||||
n = sizeof(file_buf);
|
||||
}
|
||||
count = read_with_retry(_fw_fd, file_buf, n);
|
||||
|
||||
if (count != (ssize_t)n) {
|
||||
log("firmware read of %u bytes at %u failed -> %d errno %d",
|
||||
(unsigned)n,
|
||||
(unsigned)bytes_read,
|
||||
(int)count,
|
||||
(int)errno);
|
||||
}
|
||||
|
||||
/* set the rest to ff */
|
||||
if (count == 0) {
|
||||
|
@ -482,7 +555,7 @@ PX4IO_Uploader::verify_rev3()
|
|||
}
|
||||
|
||||
/* fill the rest with 0xff */
|
||||
while (bytes_read < fw_size) {
|
||||
while (bytes_read < fw_size_remote) {
|
||||
sum = crc32(&fill_blank, sizeof(fill_blank), sum);
|
||||
bytes_read += sizeof(fill_blank);
|
||||
}
|
||||
|
@ -516,36 +589,6 @@ PX4IO_Uploader::reboot()
|
|||
return OK;
|
||||
}
|
||||
|
||||
int
|
||||
PX4IO_Uploader::compare(bool &identical)
|
||||
{
|
||||
uint32_t file_vectors[15];
|
||||
uint32_t fw_vectors[15];
|
||||
int ret;
|
||||
|
||||
lseek(_fw_fd, 0, SEEK_SET);
|
||||
ret = read(_fw_fd, &file_vectors[0], sizeof(file_vectors));
|
||||
|
||||
send(PROTO_CHIP_VERIFY);
|
||||
send(PROTO_EOC);
|
||||
ret = get_sync();
|
||||
|
||||
if (ret != OK)
|
||||
return ret;
|
||||
|
||||
send(PROTO_READ_MULTI);
|
||||
send(sizeof(fw_vectors));
|
||||
send(PROTO_EOC);
|
||||
ret = recv((uint8_t *)&fw_vectors[0], sizeof(fw_vectors));
|
||||
|
||||
if (ret != OK)
|
||||
return ret;
|
||||
|
||||
identical = (memcmp(&file_vectors[0], &fw_vectors[0], sizeof(file_vectors))) ? true : false;
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
void
|
||||
PX4IO_Uploader::log(const char *fmt, ...)
|
||||
{
|
||||
|
@ -557,4 +600,4 @@ PX4IO_Uploader::log(const char *fmt, ...)
|
|||
va_end(ap);
|
||||
printf("\n");
|
||||
fflush(stdout);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -85,7 +85,7 @@ private:
|
|||
|
||||
void log(const char *fmt, ...);
|
||||
|
||||
int recv(uint8_t &c, unsigned timeout = 1000);
|
||||
int recv(uint8_t &c, unsigned timeout);
|
||||
int recv(uint8_t *p, unsigned count);
|
||||
void drain();
|
||||
int send(uint8_t c);
|
||||
|
@ -94,11 +94,10 @@ private:
|
|||
int sync();
|
||||
int get_info(int param, uint32_t &val);
|
||||
int erase();
|
||||
int program();
|
||||
int verify_rev2();
|
||||
int verify_rev3();
|
||||
int program(size_t fw_size);
|
||||
int verify_rev2(size_t fw_size);
|
||||
int verify_rev3(size_t fw_size);
|
||||
int reboot();
|
||||
int compare(bool &identical);
|
||||
};
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
|
|
@ -51,6 +51,7 @@
|
|||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <termios.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <unistd.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
|
|
|
@ -586,12 +586,12 @@ receive_thread(void *arg)
|
|||
struct pollfd fds[] = { { .fd = uart_fd, .events = POLLIN } };
|
||||
|
||||
if (poll(fds, 1, timeout) > 0) {
|
||||
/* non-blocking read */
|
||||
size_t nread = read(uart_fd, buf, sizeof(buf));
|
||||
ASSERT(nread > 0)
|
||||
/* non-blocking read. read may return negative values */
|
||||
ssize_t nread = read(uart_fd, buf, sizeof(buf));
|
||||
|
||||
for (size_t i = 0; i < nread; i++) {
|
||||
if (mavlink_parse_char(chan, buf[i], &msg, &status)) { //parse the char
|
||||
/* if read failed, this loop won't execute */
|
||||
for (ssize_t i = 0; i < nread; i++) {
|
||||
if (mavlink_parse_char(chan, buf[i], &msg, &status)) {
|
||||
/* handle generic messages and commands */
|
||||
handle_message(&msg);
|
||||
|
||||
|
|
|
@ -0,0 +1,40 @@
|
|||
#
|
||||
# For a description of the syntax of this configuration file,
|
||||
# see misc/tools/kconfig-language.txt.
|
||||
#
|
||||
|
||||
config ELF_ALIGN_LOG2
|
||||
int "Log2 Section Alignment"
|
||||
default 2
|
||||
---help---
|
||||
Align all sections to this Log2 value: 0->1, 1->2, 2->4, etc.
|
||||
|
||||
config ELF_STACKSIZE
|
||||
int "ELF Stack Size"
|
||||
default 2048
|
||||
---help---
|
||||
This is the default stack size that will will be used when starting ELF binaries.
|
||||
|
||||
config ELF_BUFFERSIZE
|
||||
int "ELF I/O Buffer Size"
|
||||
default 128
|
||||
---help---
|
||||
This is an I/O buffer that is used to access the ELF file. Variable length items
|
||||
will need to be read (such as symbol names). This is really just this initial
|
||||
size of the buffer; it will be reallocated as necessary to hold large symbol
|
||||
names). Default: 128
|
||||
|
||||
config ELF_BUFFERINCR
|
||||
int "ELF I/O Buffer Realloc Increment"
|
||||
default 32
|
||||
---help---
|
||||
This is an I/O buffer that is used to access the ELF file. Variable length items
|
||||
will need to be read (such as symbol names). This value specifies the size
|
||||
increment to use each time the buffer is reallocated. Default: 32
|
||||
|
||||
config ELF_DUMPBUFFER
|
||||
bool "Dump ELF buffers"
|
||||
default n
|
||||
depends on DEBUG && DEBUG_VERBOSE
|
||||
---help---
|
||||
Dump various ELF buffers for debug purposes
|
|
@ -0,0 +1,129 @@
|
|||
/****************************************************************************
|
||||
* binfmt/libelf/gnu-elf.ld
|
||||
*
|
||||
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
SECTIONS
|
||||
{
|
||||
.text 0x00000000 :
|
||||
{
|
||||
_stext = . ;
|
||||
*(.text)
|
||||
*(.text.*)
|
||||
*(.gnu.warning)
|
||||
*(.stub)
|
||||
*(.glue_7)
|
||||
*(.glue_7t)
|
||||
*(.jcr)
|
||||
|
||||
/* C++ support: The .init and .fini sections contain specific logic
|
||||
* to manage static constructors and destructors.
|
||||
*/
|
||||
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.init) /* Old ABI */
|
||||
*(.fini) /* Old ABI */
|
||||
_etext = . ;
|
||||
}
|
||||
|
||||
.rodata :
|
||||
{
|
||||
_srodata = . ;
|
||||
*(.rodata)
|
||||
*(.rodata1)
|
||||
*(.rodata.*)
|
||||
*(.gnu.linkonce.r*)
|
||||
_erodata = . ;
|
||||
}
|
||||
|
||||
.data :
|
||||
{
|
||||
_sdata = . ;
|
||||
*(.data)
|
||||
*(.data1)
|
||||
*(.data.*)
|
||||
*(.gnu.linkonce.d*)
|
||||
_edata = . ;
|
||||
}
|
||||
|
||||
/* C++ support. For each global and static local C++ object,
|
||||
* GCC creates a small subroutine to construct the object. Pointers
|
||||
* to these routines (not the routines themselves) are stored as
|
||||
* simple, linear arrays in the .ctors section of the object file.
|
||||
* Similarly, pointers to global/static destructor routines are
|
||||
* stored in .dtors.
|
||||
*/
|
||||
|
||||
.ctors :
|
||||
{
|
||||
_sctors = . ;
|
||||
*(.ctors) /* Old ABI: Unallocated */
|
||||
*(.init_array) /* New ABI: Allocated */
|
||||
_edtors = . ;
|
||||
}
|
||||
|
||||
.dtors :
|
||||
{
|
||||
_sdtors = . ;
|
||||
*(.dtors) /* Old ABI: Unallocated */
|
||||
*(.fini_array) /* New ABI: Allocated */
|
||||
_edtors = . ;
|
||||
}
|
||||
|
||||
.bss :
|
||||
{
|
||||
_sbss = . ;
|
||||
*(.bss)
|
||||
*(.bss.*)
|
||||
*(.sbss)
|
||||
*(.sbss.*)
|
||||
*(.gnu.linkonce.b*)
|
||||
*(COMMON)
|
||||
_ebss = . ;
|
||||
}
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
.stab.excl 0 : { *(.stab.excl) }
|
||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||
.stab.index 0 : { *(.stab.index) }
|
||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||
.comment 0 : { *(.comment) }
|
||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||
.debug_info 0 : { *(.debug_info) }
|
||||
.debug_line 0 : { *(.debug_line) }
|
||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||
.debug_aranges 0 : { *(.debug_aranges) }
|
||||
}
|
|
@ -0,0 +1,215 @@
|
|||
/****************************************************************************
|
||||
* binfmt/libelf/libelf_ctors.c
|
||||
*
|
||||
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <string.h>
|
||||
#include <errno.h>
|
||||
#include <assert.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/binfmt/elf.h>
|
||||
|
||||
#include "libelf.h"
|
||||
|
||||
#ifdef CONFIG_BINFMT_CONSTRUCTORS
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Constant Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: elf_loadctors
|
||||
*
|
||||
* Description:
|
||||
* Load pointers to static constructors into an in-memory array.
|
||||
*
|
||||
* Input Parameters:
|
||||
* loadinfo - Load state information
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 (OK) is returned on success and a negated errno is returned on
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int elf_loadctors(FAR struct elf_loadinfo_s *loadinfo)
|
||||
{
|
||||
FAR Elf32_Shdr *shdr;
|
||||
size_t ctorsize;
|
||||
int ctoridx;
|
||||
int ret;
|
||||
int i;
|
||||
|
||||
DEBUGASSERT(loadinfo->ctors == NULL);
|
||||
|
||||
/* Allocate an I/O buffer if necessary. This buffer is used by
|
||||
* elf_sectname() to accumulate the variable length symbol name.
|
||||
*/
|
||||
|
||||
ret = elf_allocbuffer(loadinfo);
|
||||
if (ret < 0)
|
||||
{
|
||||
bdbg("elf_allocbuffer failed: %d\n", ret);
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
/* Find the index to the section named ".ctors." NOTE: On old ABI system,
|
||||
* .ctors is the name of the section containing the list of constructors;
|
||||
* On newer systems, the similar section is called .init_array. It is
|
||||
* expected that the linker script will force the section name to be ".ctors"
|
||||
* in either case.
|
||||
*/
|
||||
|
||||
ctoridx = elf_findsection(loadinfo, ".ctors");
|
||||
if (ctoridx < 0)
|
||||
{
|
||||
/* This may not be a failure. -ENOENT indicates that the file has no
|
||||
* static constructor section.
|
||||
*/
|
||||
|
||||
bvdbg("elf_findsection .ctors section failed: %d\n", ctoridx);
|
||||
return ret == -ENOENT ? OK : ret;
|
||||
}
|
||||
|
||||
/* Now we can get a pointer to the .ctor section in the section header
|
||||
* table.
|
||||
*/
|
||||
|
||||
shdr = &loadinfo->shdr[ctoridx];
|
||||
|
||||
/* Get the size of the .ctor section and the number of constructors that
|
||||
* will need to be called.
|
||||
*/
|
||||
|
||||
ctorsize = shdr->sh_size;
|
||||
loadinfo->nctors = ctorsize / sizeof(binfmt_ctor_t);
|
||||
|
||||
bvdbg("ctoridx=%d ctorsize=%d sizeof(binfmt_ctor_t)=%d nctors=%d\n",
|
||||
ctoridx, ctorsize, sizeof(binfmt_ctor_t), loadinfo->nctors);
|
||||
|
||||
/* Check if there are any constructors. It is not an error if there
|
||||
* are none.
|
||||
*/
|
||||
|
||||
if (loadinfo->nctors > 0)
|
||||
{
|
||||
/* Check an assumption that we made above */
|
||||
|
||||
DEBUGASSERT(shdr->sh_size == loadinfo->nctors * sizeof(binfmt_ctor_t));
|
||||
|
||||
/* In the old ABI, the .ctors section is not allocated. In that case,
|
||||
* we need to allocate memory to hold the .ctors and then copy the
|
||||
* from the file into the allocated memory.
|
||||
*
|
||||
* SHF_ALLOC indicates that the section requires memory during
|
||||
* execution.
|
||||
*/
|
||||
|
||||
if ((shdr->sh_flags & SHF_ALLOC) == 0)
|
||||
{
|
||||
/* Allocate memory to hold a copy of the .ctor section */
|
||||
|
||||
loadinfo->ctoralloc = (binfmt_ctor_t*)kmalloc(ctorsize);
|
||||
if (!loadinfo->ctoralloc)
|
||||
{
|
||||
bdbg("Failed to allocate memory for .ctors\n");
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
loadinfo->ctors = (binfmt_ctor_t *)loadinfo->ctoralloc;
|
||||
|
||||
/* Read the section header table into memory */
|
||||
|
||||
ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->ctors, ctorsize,
|
||||
shdr->sh_offset);
|
||||
if (ret < 0)
|
||||
{
|
||||
bdbg("Failed to allocate .ctors: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Fix up all of the .ctor addresses. Since the addresses
|
||||
* do not lie in allocated memory, there will be no relocation
|
||||
* section for them.
|
||||
*/
|
||||
|
||||
for (i = 0; i < loadinfo->nctors; i++)
|
||||
{
|
||||
FAR uintptr_t *ptr = (uintptr_t *)((FAR void *)(&loadinfo->ctors)[i]);
|
||||
|
||||
bvdbg("ctor %d: %08lx + %08lx = %08lx\n",
|
||||
i, *ptr, loadinfo->elfalloc, *ptr + loadinfo->elfalloc);
|
||||
|
||||
*ptr += loadinfo->elfalloc;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
/* Save the address of the .ctors (actually, .init_array) where it was
|
||||
* loaded into memory. Since the .ctors lie in allocated memory, they
|
||||
* will be relocated via the normal mechanism.
|
||||
*/
|
||||
|
||||
loadinfo->ctors = (binfmt_ctor_t*)shdr->sh_addr;
|
||||
}
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_BINFMT_CONSTRUCTORS */
|
|
@ -0,0 +1,215 @@
|
|||
/****************************************************************************
|
||||
* binfmt/libelf/libelf_dtors.c
|
||||
*
|
||||
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <string.h>
|
||||
#include <errno.h>
|
||||
#include <assert.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/binfmt/elf.h>
|
||||
|
||||
#include "libelf.h"
|
||||
|
||||
#ifdef CONFIG_BINFMT_CONSTRUCTORS
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Constant Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: elf_loaddtors
|
||||
*
|
||||
* Description:
|
||||
* Load pointers to static destructors into an in-memory array.
|
||||
*
|
||||
* Input Parameters:
|
||||
* loadinfo - Load state information
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 (OK) is returned on success and a negated errno is returned on
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int elf_loaddtors(FAR struct elf_loadinfo_s *loadinfo)
|
||||
{
|
||||
FAR Elf32_Shdr *shdr;
|
||||
size_t dtorsize;
|
||||
int dtoridx;
|
||||
int ret;
|
||||
int i;
|
||||
|
||||
DEBUGASSERT(loadinfo->dtors == NULL);
|
||||
|
||||
/* Allocate an I/O buffer if necessary. This buffer is used by
|
||||
* elf_sectname() to accumulate the variable length symbol name.
|
||||
*/
|
||||
|
||||
ret = elf_allocbuffer(loadinfo);
|
||||
if (ret < 0)
|
||||
{
|
||||
bdbg("elf_allocbuffer failed: %d\n", ret);
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
/* Find the index to the section named ".dtors." NOTE: On old ABI system,
|
||||
* .dtors is the name of the section containing the list of destructors;
|
||||
* On newer systems, the similar section is called .fini_array. It is
|
||||
* expected that the linker script will force the section name to be ".dtors"
|
||||
* in either case.
|
||||
*/
|
||||
|
||||
dtoridx = elf_findsection(loadinfo, ".dtors");
|
||||
if (dtoridx < 0)
|
||||
{
|
||||
/* This may not be a failure. -ENOENT indicates that the file has no
|
||||
* static destructor section.
|
||||
*/
|
||||
|
||||
bvdbg("elf_findsection .dtors section failed: %d\n", dtoridx);
|
||||
return ret == -ENOENT ? OK : ret;
|
||||
}
|
||||
|
||||
/* Now we can get a pointer to the .dtor section in the section header
|
||||
* table.
|
||||
*/
|
||||
|
||||
shdr = &loadinfo->shdr[dtoridx];
|
||||
|
||||
/* Get the size of the .dtor section and the number of destructors that
|
||||
* will need to be called.
|
||||
*/
|
||||
|
||||
dtorsize = shdr->sh_size;
|
||||
loadinfo->ndtors = dtorsize / sizeof(binfmt_dtor_t);
|
||||
|
||||
bvdbg("dtoridx=%d dtorsize=%d sizeof(binfmt_dtor_t)=%d ndtors=%d\n",
|
||||
dtoridx, dtorsize, sizeof(binfmt_dtor_t), loadinfo->ndtors);
|
||||
|
||||
/* Check if there are any destructors. It is not an error if there
|
||||
* are none.
|
||||
*/
|
||||
|
||||
if (loadinfo->ndtors > 0)
|
||||
{
|
||||
/* Check an assumption that we made above */
|
||||
|
||||
DEBUGASSERT(shdr->sh_size == loadinfo->ndtors * sizeof(binfmt_dtor_t));
|
||||
|
||||
/* In the old ABI, the .dtors section is not allocated. In that case,
|
||||
* we need to allocate memory to hold the .dtors and then copy the
|
||||
* from the file into the allocated memory.
|
||||
*
|
||||
* SHF_ALLOC indicates that the section requires memory during
|
||||
* execution.
|
||||
*/
|
||||
|
||||
if ((shdr->sh_flags & SHF_ALLOC) == 0)
|
||||
{
|
||||
/* Allocate memory to hold a copy of the .dtor section */
|
||||
|
||||
loadinfo->ctoralloc = (binfmt_dtor_t*)kmalloc(dtorsize);
|
||||
if (!loadinfo->ctoralloc)
|
||||
{
|
||||
bdbg("Failed to allocate memory for .dtors\n");
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
loadinfo->dtors = (binfmt_dtor_t *)loadinfo->ctoralloc;
|
||||
|
||||
/* Read the section header table into memory */
|
||||
|
||||
ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->dtors, dtorsize,
|
||||
shdr->sh_offset);
|
||||
if (ret < 0)
|
||||
{
|
||||
bdbg("Failed to allocate .dtors: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Fix up all of the .dtor addresses. Since the addresses
|
||||
* do not lie in allocated memory, there will be no relocation
|
||||
* section for them.
|
||||
*/
|
||||
|
||||
for (i = 0; i < loadinfo->ndtors; i++)
|
||||
{
|
||||
FAR uintptr_t *ptr = (uintptr_t *)((FAR void *)(&loadinfo->dtors)[i]);
|
||||
|
||||
bvdbg("dtor %d: %08lx + %08lx = %08lx\n",
|
||||
i, *ptr, loadinfo->elfalloc, *ptr + loadinfo->elfalloc);
|
||||
|
||||
*ptr += loadinfo->elfalloc;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
/* Save the address of the .dtors (actually, .init_array) where it was
|
||||
* loaded into memory. Since the .dtors lie in allocated memory, they
|
||||
* will be relocated via the normal mechanism.
|
||||
*/
|
||||
|
||||
loadinfo->dtors = (binfmt_dtor_t*)shdr->sh_addr;
|
||||
}
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_BINFMT_CONSTRUCTORS */
|
|
@ -0,0 +1,202 @@
|
|||
/****************************************************************************
|
||||
* binfmt/libelf/libelf_init.c
|
||||
*
|
||||
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <sys/stat.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include <fcntl.h>
|
||||
#include <elf32.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/binfmt/elf.h>
|
||||
|
||||
#include "libelf.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE, and CONFIG_DEBUG_BINFMT have to be
|
||||
* defined or CONFIG_ELF_DUMPBUFFER does nothing.
|
||||
*/
|
||||
|
||||
#if !defined(CONFIG_DEBUG_VERBOSE) || !defined (CONFIG_DEBUG_BINFMT)
|
||||
# undef CONFIG_ELF_DUMPBUFFER
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ELF_DUMPBUFFER
|
||||
# define elf_dumpbuffer(m,b,n) bvdbgdumpbuffer(m,b,n)
|
||||
#else
|
||||
# define elf_dumpbuffer(m,b,n)
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Constant Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: elf_filelen
|
||||
*
|
||||
* Description:
|
||||
* Get the size of the ELF file
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 (OK) is returned on success and a negated errno is returned on
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static inline int elf_filelen(FAR struct elf_loadinfo_s *loadinfo,
|
||||
FAR const char *filename)
|
||||
{
|
||||
struct stat buf;
|
||||
int ret;
|
||||
|
||||
/* Get the file stats */
|
||||
|
||||
ret = stat(filename, &buf);
|
||||
if (ret < 0)
|
||||
{
|
||||
int errval = errno;
|
||||
bdbg("Failed to fstat file: %d\n", errval);
|
||||
return -errval;
|
||||
}
|
||||
|
||||
/* Verify that it is a regular file */
|
||||
|
||||
if (!S_ISREG(buf.st_mode))
|
||||
{
|
||||
bdbg("Not a regular file. mode: %d\n", buf.st_mode);
|
||||
return -ENOENT;
|
||||
}
|
||||
|
||||
/* TODO: Verify that the file is readable. Not really important because
|
||||
* we will detect this when we try to open the file read-only.
|
||||
*/
|
||||
|
||||
/* Return the size of the file in the loadinfo structure */
|
||||
|
||||
loadinfo->filelen = buf.st_size;
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: elf_init
|
||||
*
|
||||
* Description:
|
||||
* This function is called to configure the library to process an ELF
|
||||
* program binary.
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 (OK) is returned on success and a negated errno is returned on
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int elf_init(FAR const char *filename, FAR struct elf_loadinfo_s *loadinfo)
|
||||
{
|
||||
int ret;
|
||||
|
||||
bvdbg("filename: %s loadinfo: %p\n", filename, loadinfo);
|
||||
|
||||
/* Clear the load info structure */
|
||||
|
||||
memset(loadinfo, 0, sizeof(struct elf_loadinfo_s));
|
||||
|
||||
/* Get the length of the file. */
|
||||
|
||||
ret = elf_filelen(loadinfo, filename);
|
||||
if (ret < 0)
|
||||
{
|
||||
bdbg("elf_filelen failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Open the binary file for reading (only) */
|
||||
|
||||
loadinfo->filfd = open(filename, O_RDONLY);
|
||||
if (loadinfo->filfd < 0)
|
||||
{
|
||||
int errval = errno;
|
||||
bdbg("Failed to open ELF binary %s: %d\n", filename, errval);
|
||||
return -errval;
|
||||
}
|
||||
|
||||
/* Read the ELF ehdr from offset 0 */
|
||||
|
||||
ret = elf_read(loadinfo, (FAR uint8_t*)&loadinfo->ehdr, sizeof(Elf32_Ehdr), 0);
|
||||
if (ret < 0)
|
||||
{
|
||||
bdbg("Failed to read ELF header: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
elf_dumpbuffer("ELF header", (FAR const uint8_t*)&loadinfo->ehdr, sizeof(Elf32_Ehdr));
|
||||
|
||||
/* Verify the ELF header */
|
||||
|
||||
ret = elf_verifyheader(&loadinfo->ehdr);
|
||||
if (ret <0)
|
||||
{
|
||||
/* This may not be an error because we will be called to attempt loading
|
||||
* EVERY binary. If elf_verifyheader() does not recognize the ELF header,
|
||||
* it will -ENOEXEC whcih simply informs the system that the file is not an
|
||||
* ELF file. elf_verifyheader() will return other errors if the ELF header
|
||||
* is not correctly formed.
|
||||
*/
|
||||
|
||||
bdbg("Bad ELF header: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
|
@ -0,0 +1,136 @@
|
|||
/****************************************************************************
|
||||
* binfmt/libelf/elf_iobuffer.c
|
||||
*
|
||||
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/binfmt/elf.h>
|
||||
|
||||
#include "libelf.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Constant Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: elf_allocbuffer
|
||||
*
|
||||
* Description:
|
||||
* Perform the initial allocation of the I/O buffer, if it has not already
|
||||
* been allocated.
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 (OK) is returned on success and a negated errno is returned on
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int elf_allocbuffer(FAR struct elf_loadinfo_s *loadinfo)
|
||||
{
|
||||
/* Has a buffer been allocated> */
|
||||
|
||||
if (!loadinfo->iobuffer)
|
||||
{
|
||||
/* No.. allocate one now */
|
||||
|
||||
loadinfo->iobuffer = (FAR uint8_t *)kmalloc(CONFIG_ELF_BUFFERSIZE);
|
||||
if (!loadinfo->iobuffer)
|
||||
{
|
||||
bdbg("Failed to allocate an I/O buffer\n");
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
loadinfo->buflen = CONFIG_ELF_BUFFERSIZE;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: elf_reallocbuffer
|
||||
*
|
||||
* Description:
|
||||
* Increase the size of I/O buffer by the specified buffer increment.
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 (OK) is returned on success and a negated errno is returned on
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int elf_reallocbuffer(FAR struct elf_loadinfo_s *loadinfo, size_t increment)
|
||||
{
|
||||
FAR void *buffer;
|
||||
size_t newsize;
|
||||
|
||||
/* Get the new size of the allocation */
|
||||
|
||||
newsize = loadinfo->buflen + increment;
|
||||
|
||||
/* And perform the reallocation */
|
||||
|
||||
buffer = krealloc((FAR void *)loadinfo->iobuffer, newsize);
|
||||
if (!buffer)
|
||||
{
|
||||
bdbg("Failed to reallocate the I/O buffer\n");
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
/* Save the new buffer info */
|
||||
|
||||
loadinfo->iobuffer = buffer;
|
||||
loadinfo->buflen = newsize;
|
||||
return OK;
|
||||
}
|
||||
|
|
@ -0,0 +1,284 @@
|
|||
/****************************************************************************
|
||||
* binfmt/libelf/libelf_sections.c
|
||||
*
|
||||
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <assert.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/binfmt/elf.h>
|
||||
|
||||
#include "libelf.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Constant Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: elf_sectname
|
||||
*
|
||||
* Description:
|
||||
* Get the symbol name in loadinfo->iobuffer[].
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 (OK) is returned on success and a negated errno is returned on
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static inline int elf_sectname(FAR struct elf_loadinfo_s *loadinfo,
|
||||
FAR const Elf32_Shdr *shdr)
|
||||
{
|
||||
FAR Elf32_Shdr *shstr;
|
||||
FAR uint8_t *buffer;
|
||||
off_t offset;
|
||||
size_t readlen;
|
||||
size_t bytesread;
|
||||
int shstrndx;
|
||||
int ret;
|
||||
|
||||
/* Get the section header table index of the entry associated with the
|
||||
* section name string table. If the file has no section name string table,
|
||||
* this member holds the value SH_UNDEF.
|
||||
*/
|
||||
|
||||
shstrndx = loadinfo->ehdr.e_shstrndx;
|
||||
if (shstrndx == SHN_UNDEF)
|
||||
{
|
||||
bdbg("No section header string table\n");
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
/* Get the section name string table section header */
|
||||
|
||||
shstr = &loadinfo->shdr[shstrndx];
|
||||
|
||||
/* Get the file offset to the string that is the name of the section. This
|
||||
* is the sum of:
|
||||
*
|
||||
* shstr->sh_offset: The file offset to the first byte of the section
|
||||
* header string table data.
|
||||
* shdr->sh_name: The offset to the name of the section in the section
|
||||
* name table
|
||||
*/
|
||||
|
||||
offset = shstr->sh_offset + shdr->sh_name;
|
||||
|
||||
/* Loop until we get the entire section name into memory */
|
||||
|
||||
buffer = loadinfo->iobuffer;
|
||||
bytesread = 0;
|
||||
|
||||
for (;;)
|
||||
{
|
||||
/* Get the number of bytes to read */
|
||||
|
||||
readlen = loadinfo->buflen - bytesread;
|
||||
if (offset + readlen > loadinfo->filelen)
|
||||
{
|
||||
readlen = loadinfo->filelen - offset;
|
||||
if (readlen <= 0)
|
||||
{
|
||||
bdbg("At end of file\n");
|
||||
return -EINVAL;
|
||||
}
|
||||
}
|
||||
|
||||
/* Read that number of bytes into the array */
|
||||
|
||||
buffer = &loadinfo->iobuffer[bytesread];
|
||||
ret = elf_read(loadinfo, buffer, readlen, offset);
|
||||
if (ret < 0)
|
||||
{
|
||||
bdbg("Failed to read section name\n");
|
||||
return ret;
|
||||
}
|
||||
|
||||
bytesread += readlen;
|
||||
|
||||
/* Did we read the NUL terminator? */
|
||||
|
||||
if (memchr(buffer, '\0', readlen) != NULL)
|
||||
{
|
||||
/* Yes, the buffer contains a NUL terminator. */
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/* No.. then we have to read more */
|
||||
|
||||
ret = elf_reallocbuffer(loadinfo, CONFIG_ELF_BUFFERINCR);
|
||||
if (ret < 0)
|
||||
{
|
||||
bdbg("elf_reallocbuffer failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
}
|
||||
|
||||
/* We will not get here */
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: elf_loadshdrs
|
||||
*
|
||||
* Description:
|
||||
* Loads section headers into memory.
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 (OK) is returned on success and a negated errno is returned on
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int elf_loadshdrs(FAR struct elf_loadinfo_s *loadinfo)
|
||||
{
|
||||
size_t shdrsize;
|
||||
int ret;
|
||||
|
||||
DEBUGASSERT(loadinfo->shdr == NULL);
|
||||
|
||||
/* Verify that there are sections */
|
||||
|
||||
if (loadinfo->ehdr.e_shnum < 1)
|
||||
{
|
||||
bdbg("No sections(?)\n");
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
/* Get the total size of the section header table */
|
||||
|
||||
shdrsize = (size_t)loadinfo->ehdr.e_shentsize * (size_t)loadinfo->ehdr.e_shnum;
|
||||
if(loadinfo->ehdr.e_shoff + shdrsize > loadinfo->filelen)
|
||||
{
|
||||
bdbg("Insufficent space in file for section header table\n");
|
||||
return -ESPIPE;
|
||||
}
|
||||
|
||||
/* Allocate memory to hold a working copy of the sector header table */
|
||||
|
||||
loadinfo->shdr = (FAR Elf32_Shdr*)kmalloc(shdrsize);
|
||||
if (!loadinfo->shdr)
|
||||
{
|
||||
bdbg("Failed to allocate the section header table. Size: %ld\n", (long)shdrsize);
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
/* Read the section header table into memory */
|
||||
|
||||
ret = elf_read(loadinfo, (FAR uint8_t*)loadinfo->shdr, shdrsize, loadinfo->ehdr.e_shoff);
|
||||
if (ret < 0)
|
||||
{
|
||||
bdbg("Failed to read section header table: %d\n", ret);
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: elf_findsection
|
||||
*
|
||||
* Description:
|
||||
* A section by its name.
|
||||
*
|
||||
* Input Parameters:
|
||||
* loadinfo - Load state information
|
||||
* sectname - Name of the section to find
|
||||
*
|
||||
* Returned Value:
|
||||
* On success, the index to the section is returned; A negated errno value
|
||||
* is returned on failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int elf_findsection(FAR struct elf_loadinfo_s *loadinfo,
|
||||
FAR const char *sectname)
|
||||
{
|
||||
FAR const Elf32_Shdr *shdr;
|
||||
int ret;
|
||||
int i;
|
||||
|
||||
/* Search through the shdr[] array in loadinfo for a section named 'sectname' */
|
||||
|
||||
for (i = 0; i < loadinfo->ehdr.e_shnum; i++)
|
||||
{
|
||||
/* Get the name of this section */
|
||||
|
||||
shdr = &loadinfo->shdr[i];
|
||||
ret = elf_sectname(loadinfo, shdr);
|
||||
if (ret < 0)
|
||||
{
|
||||
bdbg("elf_sectname failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Check if the name of this section is 'sectname' */
|
||||
|
||||
bvdbg("%d. Comparing \"%s\" and .\"%s\"\n",
|
||||
i, loadinfo->iobuffer, sectname);
|
||||
|
||||
if (strcmp((FAR const char *)loadinfo->iobuffer, sectname) == 0)
|
||||
{
|
||||
/* We found it... return the index */
|
||||
|
||||
return i;
|
||||
}
|
||||
}
|
||||
|
||||
/* We failed to find a section with this name. */
|
||||
|
||||
return -ENOENT;
|
||||
}
|
|
@ -0,0 +1,329 @@
|
|||
/****************************************************************************
|
||||
* binfmt/libelf/libelf_symbols.c
|
||||
*
|
||||
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <elf32.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/binfmt/elf.h>
|
||||
#include <nuttx/binfmt/symtab.h>
|
||||
|
||||
#include "libelf.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef CONFIG_ELF_BUFFERINCR
|
||||
# define CONFIG_ELF_BUFFERINCR 32
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Constant Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: elf_symname
|
||||
*
|
||||
* Description:
|
||||
* Get the symbol name in loadinfo->iobuffer[].
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 (OK) is returned on success and a negated errno is returned on
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int elf_symname(FAR struct elf_loadinfo_s *loadinfo,
|
||||
FAR const Elf32_Sym *sym)
|
||||
{
|
||||
FAR uint8_t *buffer;
|
||||
off_t offset;
|
||||
size_t readlen;
|
||||
size_t bytesread;
|
||||
int ret;
|
||||
|
||||
/* Get the file offset to the string that is the name of the symbol. The
|
||||
* st_name member holds an offset into the file's symbol string table.
|
||||
*/
|
||||
|
||||
if (sym->st_name == 0)
|
||||
{
|
||||
bdbg("Symbol has no name\n");
|
||||
return -ENOENT;
|
||||
}
|
||||
|
||||
offset = loadinfo->shdr[loadinfo->strtabidx].sh_offset + sym->st_name;
|
||||
|
||||
/* Loop until we get the entire symbol name into memory */
|
||||
|
||||
bytesread = 0;
|
||||
|
||||
for (;;)
|
||||
{
|
||||
/* Get the number of bytes to read */
|
||||
|
||||
readlen = loadinfo->buflen - bytesread;
|
||||
if (offset + readlen > loadinfo->filelen)
|
||||
{
|
||||
readlen = loadinfo->filelen - offset;
|
||||
if (readlen <= 0)
|
||||
{
|
||||
bdbg("At end of file\n");
|
||||
return -EINVAL;
|
||||
}
|
||||
}
|
||||
|
||||
/* Read that number of bytes into the array */
|
||||
|
||||
buffer = &loadinfo->iobuffer[bytesread];
|
||||
ret = elf_read(loadinfo, buffer, readlen, offset);
|
||||
if (ret < 0)
|
||||
{
|
||||
bdbg("elf_read failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
bytesread += readlen;
|
||||
|
||||
/* Did we read the NUL terminator? */
|
||||
|
||||
if (memchr(buffer, '\0', readlen) != NULL)
|
||||
{
|
||||
/* Yes, the buffer contains a NUL terminator. */
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/* No.. then we have to read more */
|
||||
|
||||
ret = elf_reallocbuffer(loadinfo, CONFIG_ELF_BUFFERINCR);
|
||||
if (ret < 0)
|
||||
{
|
||||
bdbg("elf_reallocbuffer failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
}
|
||||
|
||||
/* We will not get here */
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: elf_findsymtab
|
||||
*
|
||||
* Description:
|
||||
* Find the symbol table section.
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 (OK) is returned on success and a negated errno is returned on
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int elf_findsymtab(FAR struct elf_loadinfo_s *loadinfo)
|
||||
{
|
||||
int i;
|
||||
|
||||
/* Find the symbol table section header and its associated string table */
|
||||
|
||||
for (i = 1; i < loadinfo->ehdr.e_shnum; i++)
|
||||
{
|
||||
if (loadinfo->shdr[i].sh_type == SHT_SYMTAB)
|
||||
{
|
||||
loadinfo->symtabidx = i;
|
||||
loadinfo->strtabidx = loadinfo->shdr[i].sh_link;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/* Verify that there is a symbol and string table */
|
||||
|
||||
if (loadinfo->symtabidx == 0)
|
||||
{
|
||||
bdbg("No symbols in ELF file\n");
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: elf_readsym
|
||||
*
|
||||
* Description:
|
||||
* Read the ELFT symbol structure at the specfied index into memory.
|
||||
*
|
||||
* Input Parameters:
|
||||
* loadinfo - Load state information
|
||||
* index - Symbol table index
|
||||
* sym - Location to return the table entry
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 (OK) is returned on success and a negated errno is returned on
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int elf_readsym(FAR struct elf_loadinfo_s *loadinfo, int index,
|
||||
FAR Elf32_Sym *sym)
|
||||
{
|
||||
FAR Elf32_Shdr *symtab = &loadinfo->shdr[loadinfo->symtabidx];
|
||||
off_t offset;
|
||||
|
||||
/* Verify that the symbol table index lies within symbol table */
|
||||
|
||||
if (index < 0 || index > (symtab->sh_size / sizeof(Elf32_Sym)))
|
||||
{
|
||||
bdbg("Bad relocation symbol index: %d\n", index);
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
/* Get the file offset to the symbol table entry */
|
||||
|
||||
offset = symtab->sh_offset + sizeof(Elf32_Sym) * index;
|
||||
|
||||
/* And, finally, read the symbol table entry into memory */
|
||||
|
||||
return elf_read(loadinfo, (FAR uint8_t*)sym, sizeof(Elf32_Sym), offset);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: elf_symvalue
|
||||
*
|
||||
* Description:
|
||||
* Get the value of a symbol. The updated value of the symbol is returned
|
||||
* in the st_value field of the symbol table entry.
|
||||
*
|
||||
* Input Parameters:
|
||||
* loadinfo - Load state information
|
||||
* sym - Symbol table entry (value might be undefined)
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 (OK) is returned on success and a negated errno is returned on
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int elf_symvalue(FAR struct elf_loadinfo_s *loadinfo, FAR Elf32_Sym *sym,
|
||||
FAR const struct symtab_s *exports, int nexports)
|
||||
{
|
||||
FAR const struct symtab_s *symbol;
|
||||
uintptr_t secbase;
|
||||
int ret;
|
||||
|
||||
switch (sym->st_shndx)
|
||||
{
|
||||
case SHN_COMMON:
|
||||
{
|
||||
/* NuttX ELF modules should be compiled with -fno-common. */
|
||||
|
||||
bdbg("SHN_COMMON: Re-compile with -fno-common\n");
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
case SHN_ABS:
|
||||
{
|
||||
/* st_value already holds the correct value */
|
||||
|
||||
bvdbg("SHN_ABS: st_value=%08lx\n", (long)sym->st_value);
|
||||
return OK;
|
||||
}
|
||||
|
||||
case SHN_UNDEF:
|
||||
{
|
||||
/* Get the name of the undefined symbol */
|
||||
|
||||
ret = elf_symname(loadinfo, sym);
|
||||
if (ret < 0)
|
||||
{
|
||||
bdbg("SHN_UNDEF: Failed to get symbol name: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Check if the base code exports a symbol of this name */
|
||||
|
||||
#ifdef CONFIG_SYMTAB_ORDEREDBYNAME
|
||||
symbol = symtab_findorderedbyname(exports, (FAR char *)loadinfo->iobuffer, nexports);
|
||||
#else
|
||||
symbol = symtab_findbyname(exports, (FAR char *)loadinfo->iobuffer, nexports);
|
||||
#endif
|
||||
if (!symbol)
|
||||
{
|
||||
bdbg("SHN_UNDEF: Exported symbol \"%s\" not found\n", loadinfo->iobuffer);
|
||||
return -ENOENT;
|
||||
}
|
||||
|
||||
/* Yes... add the exported symbol value to the ELF symbol table entry */
|
||||
|
||||
bvdbg("SHN_ABS: name=%s %08x+%08x=%08x\n",
|
||||
loadinfo->iobuffer, sym->st_value, symbol->sym_value,
|
||||
sym->st_value + symbol->sym_value);
|
||||
|
||||
sym->st_value += (Elf32_Word)((uintptr_t)symbol->sym_value);
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
{
|
||||
secbase = loadinfo->shdr[sym->st_shndx].sh_addr;
|
||||
|
||||
bvdbg("Other: %08x+%08x=%08x\n",
|
||||
sym->st_value, secbase, sym->st_value + secbase);
|
||||
|
||||
sym->st_value += secbase;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
|
@ -0,0 +1,126 @@
|
|||
/****************************************************************************
|
||||
* binfmt/libelf/libelf_uninit.c
|
||||
*
|
||||
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <unistd.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/binfmt/elf.h>
|
||||
|
||||
#include "libelf.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Constant Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: elf_uninit
|
||||
*
|
||||
* Description:
|
||||
* Releases any resources committed by elf_init(). This essentially
|
||||
* undoes the actions of elf_init.
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 (OK) is returned on success and a negated errno is returned on
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int elf_uninit(struct elf_loadinfo_s *loadinfo)
|
||||
{
|
||||
/* Free all working buffers */
|
||||
|
||||
elf_freebuffers(loadinfo);
|
||||
|
||||
/* Close the ELF file */
|
||||
|
||||
if (loadinfo->filfd >= 0)
|
||||
{
|
||||
close(loadinfo->filfd);
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: elf_freebuffers
|
||||
*
|
||||
* Description:
|
||||
* Release all working buffers.
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 (OK) is returned on success and a negated errno is returned on
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int elf_freebuffers(struct elf_loadinfo_s *loadinfo)
|
||||
{
|
||||
/* Release all working allocations */
|
||||
|
||||
if (loadinfo->shdr)
|
||||
{
|
||||
kfree((FAR void *)loadinfo->shdr);
|
||||
loadinfo->shdr = NULL;
|
||||
}
|
||||
|
||||
if (loadinfo->iobuffer)
|
||||
{
|
||||
kfree((FAR void *)loadinfo->iobuffer);
|
||||
loadinfo->iobuffer = NULL;
|
||||
loadinfo->buflen = 0;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
|
@ -0,0 +1,120 @@
|
|||
/****************************************************************************
|
||||
* binfmt/libelf/elf_verify.c
|
||||
*
|
||||
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <string.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/binfmt/elf.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Constant Data
|
||||
****************************************************************************/
|
||||
|
||||
static const char g_elfmagic[EI_MAGIC_SIZE] = { 0x7f, 'E', 'L', 'F' };
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: elf_verifyheader
|
||||
*
|
||||
* Description:
|
||||
* Given the header from a possible ELF executable, verify that it
|
||||
* is an ELF executable.
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 (OK) is returned on success and a negated errno is returned on
|
||||
* failure.
|
||||
*
|
||||
* -ENOEXEC : Not an ELF file
|
||||
* -EINVAL : Not a relocatable ELF file or not supported by the current,
|
||||
* configured architecture.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int elf_verifyheader(FAR const Elf32_Ehdr *ehdr)
|
||||
{
|
||||
if (!ehdr)
|
||||
{
|
||||
bdbg("NULL ELF header!");
|
||||
return -ENOEXEC;
|
||||
}
|
||||
|
||||
/* Verify that the magic number indicates an ELF file */
|
||||
|
||||
if (memcmp(ehdr->e_ident, g_elfmagic, EI_MAGIC_SIZE) != 0)
|
||||
{
|
||||
bvdbg("Not ELF magic {%02x, %02x, %02x, %02x}\n",
|
||||
ehdr->e_ident[0], ehdr->e_ident[1], ehdr->e_ident[2], ehdr->e_ident[3]);
|
||||
return -ENOEXEC;
|
||||
}
|
||||
|
||||
/* Verify that this is a relocatable file */
|
||||
|
||||
if (ehdr->e_type != ET_REL)
|
||||
{
|
||||
bdbg("Not a relocatable file: e_type=%d\n", ehdr->e_type);
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
/* Verify that this file works with the currently configured architecture */
|
||||
|
||||
if (arch_checkarch(ehdr))
|
||||
{
|
||||
bdbg("Not a supported architecture\n");
|
||||
return -ENOEXEC;
|
||||
}
|
||||
|
||||
/* Looks good so far... we still might find some problems later. */
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
Loading…
Reference in New Issue