aboutsummaryrefslogtreecommitdiff
path: root/src/drivers
diff options
context:
space:
mode:
authorSimon Wilks <sjwilks@gmail.com>2013-07-09 08:04:07 +0200
committerSimon Wilks <sjwilks@gmail.com>2013-07-09 08:04:07 +0200
commita18c6cea18aff92f226fdcd9da666ef1a9b6c99b (patch)
treeaa37dc3799a5a1bba8aae439da7f2fb661d5ca4f /src/drivers
parent86adaeb3e8f28c92005a38b7c71e12111efe8694 (diff)
parentced2871263d5395da84ae6d034aa18015bf66d1c (diff)
downloadpx4-firmware-a18c6cea18aff92f226fdcd9da666ef1a9b6c99b.tar.gz
px4-firmware-a18c6cea18aff92f226fdcd9da666ef1a9b6c99b.tar.bz2
px4-firmware-a18c6cea18aff92f226fdcd9da666ef1a9b6c99b.zip
Merge remote-tracking branch 'upstream/master' into hott-esc
Diffstat (limited to 'src/drivers')
-rw-r--r--src/drivers/ardrone_interface/ardrone_interface.c2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_init.c2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_internal.h2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_led.c2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_pwm_servo.c2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_spi.c2
-rw-r--r--src/drivers/boards/px4fmu/px4fmu_usb.c2
-rw-r--r--src/drivers/boards/px4io/px4io_init.c2
-rw-r--r--src/drivers/boards/px4io/px4io_internal.h2
-rw-r--r--src/drivers/boards/px4io/px4io_pwm_servo.c2
-rw-r--r--src/drivers/drv_gpio.h6
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp5
-rw-r--r--src/drivers/hil/hil.cpp2
-rw-r--r--src/drivers/hott/hott_telemetry/hott_telemetry.c2
-rw-r--r--src/drivers/hott/messages.c2
-rw-r--r--src/drivers/md25/md25_main.cpp2
-rw-r--r--src/drivers/mkblctrl/mkblctrl.cpp127
-rw-r--r--src/drivers/px4fmu/fmu.cpp2
-rw-r--r--src/drivers/px4io/uploader.cpp9
-rw-r--r--src/drivers/stm32/adc/adc.cpp2
-rw-r--r--src/drivers/stm32/drv_hrt.c6
-rw-r--r--src/drivers/stm32/drv_pwm_servo.c2
-rw-r--r--src/drivers/stm32/tone_alarm/tone_alarm.cpp2
23 files changed, 132 insertions, 57 deletions
diff --git a/src/drivers/ardrone_interface/ardrone_interface.c b/src/drivers/ardrone_interface/ardrone_interface.c
index aeaf830de..735bdb41a 100644
--- a/src/drivers/ardrone_interface/ardrone_interface.c
+++ b/src/drivers/ardrone_interface/ardrone_interface.c
@@ -114,7 +114,7 @@ int ardrone_interface_main(int argc, char *argv[])
}
thread_should_exit = false;
- ardrone_interface_task = task_spawn("ardrone_interface",
+ ardrone_interface_task = task_spawn_cmd("ardrone_interface",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 15,
2048,
diff --git a/src/drivers/boards/px4fmu/px4fmu_init.c b/src/drivers/boards/px4fmu/px4fmu_init.c
index 69edc23ab..212a92cfa 100644
--- a/src/drivers/boards/px4fmu/px4fmu_init.c
+++ b/src/drivers/boards/px4fmu/px4fmu_init.c
@@ -58,7 +58,7 @@
#include <nuttx/mmcsd.h>
#include <nuttx/analog/adc.h>
-#include "stm32_internal.h"
+#include "stm32.h"
#include "px4fmu_internal.h"
#include "stm32_uart.h"
diff --git a/src/drivers/boards/px4fmu/px4fmu_internal.h b/src/drivers/boards/px4fmu/px4fmu_internal.h
index 671a58f8f..383a046ff 100644
--- a/src/drivers/boards/px4fmu/px4fmu_internal.h
+++ b/src/drivers/boards/px4fmu/px4fmu_internal.h
@@ -50,7 +50,7 @@
__BEGIN_DECLS
/* these headers are not C++ safe */
-#include <stm32_internal.h>
+#include <stm32.h>
/****************************************************************************************************
diff --git a/src/drivers/boards/px4fmu/px4fmu_led.c b/src/drivers/boards/px4fmu/px4fmu_led.c
index 34fd194c3..31b25984e 100644
--- a/src/drivers/boards/px4fmu/px4fmu_led.c
+++ b/src/drivers/boards/px4fmu/px4fmu_led.c
@@ -41,7 +41,7 @@
#include <stdbool.h>
-#include "stm32_internal.h"
+#include "stm32.h"
#include "px4fmu_internal.h"
#include <arch/board/board.h>
diff --git a/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c b/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c
index cb8918306..d85131dd8 100644
--- a/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c
+++ b/src/drivers/boards/px4fmu/px4fmu_pwm_servo.c
@@ -46,7 +46,7 @@
#include <arch/board/board.h>
#include <drivers/drv_pwm_output.h>
-#include <stm32_internal.h>
+#include <stm32.h>
#include <stm32_gpio.h>
#include <stm32_tim.h>
diff --git a/src/drivers/boards/px4fmu/px4fmu_spi.c b/src/drivers/boards/px4fmu/px4fmu_spi.c
index b5d00eac0..e05ddecf3 100644
--- a/src/drivers/boards/px4fmu/px4fmu_spi.c
+++ b/src/drivers/boards/px4fmu/px4fmu_spi.c
@@ -52,7 +52,7 @@
#include "up_arch.h"
#include "chip.h"
-#include "stm32_internal.h"
+#include "stm32.h"
#include "px4fmu_internal.h"
/************************************************************************************
diff --git a/src/drivers/boards/px4fmu/px4fmu_usb.c b/src/drivers/boards/px4fmu/px4fmu_usb.c
index b0b669fbe..0be981c1e 100644
--- a/src/drivers/boards/px4fmu/px4fmu_usb.c
+++ b/src/drivers/boards/px4fmu/px4fmu_usb.c
@@ -52,7 +52,7 @@
#include <nuttx/usb/usbdev_trace.h>
#include "up_arch.h"
-#include "stm32_internal.h"
+#include "stm32.h"
#include "px4fmu_internal.h"
/************************************************************************************
diff --git a/src/drivers/boards/px4io/px4io_init.c b/src/drivers/boards/px4io/px4io_init.c
index d36353c6f..15c59e423 100644
--- a/src/drivers/boards/px4io/px4io_init.c
+++ b/src/drivers/boards/px4io/px4io_init.c
@@ -54,7 +54,7 @@
#include <nuttx/arch.h>
-#include "stm32_internal.h"
+#include "stm32.h"
#include "px4io_internal.h"
#include "stm32_uart.h"
diff --git a/src/drivers/boards/px4io/px4io_internal.h b/src/drivers/boards/px4io/px4io_internal.h
index eb2820bb7..6638e715e 100644
--- a/src/drivers/boards/px4io/px4io_internal.h
+++ b/src/drivers/boards/px4io/px4io_internal.h
@@ -47,7 +47,7 @@
#include <nuttx/compiler.h>
#include <stdint.h>
-#include <stm32_internal.h>
+#include <stm32.h>
/************************************************************************************
* Definitions
diff --git a/src/drivers/boards/px4io/px4io_pwm_servo.c b/src/drivers/boards/px4io/px4io_pwm_servo.c
index a2f73c429..6df470da6 100644
--- a/src/drivers/boards/px4io/px4io_pwm_servo.c
+++ b/src/drivers/boards/px4io/px4io_pwm_servo.c
@@ -46,7 +46,7 @@
#include <arch/board/board.h>
#include <drivers/drv_pwm_output.h>
-#include <stm32_internal.h>
+#include <stm32.h>
#include <stm32_gpio.h>
#include <stm32_tim.h>
diff --git a/src/drivers/drv_gpio.h b/src/drivers/drv_gpio.h
index 92d184326..7e3998fca 100644
--- a/src/drivers/drv_gpio.h
+++ b/src/drivers/drv_gpio.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -42,7 +42,7 @@
#include <sys/ioctl.h>
-#ifdef CONFIG_ARCH_BOARD_PX4FMU
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
/*
* PX4FMU GPIO numbers.
*
@@ -67,7 +67,7 @@
#endif
-#ifdef CONFIG_ARCH_BOARD_PX4IO
+#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
/*
* PX4IO GPIO numbers.
*
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index c39da98d7..b34d3fa5d 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.cpp
@@ -84,8 +84,9 @@
/**
* The Eagle Tree Airspeed V3 cannot provide accurate reading below speeds of 15km/h.
+ * You can set this value to 12 if you want a zero reading below 15km/h.
*/
-#define MIN_ACCURATE_DIFF_PRES_PA 12
+#define MIN_ACCURATE_DIFF_PRES_PA 0
/* Measurement rate is 100Hz */
#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */
@@ -463,8 +464,8 @@ ETSAirspeed::collect()
uint16_t diff_pres_pa = val[1] << 8 | val[0];
+ // XXX move the parameter read out of the driver.
param_get(param_find("SENS_DPRES_OFF"), &_diff_pres_offset);
-
if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
diff_pres_pa = 0;
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index d9aa772d4..bd027ce0b 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -224,7 +224,7 @@ HIL::init()
// gpio_reset();
/* start the HIL interface task */
- _task = task_spawn("fmuhil",
+ _task = task_spawn_cmd("fmuhil",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2048,
diff --git a/src/drivers/hott/hott_telemetry/hott_telemetry.c b/src/drivers/hott/hott_telemetry/hott_telemetry.c
index c87810b42..a88f357f6 100644
--- a/src/drivers/hott/hott_telemetry/hott_telemetry.c
+++ b/src/drivers/hott/hott_telemetry/hott_telemetry.c
@@ -255,7 +255,7 @@ hott_telemetry_main(int argc, char *argv[])
}
thread_should_exit = false;
- deamon_task = task_spawn(daemon_name,
+ deamon_task = task_spawn_cmd(daemon_name,
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 40,
2048,
diff --git a/src/drivers/hott/messages.c b/src/drivers/hott/messages.c
index ba2f6212d..36d5fe942 100644
--- a/src/drivers/hott/messages.c
+++ b/src/drivers/hott/messages.c
@@ -159,7 +159,7 @@ build_eam_response(uint8_t *buffer, size_t *size)
memset(&airspeed, 0, sizeof(airspeed));
orb_copy(ORB_ID(airspeed), airspeed_sub, &airspeed);
- uint16_t speed = (uint16_t)(airspeed.indicated_airspeed_m_s);
+ uint16_t speed = (uint16_t)(airspeed.indicated_airspeed_m_s * 3.6f);
msg.speed_L = (uint8_t)speed & 0xff;
msg.speed_H = (uint8_t)(speed >> 8) & 0xff;
diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp
index 80850e708..e62c46b0d 100644
--- a/src/drivers/md25/md25_main.cpp
+++ b/src/drivers/md25/md25_main.cpp
@@ -109,7 +109,7 @@ int md25_main(int argc, char *argv[])
}
thread_should_exit = false;
- deamon_task = task_spawn("md25",
+ deamon_task = task_spawn_cmd("md25",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 10,
2048,
diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp
index c67276f8a..e78d96569 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -74,6 +74,7 @@
#include <uORB/topics/actuator_controls.h>
#include <uORB/topics/actuator_controls_effective.h>
#include <uORB/topics/actuator_outputs.h>
+#include <uORB/topics/esc_status.h>
#include <systemlib/err.h>
@@ -87,7 +88,7 @@
#define MOTOR_STATE_PRESENT_MASK 0x80
#define MOTOR_STATE_ERROR_MASK 0x7F
#define MOTOR_SPINUP_COUNTER 2500
-
+#define ESC_UORB_PUBLISH_DELAY 200
class MK : public device::I2C
{
@@ -119,6 +120,7 @@ public:
int set_pwm_rate(unsigned rate);
int set_motor_count(unsigned count);
int set_motor_test(bool motortest);
+ int set_overrideSecurityChecks(bool overrideSecurityChecks);
int set_px4mode(int px4mode);
int set_frametype(int frametype);
unsigned int mk_check_for_blctrl(unsigned int count, bool showOutput);
@@ -136,11 +138,15 @@ private:
unsigned int _motor;
int _px4mode;
int _frametype;
+
orb_advert_t _t_outputs;
orb_advert_t _t_actuators_effective;
+ orb_advert_t _t_esc_status;
+
unsigned int _num_outputs;
bool _primary_pwm_device;
bool _motortest;
+ bool _overrideSecurityChecks;
volatile bool _task_should_exit;
bool _armed;
@@ -214,6 +220,7 @@ struct MotorData_t {
unsigned int Version; // the version of the BL (0 = old)
unsigned int SetPoint; // written by attitude controller
unsigned int SetPointLowerBits; // for higher Resolution of new BLs
+ float SetPoint_PX4; // Values from PX4
unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present
unsigned int ReadMode; // select data to read
unsigned short RawPwmValue; // length of PWM pulse
@@ -243,8 +250,10 @@ MK::MK(int bus) :
_t_armed(-1),
_t_outputs(0),
_t_actuators_effective(0),
+ _t_esc_status(0),
_num_outputs(0),
_motortest(false),
+ _overrideSecurityChecks(false),
_motor(-1),
_px4mode(MAPPING_MK),
_frametype(FRAME_PLUS),
@@ -313,7 +322,7 @@ MK::init(unsigned motors)
gpio_reset();
/* start the IO interface task */
- _task = task_spawn("mkblctrl",
+ _task = task_spawn_cmd("mkblctrl",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 20,
2048,
@@ -464,6 +473,13 @@ MK::set_motor_test(bool motortest)
return OK;
}
+int
+MK::set_overrideSecurityChecks(bool overrideSecurityChecks)
+{
+ _overrideSecurityChecks = overrideSecurityChecks;
+ return OK;
+}
+
short
MK::scaling(float val, float inMin, float inMax, float outMin, float outMax)
{
@@ -506,8 +522,6 @@ MK::task_main()
_t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1),
&outputs);
-
-
/* advertise the effective control inputs */
actuator_controls_effective_s controls_effective;
memset(&controls_effective, 0, sizeof(controls_effective));
@@ -515,6 +529,12 @@ MK::task_main()
_t_actuators_effective = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1),
&controls_effective);
+ /* advertise the blctrl status */
+ esc_status_s esc;
+ memset(&esc, 0, sizeof(esc));
+ _t_esc_status = orb_advertise(ORB_ID(esc_status), &esc);
+
+
pollfd fds[2];
fds[0].fd = _t_actuators;
@@ -602,9 +622,11 @@ MK::task_main()
}
}
- /* don't go under BLCTRL_MIN_VALUE */
- if (outputs.output[i] < BLCTRL_MIN_VALUE) {
- outputs.output[i] = BLCTRL_MIN_VALUE;
+ if(!_overrideSecurityChecks) {
+ /* don't go under BLCTRL_MIN_VALUE */
+ if (outputs.output[i] < BLCTRL_MIN_VALUE) {
+ outputs.output[i] = BLCTRL_MIN_VALUE;
+ }
}
/* output to BLCtrl's */
@@ -612,7 +634,10 @@ MK::task_main()
mk_servo_test(i);
} else {
- mk_servo_set_value(i, scaling(outputs.output[i], -1.0f, 1.0f, 0, 1024)); // scale the output to 0 - 1024 and sent to output routine
+ //mk_servo_set_value(i, scaling(outputs.output[i], -1.0f, 1.0f, 0, 1024)); // scale the output to 0 - 1024 and sent to output routine
+ // 11 Bit
+ Motor[i].SetPoint_PX4 = outputs.output[i];
+ mk_servo_set(i, scaling(outputs.output[i], -1.0f, 1.0f, 0, 2047)); // scale the output to 0 - 2047 and sent to output routine
}
}
@@ -635,8 +660,43 @@ MK::task_main()
}
+
+ /*
+ * Only update esc topic every half second.
+ */
+
+ if (hrt_absolute_time() - esc.timestamp > 500000) {
+ esc.counter++;
+ esc.timestamp = hrt_absolute_time();
+ esc.esc_count = (uint8_t) _num_outputs;
+ esc.esc_connectiontype = ESC_CONNECTION_TYPE_I2C;
+
+ for (unsigned int i = 0; i < _num_outputs; i++) {
+ esc.esc[i].esc_address = (uint8_t) BLCTRL_BASE_ADDR + i;
+ esc.esc[i].esc_vendor = ESC_VENDOR_MIKROKOPTER;
+ esc.esc[i].esc_version = (uint16_t) Motor[i].Version;
+ esc.esc[i].esc_voltage = (uint16_t) 0;
+ esc.esc[i].esc_current = (uint16_t) Motor[i].Current;
+ esc.esc[i].esc_rpm = (uint16_t) 0;
+ esc.esc[i].esc_setpoint = (float) Motor[i].SetPoint_PX4;
+ if (Motor[i].Version == 1) {
+ // BLCtrl 2.0 (11Bit)
+ esc.esc[i].esc_setpoint_raw = (uint16_t) (Motor[i].SetPoint<<3) | Motor[i].SetPointLowerBits;
+ } else {
+ // BLCtrl < 2.0 (8Bit)
+ esc.esc[i].esc_setpoint_raw = (uint16_t) Motor[i].SetPoint;
+ }
+ esc.esc[i].esc_temperature = (uint16_t) Motor[i].Temperature;
+ esc.esc[i].esc_state = (uint16_t) Motor[i].State;
+ esc.esc[i].esc_errorcount = (uint16_t) 0;
+ }
+
+ orb_publish(ORB_ID(esc_status), _t_esc_status, &esc);
+ }
+
}
+ //::close(_t_esc_status);
::close(_t_actuators);
::close(_t_actuators_effective);
::close(_t_armed);
@@ -715,17 +775,17 @@ MK::mk_check_for_blctrl(unsigned int count, bool showOutput)
fprintf(stderr, "[mkblctrl] blctrl[%i] : found=%i\tversion=%i\tcurrent=%i\tmaxpwm=%i\ttemperature=%i\n", i, Motor[i].State, Motor[i].Version, Motor[i].Current, Motor[i].MaxPWM, Motor[i].Temperature);
}
- if (foundMotorCount != 4 && foundMotorCount != 6 && foundMotorCount != 8) {
- _task_should_exit = true;
+
+ if(!_overrideSecurityChecks) {
+ if (foundMotorCount != 4 && foundMotorCount != 6 && foundMotorCount != 8) {
+ _task_should_exit = true;
+ }
}
}
return foundMotorCount;
}
-
-
-
int
MK::mk_servo_set(unsigned int chan, short val)
{
@@ -738,17 +798,15 @@ MK::mk_servo_set(unsigned int chan, short val)
tmpVal = val;
- if (tmpVal > 1024) {
- tmpVal = 1024;
+ if (tmpVal > 2047) {
+ tmpVal = 2047;
} else if (tmpVal < 0) {
tmpVal = 0;
}
- Motor[chan].SetPoint = (uint8_t)(tmpVal / 4);
- //Motor[chan].SetPointLowerBits = (uint8_t) tmpVal % 4;
-
- Motor[chan].SetPointLowerBits = 0;
+ Motor[chan].SetPoint = (uint8_t)(tmpVal>>3)&0xff;
+ Motor[chan].SetPointLowerBits = ((uint8_t)tmpVal%8)&0x07;
if (_armed == false) {
Motor[chan].SetPoint = 0;
@@ -1014,8 +1072,7 @@ MK::pwm_ioctl(file *filp, int cmd, unsigned long arg)
case PWM_SERVO_SET(0) ... PWM_SERVO_SET(_max_actuators - 1):
if (arg < 2150) {
Motor[cmd - PWM_SERVO_SET(0)].RawPwmValue = (unsigned short)arg;
- mk_servo_set_value(cmd - PWM_SERVO_SET(0), scaling(arg, 1010, 2100, 0, 1024));
-
+ mk_servo_set(cmd - PWM_SERVO_SET(0), scaling(arg, 1010, 2100, 0, 2047));
} else {
ret = -EINVAL;
}
@@ -1112,25 +1169,19 @@ ssize_t
MK::write(file *filp, const char *buffer, size_t len)
{
unsigned count = len / 2;
- // loeschen uint16_t values[4];
uint16_t values[8];
- // loeschen if (count > 4) {
- // loeschen // we only have 4 PWM outputs on the FMU
- // loeschen count = 4;
- // loeschen }
if (count > _num_outputs) {
// we only have 8 I2C outputs in the driver
count = _num_outputs;
}
-
// allow for misaligned values
memcpy(values, buffer, count * 2);
for (uint8_t i = 0; i < count; i++) {
Motor[i].RawPwmValue = (unsigned short)values[i];
- mk_servo_set_value(i, scaling(values[i], 1010, 2100, 0, 1024));
+ mk_servo_set(i, scaling(values[i], 1010, 2100, 0, 2047));
}
return count * 2;
@@ -1282,7 +1333,7 @@ enum FrameType {
PortMode g_port_mode;
int
-mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, int px4mode, int frametype)
+mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, int px4mode, int frametype, bool overrideSecurityChecks)
{
uint32_t gpio_bits;
int shouldStop = 0;
@@ -1341,6 +1392,9 @@ mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest,
/* motortest if enabled */
g_mk->set_motor_test(motortest);
+ /* ovveride security checks if enabled */
+ g_mk->set_overrideSecurityChecks(overrideSecurityChecks);
+
/* count used motors */
do {
@@ -1406,6 +1460,7 @@ mkblctrl_main(int argc, char *argv[])
int px4mode = MAPPING_PX4;
int frametype = FRAME_PLUS; // + plus is default
bool motortest = false;
+ bool overrideSecurityChecks = false;
bool showHelp = false;
bool newMode = false;
@@ -1461,11 +1516,21 @@ mkblctrl_main(int argc, char *argv[])
showHelp = true;
}
+ /* look for the optional --override-security-checks parameter */
+ if (strcmp(argv[i], "--override-security-checks") == 0) {
+ overrideSecurityChecks = true;
+ newMode = true;
+ }
+
}
if (showHelp) {
fprintf(stderr, "mkblctrl: help:\n");
- fprintf(stderr, " [-mkmode frame{+/x}] [-b i2c_bus_number] [-t motortest] [-h / --help]\n");
+ fprintf(stderr, " [-mkmode frame{+/x}] [-b i2c_bus_number] [-t motortest] [--override-security-checks] [-h / --help]\n\n");
+ fprintf(stderr, "\t -mkmode frame {+/x} \t\t Type of frame, if Mikrokopter motor order is used.\n");
+ fprintf(stderr, "\t -b i2c_bus_number \t\t Set the i2c bus where the ESCs are connected to (default 1).\n");
+ fprintf(stderr, "\t -t motortest \t\t\t Spin up once every motor in order of motoraddress. (DANGER !!!)\n");
+ fprintf(stderr, "\t --override-security-checks \t\t Disable all security checks (arming and number of ESCs). Used to test single Motors etc. (DANGER !!!)\n");
exit(1);
}
@@ -1483,7 +1548,7 @@ mkblctrl_main(int argc, char *argv[])
/* parameter set ? */
if (newMode) {
/* switch parameter */
- return mk_new_mode(port_mode, pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype);
+ return mk_new_mode(port_mode, pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype, overrideSecurityChecks);
}
/* test, etc. here g*/
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index bf72892eb..5147ac500 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -239,7 +239,7 @@ PX4FMU::init()
gpio_reset();
/* start the IO interface task */
- _task = task_spawn("fmuservo",
+ _task = task_spawn_cmd("fmuservo",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
2048,
diff --git a/src/drivers/px4io/uploader.cpp b/src/drivers/px4io/uploader.cpp
index 15524c3ae..9e3f041e3 100644
--- a/src/drivers/px4io/uploader.cpp
+++ b/src/drivers/px4io/uploader.cpp
@@ -49,6 +49,7 @@
#include <unistd.h>
#include <fcntl.h>
#include <poll.h>
+#include <termios.h>
#include <sys/stat.h>
#include "uploader.h"
@@ -121,6 +122,12 @@ PX4IO_Uploader::upload(const char *filenames[])
return -errno;
}
+ /* adjust line speed to match bootloader */
+ struct termios t;
+ tcgetattr(_io_fd, &t);
+ cfsetspeed(&t, 115200);
+ tcsetattr(_io_fd, TCSANOW, &t);
+
/* look for the bootloader */
ret = sync();
@@ -251,7 +258,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;
}
diff --git a/src/drivers/stm32/adc/adc.cpp b/src/drivers/stm32/adc/adc.cpp
index 911def943..1020eb946 100644
--- a/src/drivers/stm32/adc/adc.cpp
+++ b/src/drivers/stm32/adc/adc.cpp
@@ -58,7 +58,7 @@
#include <drivers/drv_adc.h>
#include <arch/stm32/chip.h>
-#include <stm32_internal.h>
+#include <stm32.h>
#include <stm32_gpio.h>
#include <systemlib/err.h>
diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c
index fd63681e3..7ef3db970 100644
--- a/src/drivers/stm32/drv_hrt.c
+++ b/src/drivers/stm32/drv_hrt.c
@@ -66,7 +66,7 @@
#include "up_internal.h"
#include "up_arch.h"
-#include "stm32_internal.h"
+#include "stm32.h"
#include "stm32_gpio.h"
#include "stm32_tim.h"
@@ -278,8 +278,10 @@ static void hrt_call_invoke(void);
#ifdef CONFIG_HRT_PPM
/*
* If the timer hardware doesn't support GTIM_CCER_CCxNP, then we will work around it.
+ *
+ * Note that we assume that M3 means STM32F1 (since we don't really care about the F2).
*/
-# ifndef GTIM_CCER_CC1NP
+# ifdef CONFIG_ARCH_CORTEXM3
# define GTIM_CCER_CC1NP 0
# define GTIM_CCER_CC2NP 0
# define GTIM_CCER_CC3NP 0
diff --git a/src/drivers/stm32/drv_pwm_servo.c b/src/drivers/stm32/drv_pwm_servo.c
index c1efb8515..7b060412c 100644
--- a/src/drivers/stm32/drv_pwm_servo.c
+++ b/src/drivers/stm32/drv_pwm_servo.c
@@ -64,7 +64,7 @@
#include <up_internal.h>
#include <up_arch.h>
-#include <stm32_internal.h>
+#include <stm32.h>
#include <stm32_gpio.h>
#include <stm32_tim.h>
diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
index ac5511e60..167ef30a8 100644
--- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp
+++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
@@ -111,7 +111,7 @@
#include <up_internal.h>
#include <up_arch.h>
-#include <stm32_internal.h>
+#include <stm32.h>
#include <stm32_gpio.h>
#include <stm32_tim.h>