aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--ROMFS/px4fmu_common/init.d/10_dji_f33056
-rw-r--r--ROMFS/px4fmu_common/init.d/11_dji_f45024
-rw-r--r--ROMFS/px4fmu_common/init.d/15_tbs_discovery24
-rw-r--r--ROMFS/px4fmu_common/init.d/16_3dr_iris24
-rw-r--r--ROMFS/px4fmu_common/init.d/666_fmu_q_x55030
-rwxr-xr-xROMFS/px4fmu_common/init.d/rcS4
-rw-r--r--nuttx-configs/px4fmu-v1/nsh/defconfig4
-rw-r--r--nuttx-configs/px4fmu-v2/nsh/defconfig8
-rw-r--r--src/drivers/ardrone_interface/ardrone_motor_control.c88
-rw-r--r--src/drivers/px4io/px4io_uploader.cpp15
-rw-r--r--src/modules/mavlink/mavlink.c2
-rw-r--r--src/modules/systemlib/mavlink_log.c2
12 files changed, 141 insertions, 140 deletions
diff --git a/ROMFS/px4fmu_common/init.d/10_dji_f330 b/ROMFS/px4fmu_common/init.d/10_dji_f330
index 743dce9ef..709e17083 100644
--- a/ROMFS/px4fmu_common/init.d/10_dji_f330
+++ b/ROMFS/px4fmu_common/init.d/10_dji_f330
@@ -10,34 +10,34 @@ then
# Set all params here, then disable autoconfig
param set SYS_AUTOCONFIG 0
- param set MC_ATTRATE_D 0.004
- param set MC_ATTRATE_I 0.0
- param set MC_ATTRATE_P 0.12
- param set MC_ATT_D 0.0
- param set MC_ATT_I 0.0
- param set MC_ATT_P 7.0
- param set MC_YAWPOS_D 0.0
- param set MC_YAWPOS_I 0.0
- param set MC_YAWPOS_P 2.0
- param set MC_YAWRATE_D 0.005
- param set MC_YAWRATE_I 0.2
- param set MC_YAWRATE_P 0.3
- param set NAV_TAKEOFF_ALT 1.0
- param set MPC_TILT_MAX 0.5
- param set MPC_THR_MAX 0.7
- param set MPC_THR_MIN 0.3
- param set MPC_XY_D 0
- param set MPC_XY_P 0.5
- param set MPC_XY_VEL_D 0
- param set MPC_XY_VEL_I 0
- param set MPC_XY_VEL_MAX 2
- param set MPC_XY_VEL_P 0.2
- param set MPC_Z_D 0
- param set MPC_Z_P 1
- param set MPC_Z_VEL_D 0
- param set MPC_Z_VEL_I 0.10
- param set MPC_Z_VEL_MAX 2
- param set MPC_Z_VEL_P 0.20
+ param set MC_ATTRATE_D 0.004
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.12
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 7.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_P 2.0
+ param set MC_YAWRATE_D 0.005
+ param set MC_YAWRATE_I 0.2
+ param set MC_YAWRATE_P 0.3
+ param set NAV_TAKEOFF_ALT 3.0
+ param set MPC_TILT_MAX 0.5
+ param set MPC_THR_MAX 0.7
+ param set MPC_THR_MIN 0.3
+ param set MPC_XY_D 0
+ param set MPC_XY_P 0.5
+ param set MPC_XY_VEL_D 0
+ param set MPC_XY_VEL_I 0
+ param set MPC_XY_VEL_MAX 2
+ param set MPC_XY_VEL_P 0.2
+ param set MPC_Z_D 0
+ param set MPC_Z_P 1
+ param set MPC_Z_VEL_D 0
+ param set MPC_Z_VEL_I 0.10
+ param set MPC_Z_VEL_MAX 2
+ param set MPC_Z_VEL_P 0.20
param save
fi
diff --git a/ROMFS/px4fmu_common/init.d/11_dji_f450 b/ROMFS/px4fmu_common/init.d/11_dji_f450
index 1827a2c11..73af1465c 100644
--- a/ROMFS/px4fmu_common/init.d/11_dji_f450
+++ b/ROMFS/px4fmu_common/init.d/11_dji_f450
@@ -10,18 +10,18 @@ then
# Set all params here, then disable autoconfig
param set SYS_AUTOCONFIG 0
- param set MC_ATTRATE_D 0.004
- param set MC_ATTRATE_I 0.0
- param set MC_ATTRATE_P 0.12
- param set MC_ATT_D 0.0
- param set MC_ATT_I 0.0
- param set MC_ATT_P 7.0
- param set MC_YAWPOS_D 0.0
- param set MC_YAWPOS_I 0.0
- param set MC_YAWPOS_P 2.0
- param set MC_YAWRATE_D 0.005
- param set MC_YAWRATE_I 0.2
- param set MC_YAWRATE_P 0.3
+ param set MC_ATTRATE_D 0.004
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.12
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 7.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.0
+ param set MC_YAWPOS_P 2.0
+ param set MC_YAWRATE_D 0.005
+ param set MC_YAWRATE_I 0.2
+ param set MC_YAWRATE_P 0.3
param save
fi
diff --git a/ROMFS/px4fmu_common/init.d/15_tbs_discovery b/ROMFS/px4fmu_common/init.d/15_tbs_discovery
index 1fcde3e27..e4b9aee34 100644
--- a/ROMFS/px4fmu_common/init.d/15_tbs_discovery
+++ b/ROMFS/px4fmu_common/init.d/15_tbs_discovery
@@ -10,18 +10,18 @@ then
# Set all params here, then disable autoconfig
param set SYS_AUTOCONFIG 0
- param set MC_ATTRATE_D 0.006
- param set MC_ATTRATE_I 0.0
- param set MC_ATTRATE_P 0.17
- param set MC_ATT_D 0.0
- param set MC_ATT_I 0.0
- param set MC_ATT_P 5.0
- param set MC_YAWPOS_D 0.0
- param set MC_YAWPOS_I 0.15
- param set MC_YAWPOS_P 0.5
- param set MC_YAWRATE_D 0.0
- param set MC_YAWRATE_I 0.0
- param set MC_YAWRATE_P 0.2
+ param set MC_ATTRATE_D 0.006
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.17
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 5.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.15
+ param set MC_YAWPOS_P 0.5
+ param set MC_YAWRATE_D 0.0
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_P 0.2
param save
fi
diff --git a/ROMFS/px4fmu_common/init.d/16_3dr_iris b/ROMFS/px4fmu_common/init.d/16_3dr_iris
index fa2cb1feb..3fbc84899 100644
--- a/ROMFS/px4fmu_common/init.d/16_3dr_iris
+++ b/ROMFS/px4fmu_common/init.d/16_3dr_iris
@@ -10,18 +10,18 @@ then
# Set all params here, then disable autoconfig
param set SYS_AUTOCONFIG 0
- param set MC_ATTRATE_D 0.006
- param set MC_ATTRATE_I 0.0
- param set MC_ATTRATE_P 0.17
- param set MC_ATT_D 0.0
- param set MC_ATT_I 0.0
- param set MC_ATT_P 5.0
- param set MC_YAWPOS_D 0.0
- param set MC_YAWPOS_I 0.15
- param set MC_YAWPOS_P 0.5
- param set MC_YAWRATE_D 0.0
- param set MC_YAWRATE_I 0.0
- param set MC_YAWRATE_P 0.2
+ param set MC_ATTRATE_D 0.006
+ param set MC_ATTRATE_I 0.0
+ param set MC_ATTRATE_P 0.17
+ param set MC_ATT_D 0.0
+ param set MC_ATT_I 0.0
+ param set MC_ATT_P 5.0
+ param set MC_YAWPOS_D 0.0
+ param set MC_YAWPOS_I 0.15
+ param set MC_YAWPOS_P 0.5
+ param set MC_YAWRATE_D 0.0
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_P 0.2
param save
fi
diff --git a/ROMFS/px4fmu_common/init.d/666_fmu_q_x550 b/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
index 938663f0c..ae41f2a01 100644
--- a/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
+++ b/ROMFS/px4fmu_common/init.d/666_fmu_q_x550
@@ -8,21 +8,21 @@ echo "[init] 666_fmu_q_x550: PX4FMU Quad X550 with PWM outputs"
if param compare SYS_AUTOCONFIG 1
then
# Set all params here, then disable autoconfig
- param set MC_ATTRATE_P 0.14
- param set MC_ATTRATE_I 0
- param set MC_ATTRATE_D 0.006
- param set MC_ATT_P 5.5
- param set MC_ATT_I 0
- param set MC_ATT_D 0
- param set MC_YAWPOS_D 0
- param set MC_YAWPOS_I 0
- param set MC_YAWPOS_P 0.6
- param set MC_YAWRATE_D 0
- param set MC_YAWRATE_I 0
- param set MC_YAWRATE_P 0.08
- param set RC_SCALE_PITCH 1
- param set RC_SCALE_ROLL 1
- param set RC_SCALE_YAW 3
+ param set MC_ATTRATE_P 0.14
+ param set MC_ATTRATE_I 0
+ param set MC_ATTRATE_D 0.006
+ param set MC_ATT_P 5.5
+ param set MC_ATT_I 0
+ param set MC_ATT_D 0
+ param set MC_YAWPOS_D 0
+ param set MC_YAWPOS_I 0
+ param set MC_YAWPOS_P 0.6
+ param set MC_YAWRATE_D 0
+ param set MC_YAWRATE_I 0
+ param set MC_YAWRATE_P 0.08
+ param set RC_SCALE_PITCH 1
+ param set RC_SCALE_ROLL 1
+ param set RC_SCALE_YAW 3
param set SYS_AUTOCONFIG 0
param save
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 8c79a035a..32fb67a45 100755
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -63,8 +63,6 @@ then
if sercon
then
echo "USB connected"
- sleep 3
- mavlink start -d /dev/ttyACM0 -b 230400
fi
#
@@ -104,7 +102,7 @@ then
fi
# Try to get an USB console
- #nshterm /dev/ttyACM0 &
+ nshterm /dev/ttyACM0 &
#
# Upgrade PX4IO firmware
diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig
index 68ab4da32..5be528f8c 100644
--- a/nuttx-configs/px4fmu-v1/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v1/nsh/defconfig
@@ -509,8 +509,8 @@ CONFIG_USART2_OFLOWCONTROL=y
#
# UART5 Configuration
#
-CONFIG_UART5_RXBUFSIZE=32
-CONFIG_UART5_TXBUFSIZE=32
+CONFIG_UART5_RXBUFSIZE=512
+CONFIG_UART5_TXBUFSIZE=512
CONFIG_UART5_BAUD=57600
CONFIG_UART5_BITS=8
CONFIG_UART5_PARITY=0
diff --git a/nuttx-configs/px4fmu-v2/nsh/defconfig b/nuttx-configs/px4fmu-v2/nsh/defconfig
index e507c89ba..0615950a2 100644
--- a/nuttx-configs/px4fmu-v2/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v2/nsh/defconfig
@@ -608,8 +608,8 @@ CONFIG_USART6_2STOP=0
#
# UART7 Configuration
#
-CONFIG_UART7_RXBUFSIZE=256
-CONFIG_UART7_TXBUFSIZE=256
+CONFIG_UART7_RXBUFSIZE=512
+CONFIG_UART7_TXBUFSIZE=512
CONFIG_UART7_BAUD=57600
CONFIG_UART7_BITS=8
CONFIG_UART7_PARITY=0
@@ -620,8 +620,8 @@ CONFIG_UART7_2STOP=0
#
# UART8 Configuration
#
-CONFIG_UART8_RXBUFSIZE=256
-CONFIG_UART8_TXBUFSIZE=256
+CONFIG_UART8_RXBUFSIZE=512
+CONFIG_UART8_TXBUFSIZE=512
CONFIG_UART8_BAUD=57600
CONFIG_UART8_BITS=8
CONFIG_UART8_PARITY=0
diff --git a/src/drivers/ardrone_interface/ardrone_motor_control.c b/src/drivers/ardrone_interface/ardrone_motor_control.c
index be8968a4e..01b89c8fa 100644
--- a/src/drivers/ardrone_interface/ardrone_motor_control.c
+++ b/src/drivers/ardrone_interface/ardrone_motor_control.c
@@ -41,6 +41,7 @@
#include <stdio.h>
#include <fcntl.h>
#include <unistd.h>
+#include <math.h>
#include <drivers/drv_gpio.h>
#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>
@@ -369,11 +370,9 @@ void ardrone_mixing_and_output(int ardrone_write, const struct actuator_controls
float yaw_control = actuators->control[2];
float motor_thrust = actuators->control[3];
- //printf("AMO: Roll: %4.4f, Pitch: %4.4f, Yaw: %4.4f, Thrust: %4.4f\n",roll_control, pitch_control, yaw_control, motor_thrust);
-
const float min_thrust = 0.02f; /**< 2% minimum thrust */
const float max_thrust = 1.0f; /**< 100% max thrust */
- const float scaling = 500.0f; /**< 100% thrust equals a value of 500 which works, 512 leads to cutoff */
+ const float scaling = 510.0f; /**< 100% thrust equals a value of 510 which works, 512 leads to cutoff */
const float min_gas = min_thrust * scaling; /**< value range sent to motors, minimum */
const float max_gas = max_thrust * scaling; /**< value range sent to motors, maximum */
@@ -382,71 +381,56 @@ void ardrone_mixing_and_output(int ardrone_write, const struct actuator_controls
float motor_calc[4] = {0};
float output_band = 0.0f;
- float band_factor = 0.75f;
const float startpoint_full_control = 0.25f; /**< start full control at 25% thrust */
- float yaw_factor = 1.0f;
static bool initialized = false;
/* publish effective outputs */
static struct actuator_controls_effective_s actuator_controls_effective;
static orb_advert_t actuator_controls_effective_pub;
- if (motor_thrust <= min_thrust) {
- motor_thrust = min_thrust;
- output_band = 0.0f;
- } else if (motor_thrust < startpoint_full_control && motor_thrust > min_thrust) {
- output_band = band_factor * (motor_thrust - min_thrust);
- } else if (motor_thrust >= startpoint_full_control && motor_thrust < max_thrust - band_factor * startpoint_full_control) {
- output_band = band_factor * startpoint_full_control;
- } else if (motor_thrust >= max_thrust - band_factor * startpoint_full_control) {
- output_band = band_factor * (max_thrust - motor_thrust);
+ /* linearly scale the control inputs from 0 to startpoint_full_control */
+ if (motor_thrust < startpoint_full_control) {
+ output_band = motor_thrust/startpoint_full_control; // linear from 0 to 1
+ } else {
+ output_band = 1.0f;
}
+ roll_control *= output_band;
+ pitch_control *= output_band;
+ yaw_control *= output_band;
+
+
//add the yaw, nick and roll components to the basic thrust //TODO:this should be done by the mixer
// FRONT (MOTOR 1)
motor_calc[0] = motor_thrust + (roll_control / 2 + pitch_control / 2 - yaw_control);
-
// RIGHT (MOTOR 2)
motor_calc[1] = motor_thrust + (-roll_control / 2 + pitch_control / 2 + yaw_control);
-
// BACK (MOTOR 3)
motor_calc[2] = motor_thrust + (-roll_control / 2 - pitch_control / 2 - yaw_control);
-
// LEFT (MOTOR 4)
motor_calc[3] = motor_thrust + (roll_control / 2 - pitch_control / 2 + yaw_control);
- // if we are not in the output band
- if (!(motor_calc[0] < motor_thrust + output_band && motor_calc[0] > motor_thrust - output_band
- && motor_calc[1] < motor_thrust + output_band && motor_calc[1] > motor_thrust - output_band
- && motor_calc[2] < motor_thrust + output_band && motor_calc[2] > motor_thrust - output_band
- && motor_calc[3] < motor_thrust + output_band && motor_calc[3] > motor_thrust - output_band)) {
+ /* if one motor is saturated, reduce throttle */
+ float saturation = fmaxf(fmaxf(motor_calc[0], motor_calc[1]),fmaxf(motor_calc[2], motor_calc[3])) - max_thrust;
+
+
+ if (saturation > 0.0f) {
+
+ /* reduce the motor thrust according to the saturation */
+ motor_thrust = motor_thrust - saturation;
- yaw_factor = 0.5f;
- yaw_control *= yaw_factor;
// FRONT (MOTOR 1)
motor_calc[0] = motor_thrust + (roll_control / 2 + pitch_control / 2 - yaw_control);
-
// RIGHT (MOTOR 2)
motor_calc[1] = motor_thrust + (-roll_control / 2 + pitch_control / 2 + yaw_control);
-
// BACK (MOTOR 3)
motor_calc[2] = motor_thrust + (-roll_control / 2 - pitch_control / 2 - yaw_control);
-
// LEFT (MOTOR 4)
motor_calc[3] = motor_thrust + (roll_control / 2 - pitch_control / 2 + yaw_control);
}
- for (int i = 0; i < 4; i++) {
- //check for limits
- if (motor_calc[i] < motor_thrust - output_band) {
- motor_calc[i] = motor_thrust - output_band;
- }
- if (motor_calc[i] > motor_thrust + output_band) {
- motor_calc[i] = motor_thrust + output_band;
- }
- }
/* publish effective outputs */
actuator_controls_effective.control_effective[0] = roll_control;
@@ -467,25 +451,29 @@ void ardrone_mixing_and_output(int ardrone_write, const struct actuator_controls
/* set the motor values */
- /* scale up from 0..1 to 10..512) */
+ /* scale up from 0..1 to 10..500) */
motor_pwm[0] = (uint16_t) (motor_calc[0] * ((float)max_gas - min_gas) + min_gas);
motor_pwm[1] = (uint16_t) (motor_calc[1] * ((float)max_gas - min_gas) + min_gas);
motor_pwm[2] = (uint16_t) (motor_calc[2] * ((float)max_gas - min_gas) + min_gas);
motor_pwm[3] = (uint16_t) (motor_calc[3] * ((float)max_gas - min_gas) + min_gas);
- /* Keep motors spinning while armed and prevent overflows */
-
- /* Failsafe logic - should never be necessary */
- motor_pwm[0] = (motor_pwm[0] > 0) ? motor_pwm[0] : 10;
- motor_pwm[1] = (motor_pwm[1] > 0) ? motor_pwm[1] : 10;
- motor_pwm[2] = (motor_pwm[2] > 0) ? motor_pwm[2] : 10;
- motor_pwm[3] = (motor_pwm[3] > 0) ? motor_pwm[3] : 10;
-
- /* Failsafe logic - should never be necessary */
- motor_pwm[0] = (motor_pwm[0] <= 511) ? motor_pwm[0] : 511;
- motor_pwm[1] = (motor_pwm[1] <= 511) ? motor_pwm[1] : 511;
- motor_pwm[2] = (motor_pwm[2] <= 511) ? motor_pwm[2] : 511;
- motor_pwm[3] = (motor_pwm[3] <= 511) ? motor_pwm[3] : 511;
+ /* scale up from 0..1 to 10..500) */
+ motor_pwm[0] = (uint16_t) (motor_calc[0] * (float)((max_gas - min_gas) + min_gas));
+ motor_pwm[1] = (uint16_t) (motor_calc[1] * (float)((max_gas - min_gas) + min_gas));
+ motor_pwm[2] = (uint16_t) (motor_calc[2] * (float)((max_gas - min_gas) + min_gas));
+ motor_pwm[3] = (uint16_t) (motor_calc[3] * (float)((max_gas - min_gas) + min_gas));
+
+ /* Failsafe logic for min values - should never be necessary */
+ motor_pwm[0] = (motor_pwm[0] > 0) ? motor_pwm[0] : min_gas;
+ motor_pwm[1] = (motor_pwm[1] > 0) ? motor_pwm[1] : min_gas;
+ motor_pwm[2] = (motor_pwm[2] > 0) ? motor_pwm[2] : min_gas;
+ motor_pwm[3] = (motor_pwm[3] > 0) ? motor_pwm[3] : min_gas;
+
+ /* Failsafe logic for max values - should never be necessary */
+ motor_pwm[0] = (motor_pwm[0] <= max_gas) ? motor_pwm[0] : max_gas;
+ motor_pwm[1] = (motor_pwm[1] <= max_gas) ? motor_pwm[1] : max_gas;
+ motor_pwm[2] = (motor_pwm[2] <= max_gas) ? motor_pwm[2] : max_gas;
+ motor_pwm[3] = (motor_pwm[3] <= max_gas) ? motor_pwm[3] : max_gas;
/* send motors via UART */
ardrone_write_motor_commands(ardrone_write, motor_pwm[0], motor_pwm[1], motor_pwm[2], motor_pwm[3]);
diff --git a/src/drivers/px4io/px4io_uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp
index 7db28ecad..fe8561a0b 100644
--- a/src/drivers/px4io/px4io_uploader.cpp
+++ b/src/drivers/px4io/px4io_uploader.cpp
@@ -110,6 +110,10 @@ PX4IO_Uploader::upload(const char *filenames[])
return -errno;
}
+ /* save initial uart configuration to reset after the update */
+ struct termios t_original;
+ tcgetattr(_io_fd, &t_original);
+
/* adjust line speed to match bootloader */
struct termios t;
tcgetattr(_io_fd, &t);
@@ -122,6 +126,7 @@ PX4IO_Uploader::upload(const char *filenames[])
if (ret != OK) {
/* this is immediately fatal */
log("bootloader not responding");
+ tcsetattr(_io_fd, TCSANOW, &t_original);
close(_io_fd);
_io_fd = -1;
return -EIO;
@@ -130,6 +135,7 @@ PX4IO_Uploader::upload(const char *filenames[])
struct stat st;
if (stat(filename, &st) != 0) {
log("Failed to stat %s - %d\n", filename, (int)errno);
+ tcsetattr(_io_fd, TCSANOW, &t_original);
close(_io_fd);
_io_fd = -1;
return -errno;
@@ -137,6 +143,7 @@ PX4IO_Uploader::upload(const char *filenames[])
fw_size = st.st_size;
if (_fw_fd == -1) {
+ tcsetattr(_io_fd, TCSANOW, &t_original);
close(_io_fd);
_io_fd = -1;
return -ENOENT;
@@ -151,6 +158,7 @@ PX4IO_Uploader::upload(const char *filenames[])
if (ret != OK) {
/* this is immediately fatal */
log("bootloader not responding");
+ tcsetattr(_io_fd, TCSANOW, &t_original);
close(_io_fd);
_io_fd = -1;
return -EIO;
@@ -164,6 +172,7 @@ PX4IO_Uploader::upload(const char *filenames[])
log("found bootloader revision: %d", bl_rev);
} else {
log("found unsupported bootloader revision %d, exiting", bl_rev);
+ tcsetattr(_io_fd, TCSANOW, &t_original);
close(_io_fd);
_io_fd = -1;
return OK;
@@ -199,6 +208,9 @@ PX4IO_Uploader::upload(const char *filenames[])
if (ret != OK) {
log("reboot failed");
+ tcsetattr(_io_fd, TCSANOW, &t_original);
+ close(_io_fd);
+ _io_fd = -1;
return ret;
}
@@ -208,6 +220,9 @@ PX4IO_Uploader::upload(const char *filenames[])
break;
}
+ /* reset uart to previous/default baudrate */
+ tcsetattr(_io_fd, TCSANOW, &t_original);
+
close(_fw_fd);
close(_io_fd);
_io_fd = -1;
diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c
index a8ca19d7a..5eb7cba9b 100644
--- a/src/modules/mavlink/mavlink.c
+++ b/src/modules/mavlink/mavlink.c
@@ -739,7 +739,7 @@ int mavlink_thread_main(int argc, char *argv[])
tcsetattr(uart, TCSANOW, &uart_config_original);
/* destroy log buffer */
- mavlink_logbuffer_destroy(&lb);
+ //mavlink_logbuffer_destroy(&lb);
thread_running = false;
diff --git a/src/modules/systemlib/mavlink_log.c b/src/modules/systemlib/mavlink_log.c
index 03ca71375..f321f9ceb 100644
--- a/src/modules/systemlib/mavlink_log.c
+++ b/src/modules/systemlib/mavlink_log.c
@@ -51,7 +51,7 @@ __EXPORT void mavlink_logbuffer_init(struct mavlink_logbuffer *lb, int size)
lb->size = size;
lb->start = 0;
lb->count = 0;
- lb->elems = (struct mavlink_logmessage *)calloc(lb->size, sizeof(struct mavlink_logmessage));
+ lb->elems = calloc(lb->size, sizeof(struct mavlink_logmessage));
}
__EXPORT void mavlink_logbuffer_destroy(struct mavlink_logbuffer *lb)