Merge branch 'master' into ram_cleanup

This commit is contained in:
Lorenz Meier 2015-10-11 16:01:15 +02:00
commit 980ddeac08
10 changed files with 38 additions and 31 deletions

View File

@ -97,6 +97,7 @@ script:
- cat build_posix_sitl_simple/src/modules/systemlib/mixer/mixer_multirotor.generated.h
- echo -en 'travis_fold:end:script.2\\r'
- echo 'Building NuttX Firmware..' && echo -en 'travis_fold:start:script.3\\r'
- make px4fmu-v1_default
- make px4fmu-v2_default
- echo -en 'travis_fold:end:script.3\\r'
- echo 'Running Tests..' && echo -en 'travis_fold:start:script.4\\r'

View File

@ -31,6 +31,14 @@
#
############################################################################
# Enforce the presence of the GIT repository
#
# We depend on our submodules, so we have to prevent attempts to
# compile without it being present.
ifeq ($(wildcard .git),)
$(error YOU HAVE TO USE GIT TO DOWNLOAD THIS REPOSITORY. ABORTING.)
endif
# Help
# --------------------------------------------------------------------
# Don't be afraid of this makefile, it is just passing

View File

@ -112,4 +112,6 @@ fi
# Wait 20 ms for sensors (because we need to wait for the HRT and work queue callbacks to fire)
usleep 20000
sensors start
if sensors start
then
fi

View File

@ -63,7 +63,6 @@ set(config_module_list
modules/navigator
modules/mavlink
modules/gpio_led
modules/uavcan
modules/land_detector
#
@ -99,6 +98,7 @@ set(config_module_list
modules/controllib
modules/uORB
modules/dataman
modules/uavcan
#
# Libraries

View File

@ -108,6 +108,7 @@ SECTIONS
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
. = ALIGN(4);
} > sram AT > flash
.bss : {

View File

@ -45,7 +45,6 @@
#include <stdint.h>
#include <stdbool.h>
#include <assert.h>
//#include <debug.h>
#include <errno.h>
#include <unistd.h>
@ -71,20 +70,16 @@ public:
virtual ~MS5611_I2C();
virtual int init();
virtual ssize_t read(device::file_t *handlep, char *data, size_t count);
virtual int ioctl(device::file_t *handlep, int cmd, unsigned long arg);
virtual int read(unsigned offset, void *data, unsigned count);
virtual int ioctl(unsigned operation, unsigned &arg);
#ifdef __PX4_NUTTX
protected:
virtual int probe();
#endif
private:
ms5611::prom_u &_prom;
#ifdef __PX4_NUTTX
int _probe_address(uint8_t address);
#endif
/**
* Send a reset command to the MS5611.
@ -116,13 +111,7 @@ MS5611_i2c_interface(ms5611::prom_u &prom_buf, uint8_t busnum)
}
MS5611_I2C::MS5611_I2C(uint8_t bus, ms5611::prom_u &prom) :
I2C("MS5611_I2C",
#ifdef __PX4_NUTTX
nullptr, bus, 0, 400000
#else
"/dev/MS5611_I2C", bus, 0
#endif
),
I2C("MS5611_I2C", nullptr, bus, 0, 400000),
_prom(prom)
{
}
@ -138,8 +127,8 @@ MS5611_I2C::init()
return I2C::init();
}
ssize_t
MS5611_I2C::read(device::file_t *handlep, char *data, size_t buflen)
int
MS5611_I2C::read(unsigned offset, void *data, unsigned count)
{
union _cvt {
uint8_t b[4];
@ -163,11 +152,11 @@ MS5611_I2C::read(device::file_t *handlep, char *data, size_t buflen)
}
int
MS5611_I2C::ioctl(device::file_t *handlep, int cmd, unsigned long arg)
MS5611_I2C::ioctl(unsigned operation, unsigned &arg)
{
int ret;
switch (cmd) {
switch (operation) {
case IOCTL_RESET:
ret = _reset();
break;
@ -183,7 +172,6 @@ MS5611_I2C::ioctl(device::file_t *handlep, int cmd, unsigned long arg)
return ret;
}
#ifdef __PX4_NUTTX
int
MS5611_I2C::probe()
{
@ -220,8 +208,6 @@ MS5611_I2C::_probe_address(uint8_t address)
return PX4_OK;
}
#endif
int
MS5611_I2C::_reset()

View File

@ -963,7 +963,7 @@ start(enum MS5611_BUS busid)
continue;
}
started |= start_bus(bus_options[i]);
started = started || start_bus(bus_options[i]);
}
if (!started) {

View File

@ -556,7 +556,7 @@ protected:
msg.errors_count2 = status.errors_count2;
msg.errors_count3 = status.errors_count3;
msg.errors_count4 = status.errors_count4;
msg.battery_remaining = (msg.voltage_battery > 0) ?
msg.battery_remaining = (status.condition_battery_voltage_valid) ?
status.battery_remaining * 100.0f : -1;
_mavlink->send_message(MAVLINK_MSG_ID_SYS_STATUS, &msg);
@ -571,14 +571,22 @@ protected:
if (i < status.battery_cell_count) {
bat_msg.voltages[i] = (status.battery_voltage / status.battery_cell_count) * 1000.0f;
} else {
bat_msg.voltages[i] = 0;
bat_msg.voltages[i] = UINT16_MAX;
}
}
bat_msg.current_battery = status.battery_current * 100.0f;
bat_msg.current_consumed = status.battery_discharged_mah;
if (status.condition_battery_voltage_valid) {
bat_msg.current_battery = (bat_msg.current_battery >= 0.0f) ?
status.battery_current * 100.0f : -1;
bat_msg.current_consumed = (bat_msg.current_consumed >= 0.0f) ?
status.battery_discharged_mah : -1;
bat_msg.battery_remaining = status.battery_remaining * 100.0f;
} else {
bat_msg.current_battery = -1.0f;
bat_msg.current_consumed = -1.0f;
bat_msg.battery_remaining = -1.0f;
}
bat_msg.energy_consumed = -1.0f;
bat_msg.battery_remaining = (status.battery_voltage > 0) ?
status.battery_remaining * 100.0f : -1;
_mavlink->send_message(MAVLINK_MSG_ID_BATTERY_STATUS, &bat_msg);
}

View File

@ -1810,7 +1810,6 @@ PARAM_DEFINE_INT32(BAT_V_SCALE_IO, 10000);
/**
* Scaling factor for battery voltage sensor on FMU v2.
*
* @board CONFIG_ARCH_BOARD_PX4FMU_V2
* @group Battery Calibration
*/
PARAM_DEFINE_FLOAT(BAT_V_SCALING, -1.0f);

View File

@ -530,8 +530,10 @@ int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate)
* If no transceiver is connected, the RX pin will float, occasionally causing CAN controller to
* fail during initialization.
*/
#ifdef GPIO_CAN1_RX
stm32_configgpio(GPIO_CAN1_RX);
stm32_configgpio(GPIO_CAN1_TX);
#endif
stm32_configgpio(GPIO_CAN2_RX | GPIO_PULLUP);
stm32_configgpio(GPIO_CAN2_TX);