Merge branch 'master' into cmake-2

This commit is contained in:
James Goppert 2015-09-10 14:03:48 -04:00
commit 181d8db128
3 changed files with 11 additions and 5 deletions

View File

@ -551,8 +551,8 @@ CONFIG_UART7_SERIAL_CONSOLE=y
#
# USART1 Configuration
#
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_TXBUFSIZE=600
CONFIG_USART1_RXBUFSIZE=128
CONFIG_USART1_TXBUFSIZE=32
CONFIG_USART1_BAUD=115200
CONFIG_USART1_BITS=8
CONFIG_USART1_PARITY=0

View File

@ -113,6 +113,10 @@ LidarLite * get_dev(const bool use_i2c, const int bus) {
*/
void start(const bool use_i2c, const int bus)
{
if (g_dev_int != nullptr || g_dev_ext != nullptr || g_dev_pwm != nullptr) {
errx(1,"driver already started");
}
if (use_i2c) {
/* create the driver, attempt expansion bus first */
if (bus == -1 || bus == PX4_I2C_BUS_EXPANSION) {
@ -464,7 +468,6 @@ ll40ls_main(int argc, char *argv[])
/* Start/load the driver. */
if (!strcmp(verb, "start")) {
ll40ls::start(use_i2c, bus);
}

View File

@ -1642,7 +1642,8 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("GPS_RAW_INT", 1.0f);
configure_stream("GLOBAL_POSITION_INT", 3.0f);
configure_stream("LOCAL_POSITION_NED", 3.0f);
configure_stream("RC_CHANNELS", 4.0f);
configure_stream("RC_CHANNELS", 1.0f);
configure_stream("SERVO_OUTPUT_RAW_0", 1.0f);
configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f);
configure_stream("ATTITUDE_TARGET", 8.0f);
configure_stream("DISTANCE_SENSOR", 0.5f);
@ -1664,6 +1665,7 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("DISTANCE_SENSOR", 10.0f);
configure_stream("OPTICAL_FLOW_RAD", 10.0f);
configure_stream("RC_CHANNELS", 20.0f);
configure_stream("SERVO_OUTPUT_RAW_0", 10.0f);
configure_stream("VFR_HUD", 10.0f);
configure_stream("SYSTEM_TIME", 1.0f);
configure_stream("TIMESYNC", 10.0f);
@ -1683,6 +1685,7 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("BATTERY_STATUS", 1.0f);
configure_stream("SYSTEM_TIME", 1.0f);
configure_stream("RC_CHANNELS", 5.0f);
configure_stream("SERVO_OUTPUT_RAW_0", 1.0f);
configure_stream("VTOL_STATE", 0.5f);
break;
@ -1696,7 +1699,7 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("VFR_HUD", 20.0f);
configure_stream("ATTITUDE", 100.0f);
configure_stream("ACTUATOR_CONTROL_TARGET0", 30.0f);
configure_stream("RC_CHANNELS_RAW", 5.0f);
configure_stream("RC_CHANNELS", 5.0f);
configure_stream("SERVO_OUTPUT_RAW_0", 20.0f);
configure_stream("SERVO_OUTPUT_RAW_1", 20.0f);
configure_stream("POSITION_TARGET_GLOBAL_INT", 10.0f);