Browse Source

Merge branch 'master' of github.com:PX4/Firmware

sbg
Lorenz Meier 11 years ago
parent
commit
902fcf44c9
  1. 2
      nuttx-configs/px4fmu-v1/nsh/defconfig
  2. 14
      nuttx-configs/px4fmu-v2/nsh/defconfig
  3. 4
      src/drivers/meas_airspeed/meas_airspeed.cpp
  4. 6
      src/drivers/ms5611/ms5611.cpp
  5. 6
      src/modules/px4iofirmware/dsm.c
  6. 21
      src/modules/px4iofirmware/px4io.c
  7. 4
      src/modules/px4iofirmware/px4io.h
  8. 15
      src/modules/px4iofirmware/registers.c
  9. 50
      src/systemcmds/tests/test_file.c

2
nuttx-configs/px4fmu-v1/nsh/defconfig

@ -566,7 +566,7 @@ CONFIG_CDCACM_NWRREQS=4 @@ -566,7 +566,7 @@ CONFIG_CDCACM_NWRREQS=4
CONFIG_CDCACM_NRDREQS=4
CONFIG_CDCACM_BULKIN_REQLEN=96
CONFIG_CDCACM_RXBUFSIZE=512
CONFIG_CDCACM_TXBUFSIZE=512
CONFIG_CDCACM_TXBUFSIZE=2048
CONFIG_CDCACM_VENDORID=0x26ac
CONFIG_CDCACM_PRODUCTID=0x0010
CONFIG_CDCACM_VENDORSTR="3D Robotics"

14
nuttx-configs/px4fmu-v2/nsh/defconfig

@ -295,7 +295,7 @@ CONFIG_STM32_USART=y @@ -295,7 +295,7 @@ CONFIG_STM32_USART=y
# U[S]ART Configuration
#
# CONFIG_USART1_RS485 is not set
# CONFIG_USART1_RXDMA is not set
CONFIG_USART1_RXDMA=y
# CONFIG_USART2_RS485 is not set
CONFIG_USART2_RXDMA=y
# CONFIG_USART3_RS485 is not set
@ -304,7 +304,7 @@ CONFIG_USART3_RXDMA=y @@ -304,7 +304,7 @@ CONFIG_USART3_RXDMA=y
CONFIG_UART4_RXDMA=y
CONFIG_UART5_RXDMA=y
# CONFIG_USART6_RS485 is not set
# CONFIG_USART6_RXDMA is not set
CONFIG_USART6_RXDMA=y
# CONFIG_UART7_RS485 is not set
# CONFIG_UART7_RXDMA is not set
# CONFIG_UART8_RS485 is not set
@ -582,8 +582,8 @@ CONFIG_USART3_OFLOWCONTROL=y @@ -582,8 +582,8 @@ CONFIG_USART3_OFLOWCONTROL=y
#
# UART4 Configuration
#
CONFIG_UART4_RXBUFSIZE=128
CONFIG_UART4_TXBUFSIZE=128
CONFIG_UART4_RXBUFSIZE=512
CONFIG_UART4_TXBUFSIZE=512
CONFIG_UART4_BAUD=57600
CONFIG_UART4_BITS=8
CONFIG_UART4_PARITY=0
@ -594,8 +594,8 @@ CONFIG_UART4_2STOP=0 @@ -594,8 +594,8 @@ CONFIG_UART4_2STOP=0
#
# USART6 Configuration
#
CONFIG_USART6_RXBUFSIZE=256
CONFIG_USART6_TXBUFSIZE=256
CONFIG_USART6_RXBUFSIZE=512
CONFIG_USART6_TXBUFSIZE=512
CONFIG_USART6_BAUD=57600
CONFIG_USART6_BITS=8
CONFIG_USART6_PARITY=0
@ -662,7 +662,7 @@ CONFIG_CDCACM_NWRREQS=4 @@ -662,7 +662,7 @@ CONFIG_CDCACM_NWRREQS=4
CONFIG_CDCACM_NRDREQS=4
CONFIG_CDCACM_BULKIN_REQLEN=96
CONFIG_CDCACM_RXBUFSIZE=512
CONFIG_CDCACM_TXBUFSIZE=512
CONFIG_CDCACM_TXBUFSIZE=2048
CONFIG_CDCACM_VENDORID=0x26ac
CONFIG_CDCACM_PRODUCTID=0x0011
CONFIG_CDCACM_VENDORSTR="3D Robotics"

4
src/drivers/meas_airspeed/meas_airspeed.cpp

@ -198,7 +198,9 @@ MEASAirspeed::collect() @@ -198,7 +198,9 @@ MEASAirspeed::collect()
// uint16_t diff_press_pa = abs(dp_raw - (16384 / 2.0f));
const float P_min = -1.0f;
const float P_max = 1.0f;
float diff_press_pa = math::max(0.0f, fabsf( ( ((float)dp_raw - 0.1f*16383.0f) * (P_max-P_min)/(0.8f*16383.0f) + P_min) * 6894.8f) - _diff_pres_offset);
float diff_press_pa = fabsf( ( ((float)dp_raw - 0.1f*16383.0f) * (P_max-P_min)/(0.8f*16383.0f) + P_min) * 6894.8f) - _diff_pres_offset;
if (diff_press_pa < 0.0f)
diff_press_pa = 0.0f;
struct differential_pressure_s report;

6
src/drivers/ms5611/ms5611.cpp

@ -124,6 +124,8 @@ protected: @@ -124,6 +124,8 @@ protected:
int32_t _TEMP;
int64_t _OFF;
int64_t _SENS;
float _P;
float _T;
/* altitude conversion calibration */
unsigned _msl_pressure; /* in kPa */
@ -623,6 +625,8 @@ MS5611::collect() @@ -623,6 +625,8 @@ MS5611::collect()
/* pressure calculation, result in Pa */
int32_t P = (((raw * _SENS) >> 21) - _OFF) >> 15;
_P = P * 0.01f;
_T = _TEMP * 0.01f;
/* generate a new report */
report.temperature = _TEMP / 100.0f;
@ -695,6 +699,8 @@ MS5611::print_info() @@ -695,6 +699,8 @@ MS5611::print_info()
printf("TEMP: %d\n", _TEMP);
printf("SENS: %lld\n", _SENS);
printf("OFF: %lld\n", _OFF);
printf("P: %.3f\n", _P);
printf("T: %.3f\n", _T);
printf("MSL pressure: %10.4f\n", (double)(_msl_pressure / 100.f));
printf("factory_setup %u\n", _prom.factory_setup);

6
src/modules/px4iofirmware/dsm.c

@ -203,6 +203,12 @@ dsm_guess_format(bool reset) @@ -203,6 +203,12 @@ dsm_guess_format(bool reset)
int
dsm_init(const char *device)
{
#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
// enable power on DSM connector
POWER_SPEKTRUM(true);
#endif
if (dsm_fd < 0)
dsm_fd = open(device, O_RDONLY | O_NONBLOCK);

21
src/modules/px4iofirmware/px4io.c

@ -125,6 +125,25 @@ heartbeat_blink(void) @@ -125,6 +125,25 @@ heartbeat_blink(void)
LED_BLUE(heartbeat = !heartbeat);
}
static uint64_t reboot_time;
/**
schedule a reboot in time_delta_usec microseconds
*/
void schedule_reboot(uint32_t time_delta_usec)
{
reboot_time = hrt_absolute_time() + time_delta_usec;
}
/**
check for a scheduled reboot
*/
static void check_reboot(void)
{
if (reboot_time != 0 && hrt_absolute_time() > reboot_time) {
up_systemreset();
}
}
static void
calculate_fw_crc(void)
@ -249,6 +268,8 @@ user_start(int argc, char *argv[]) @@ -249,6 +268,8 @@ user_start(int argc, char *argv[])
heartbeat_blink();
}
check_reboot();
#if 0
/* check for debug activity */
show_debug_messages();

4
src/modules/px4iofirmware/px4io.h

@ -220,3 +220,7 @@ extern volatile uint8_t debug_level; @@ -220,3 +220,7 @@ extern volatile uint8_t debug_level;
/** send a debug message to the console */
extern void isr_debug(uint8_t level, const char *fmt, ...);
/** schedule a reboot */
extern void schedule_reboot(uint32_t time_delta_usec);

15
src/modules/px4iofirmware/registers.c

@ -518,16 +518,11 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value) @@ -518,16 +518,11 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
// check the magic value
if (value != PX4IO_REBOOT_BL_MAGIC)
break;
// note that we don't set BL_WAIT_MAGIC in
// BKP_DR1 as that is not necessary given the
// timing of the forceupdate command. The
// bootloader on px4io waits for enough time
// anyway, and this method works with older
// bootloader versions (tested with both
// revision 3 and revision 4).
up_systemreset();
// we schedule a reboot rather than rebooting
// immediately to allow the IO board to ACK
// the reboot command
schedule_reboot(100000);
break;
case PX4IO_P_SETUP_DSM:

50
src/systemcmds/tests/test_file.c

@ -38,6 +38,7 @@ @@ -38,6 +38,7 @@
*/
#include <sys/stat.h>
#include <poll.h>
#include <dirent.h>
#include <stdio.h>
#include <stddef.h>
@ -51,6 +52,38 @@ @@ -51,6 +52,38 @@
#include "tests.h"
int check_user_abort();
int check_user_abort() {
/* check if user wants to abort */
char c;
struct pollfd fds;
int ret;
fds.fd = 0; /* stdin */
fds.events = POLLIN;
ret = poll(&fds, 1, 0);
if (ret > 0) {
read(0, &c, 1);
switch (c) {
case 0x03: // ctrl-c
case 0x1b: // esc
case 'c':
case 'q':
{
warnx("Test aborted.");
return OK;
/* not reached */
}
}
}
return 1;
}
int
test_file(int argc, char *argv[])
{
@ -108,6 +141,9 @@ test_file(int argc, char *argv[]) @@ -108,6 +141,9 @@ test_file(int argc, char *argv[])
fsync(fd);
//perf_end(wperf);
if (!check_user_abort())
return OK;
}
end = hrt_absolute_time();
@ -142,6 +178,9 @@ test_file(int argc, char *argv[]) @@ -142,6 +178,9 @@ test_file(int argc, char *argv[])
errx(1, "ABORTING FURTHER COMPARISON DUE TO ERROR");
}
if (!check_user_abort())
return OK;
}
/*
@ -152,7 +191,7 @@ test_file(int argc, char *argv[]) @@ -152,7 +191,7 @@ test_file(int argc, char *argv[])
int ret = unlink("/fs/microsd/testfile");
fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
warnx("testing aligned writes - please wait..");
warnx("testing aligned writes - please wait.. (CTRL^C to abort)");
start = hrt_absolute_time();
for (unsigned i = 0; i < iterations; i++) {
@ -162,6 +201,9 @@ test_file(int argc, char *argv[]) @@ -162,6 +201,9 @@ test_file(int argc, char *argv[])
err(1, "WRITE ERROR!");
}
if (!check_user_abort())
return OK;
}
fsync(fd);
@ -190,6 +232,9 @@ test_file(int argc, char *argv[]) @@ -190,6 +232,9 @@ test_file(int argc, char *argv[])
align_read_ok = false;
break;
}
if (!check_user_abort())
return OK;
}
if (!align_read_ok) {
@ -228,6 +273,9 @@ test_file(int argc, char *argv[]) @@ -228,6 +273,9 @@ test_file(int argc, char *argv[])
if (unalign_read_err_count > 10)
break;
}
if (!check_user_abort())
return OK;
}
if (!unalign_read_ok) {

Loading…
Cancel
Save