aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rwxr-xr-xTools/px_uploader.py4
-rw-r--r--makefiles/config_px4fmu-v1_default.mk5
-rw-r--r--makefiles/config_px4fmu-v2_default.mk6
-rw-r--r--src/drivers/drv_pwm_output.h1
-rw-r--r--src/drivers/px4io/px4io.cpp668
-rw-r--r--src/modules/att_pos_estimator_ekf/KalmanNav.hpp26
-rw-r--r--src/modules/commander/commander.cpp22
-rw-r--r--src/modules/commander/state_machine_helper.cpp1
-rw-r--r--src/modules/controllib/block/BlockParam.hpp29
-rw-r--r--src/modules/controllib/blocks.hpp36
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp72
-rw-r--r--src/modules/mavlink/orb_listener.c2
-rw-r--r--src/modules/mavlink_onboard/mavlink.c20
-rw-r--r--src/modules/mavlink_onboard/mavlink_receiver.c94
-rw-r--r--src/modules/multirotor_att_control/multirotor_att_control_main.c397
-rw-r--r--src/modules/px4iofirmware/dsm.c2
-rw-r--r--src/modules/sensors/sensors.cpp239
-rw-r--r--src/modules/uORB/topics/vehicle_control_mode.h1
18 files changed, 920 insertions, 705 deletions
diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py
index 64af672a3..a2d7d371d 100755
--- a/Tools/px_uploader.py
+++ b/Tools/px_uploader.py
@@ -430,7 +430,7 @@ while True:
# Windows, don't open POSIX ports
if not "/" in port:
up = uploader(port, args.baud)
- except:
+ except Exception:
# open failed, rate-limit our attempts
time.sleep(0.05)
@@ -443,7 +443,7 @@ while True:
up.identify()
print("Found board %x,%x bootloader rev %x on %s" % (up.board_type, up.board_rev, up.bl_rev, port))
- except:
+ except Exception:
# most probably a timeout talking to the port, no bootloader, try to reboot the board
print("attempting reboot on %s..." % port)
up.send_reboot()
diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk
index 1dd949076..46640f3c5 100644
--- a/makefiles/config_px4fmu-v1_default.mk
+++ b/makefiles/config_px4fmu-v1_default.mk
@@ -134,7 +134,10 @@ MODULES += lib/geo
# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control
-MODULES += examples/fixedwing_control
+#MODULES += examples/fixedwing_control
+
+# Hardware test
+#MODULES += examples/hwtest
#
# Transitional support - add commands from the NuttX export archive.
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index 66216f8fe..bb589cb9f 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -128,8 +128,12 @@ MODULES += lib/geo
# https://pixhawk.ethz.ch/px4/dev/debug_values
#MODULES += examples/px4_mavlink_debug
+# Tutorial code from
+# https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control
+#MODULES += examples/fixedwing_control
+
# Hardware test
-MODULES += examples/hwtest
+#MODULES += examples/hwtest
#
# Transitional support - add commands from the NuttX export archive.
diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h
index 94e923d71..fc96bd848 100644
--- a/src/drivers/drv_pwm_output.h
+++ b/src/drivers/drv_pwm_output.h
@@ -120,6 +120,7 @@ ORB_DECLARE(output_pwm);
#define DSM2_BIND_PULSES 3 /* DSM_BIND_START ioctl parameter, pulses required to start dsm2 pairing */
#define DSMX_BIND_PULSES 7 /* DSM_BIND_START ioctl parameter, pulses required to start dsmx pairing */
+#define DSMX8_BIND_PULSES 10 /* DSM_BIND_START ioctl parameter, pulses required to start 8 or more channel dsmx pairing */
/** Power up DSM receiver */
#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 8)
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index f6d4f1ed4..aec118705 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -82,6 +82,7 @@
#include <uORB/topics/battery_status.h>
#include <uORB/topics/servorail_status.h>
#include <uORB/topics/parameter_update.h>
+
#include <debug.h>
#include <mavlink/mavlink_log.h>
@@ -95,7 +96,9 @@ extern device::Device *PX4IO_serial_interface() weak_function;
#define PX4IO_SET_DEBUG _IOC(0xff00, 0)
#define PX4IO_INAIR_RESTART_ENABLE _IOC(0xff00, 1)
-#define UPDATE_INTERVAL_MIN 2
+#define UPDATE_INTERVAL_MIN 2 // 2 ms -> 500 Hz
+#define ORB_CHECK_INTERVAL 200000 // 200 ms -> 5 Hz
+#define IO_POLL_INTERVAL 20000 // 20 ms -> 50 Hz
/**
* The PX4IO class.
@@ -107,35 +110,35 @@ class PX4IO : public device::CDev
public:
/**
* Constructor.
- *
+ *
* Initialize all class variables.
*/
PX4IO(device::Device *interface);
/**
* Destructor.
- *
+ *
* Wait for worker thread to terminate.
*/
virtual ~PX4IO();
/**
* Initialize the PX4IO class.
- *
+ *
* Retrieve relevant initial system parameters. Initialize PX4IO registers.
*/
virtual int init();
/**
* Detect if a PX4IO is connected.
- *
+ *
* Only validate if there is a PX4IO to talk to.
*/
virtual int detect();
/**
* IO Control handler.
- *
+ *
* Handle all IOCTL calls to the PX4IO file descriptor.
*
* @param[in] filp file handle (not used). This function is always called directly through object reference
@@ -146,7 +149,7 @@ public:
/**
* write handler.
- *
+ *
* Handle writes to the PX4IO file descriptor.
*
* @param[in] filp file handle (not used). This function is always called directly through object reference
@@ -218,8 +221,7 @@ public:
*
* @param[in] enable true=DSM satellite VCC is controlled by relay1, false=DSM satellite VCC not controlled
*/
- inline void set_dsm_vcc_ctl(bool enable)
- {
+ inline void set_dsm_vcc_ctl(bool enable) {
_dsm_vcc_ctl = enable;
};
@@ -228,8 +230,7 @@ public:
*
* @return true=DSM satellite VCC is controlled by relay1, false=DSM satellite VCC not controlled
*/
- inline bool get_dsm_vcc_ctl()
- {
+ inline bool get_dsm_vcc_ctl() {
return _dsm_vcc_ctl;
};
#endif
@@ -406,7 +407,7 @@ private:
/**
* Send mixer definition text to IO
*/
- int mixer_send(const char *buf, unsigned buflen, unsigned retries=3);
+ int mixer_send(const char *buf, unsigned buflen, unsigned retries = 3);
/**
* Handle a status update from IO.
@@ -452,7 +453,7 @@ private:
* @param vrssi vrssi register
*/
void io_handle_vservo(uint16_t vbatt, uint16_t ibatt);
-
+
};
namespace
@@ -492,12 +493,12 @@ PX4IO::PX4IO(device::Device *interface) :
_to_servorail(0),
_to_safety(0),
_primary_pwm_device(false),
- _battery_amp_per_volt(90.0f/5.0f), // this matches the 3DR current sensor
+ _battery_amp_per_volt(90.0f / 5.0f), // this matches the 3DR current sensor
_battery_amp_bias(0),
_battery_mamphour_total(0),
_battery_last_timestamp(0)
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
- ,_dsm_vcc_ctl(false)
+ , _dsm_vcc_ctl(false)
#endif
{
@@ -540,19 +541,22 @@ PX4IO::detect()
/* do regular cdev init */
ret = CDev::init();
+
if (ret != OK)
return ret;
/* get some parameters */
unsigned protocol = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_PROTOCOL_VERSION);
+
if (protocol != PX4IO_PROTOCOL_VERSION) {
if (protocol == _io_reg_get_error) {
log("IO not installed");
+
} else {
log("IO version error");
mavlink_log_emergency(_mavlink_fd, "IO VERSION MISMATCH, PLEASE UPGRADE SOFTWARE!");
}
-
+
return -1;
}
}
@@ -571,22 +575,26 @@ PX4IO::init()
/* do regular cdev init */
ret = CDev::init();
+
if (ret != OK)
return ret;
/* get some parameters */
unsigned protocol = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_PROTOCOL_VERSION);
+
if (protocol != PX4IO_PROTOCOL_VERSION) {
log("protocol/firmware mismatch");
mavlink_log_emergency(_mavlink_fd, "[IO] protocol/firmware mismatch, abort.");
return -1;
}
+
_hardware = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_HARDWARE_VERSION);
_max_actuators = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_ACTUATOR_COUNT);
_max_controls = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_CONTROL_COUNT);
_max_relays = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_RELAY_COUNT);
_max_transfer = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_MAX_TRANSFER) - 2;
_max_rc_input = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_RC_INPUT_COUNT);
+
if ((_max_actuators < 1) || (_max_actuators > 255) ||
(_max_relays > 32) ||
(_max_transfer < 16) || (_max_transfer > 255) ||
@@ -596,6 +604,7 @@ PX4IO::init()
mavlink_log_emergency(_mavlink_fd, "[IO] config read fail, abort.");
return -1;
}
+
if (_max_rc_input > RC_INPUT_MAX_CHANNELS)
_max_rc_input = RC_INPUT_MAX_CHANNELS;
@@ -610,6 +619,7 @@ PX4IO::init()
/* get IO's last seen FMU state */
ret = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, &reg, sizeof(reg));
+
if (ret != OK)
return ret;
@@ -623,8 +633,8 @@ PX4IO::init()
/* get a status update from IO */
io_get_status();
- mavlink_log_emergency(_mavlink_fd, "[IO] RECOVERING FROM FMU IN-AIR RESTART");
- log("INAIR RESTART RECOVERY (needs commander app running)");
+ mavlink_log_emergency(_mavlink_fd, "[IO] RECOVERING FROM FMU IN-AIR RESTART");
+ log("INAIR RESTART RECOVERY (needs commander app running)");
/* WARNING: COMMANDER app/vehicle status must be initialized.
* If this fails (or the app is not started), worst-case IO
@@ -636,7 +646,7 @@ PX4IO::init()
struct actuator_armed_s safety;
uint64_t try_start_time = hrt_absolute_time();
bool updated = false;
-
+
/* keep checking for an update, ensure we got a arming information,
not something that was published a long time ago. */
do {
@@ -652,7 +662,7 @@ PX4IO::init()
usleep(10000);
/* abort after 5s */
- if ((hrt_absolute_time() - try_start_time)/1000 > 3000) {
+ if ((hrt_absolute_time() - try_start_time) / 1000 > 3000) {
log("failed to recover from in-air restart (1), aborting IO driver init.");
return 1;
}
@@ -692,7 +702,7 @@ PX4IO::init()
usleep(50000);
/* abort after 5s */
- if ((hrt_absolute_time() - try_start_time)/1000 > 2000) {
+ if ((hrt_absolute_time() - try_start_time) / 1000 > 2000) {
log("failed to recover from in-air restart (2), aborting IO driver init.");
return 1;
}
@@ -703,25 +713,27 @@ PX4IO::init()
log("re-sending arm cmd");
}
- /* keep waiting for state change for 2 s */
+ /* keep waiting for state change for 2 s */
} while (!safety.armed);
- /* regular boot, no in-air restart, init IO */
- } else {
+ /* regular boot, no in-air restart, init IO */
+ } else {
/* dis-arm IO before touching anything */
- io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING,
- PX4IO_P_SETUP_ARMING_FMU_ARMED |
- PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK |
- PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK |
- PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE, 0);
+ io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING,
+ PX4IO_P_SETUP_ARMING_FMU_ARMED |
+ PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK |
+ PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK |
+ PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE, 0);
if (_rc_handling_disabled) {
ret = io_disable_rc_handling();
+
} else {
/* publish RC config to IO */
ret = io_set_rc_config();
+
if (ret != OK) {
log("failed to update RC input config");
mavlink_log_info(_mavlink_fd, "[IO] RC config upload fail");
@@ -761,7 +773,8 @@ PX4IO::task_main_trampoline(int argc, char *argv[])
void
PX4IO::task_main()
{
- hrt_abstime last_poll_time = 0;
+ hrt_abstime poll_last = 0;
+ hrt_abstime orb_check_last = 0;
log("starting");
@@ -774,40 +787,24 @@ PX4IO::task_main()
_t_actuators = orb_subscribe(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
ORB_ID(actuator_controls_1));
orb_set_interval(_t_actuators, 20); /* default to 50Hz */
-
_t_actuator_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_actuator_armed, 200); /* 5Hz update rate */
-
_t_vehicle_control_mode = orb_subscribe(ORB_ID(vehicle_control_mode));
- orb_set_interval(_t_vehicle_control_mode, 200); /* 5Hz update rate max. */
-
_t_param = orb_subscribe(ORB_ID(parameter_update));
- orb_set_interval(_t_param, 500); /* 2Hz update rate max. */
-
_t_vehicle_command = orb_subscribe(ORB_ID(vehicle_command));
- orb_set_interval(_t_param, 1000); /* 1Hz update rate max. */
if ((_t_actuators < 0) ||
- (_t_actuator_armed < 0) ||
- (_t_vehicle_control_mode < 0) ||
- (_t_param < 0) ||
- (_t_vehicle_command < 0)) {
+ (_t_actuator_armed < 0) ||
+ (_t_vehicle_control_mode < 0) ||
+ (_t_param < 0) ||
+ (_t_vehicle_command < 0)) {
log("subscription(s) failed");
goto out;
}
/* poll descriptor */
- pollfd fds[5];
+ pollfd fds[1];
fds[0].fd = _t_actuators;
fds[0].events = POLLIN;
- fds[1].fd = _t_actuator_armed;
- fds[1].events = POLLIN;
- fds[2].fd = _t_vehicle_control_mode;
- fds[2].events = POLLIN;
- fds[3].fd = _t_param;
- fds[3].events = POLLIN;
- fds[4].fd = _t_vehicle_command;
- fds[4].events = POLLIN;
log("ready");
@@ -821,15 +818,17 @@ PX4IO::task_main()
if (_update_interval != 0) {
if (_update_interval < UPDATE_INTERVAL_MIN)
_update_interval = UPDATE_INTERVAL_MIN;
+
if (_update_interval > 100)
_update_interval = 100;
+
orb_set_interval(_t_actuators, _update_interval);
_update_interval = 0;
}
/* sleep waiting for topic updates, but no more than 20ms */
unlock();
- int ret = ::poll(&fds[0], sizeof(fds) / sizeof(fds[0]), 20);
+ int ret = ::poll(fds, 1, 20);
lock();
/* this would be bad... */
@@ -842,68 +841,79 @@ PX4IO::task_main()
hrt_abstime now = hrt_absolute_time();
/* if we have new control data from the ORB, handle it */
- if (fds[0].revents & POLLIN)
+ if (fds[0].revents & POLLIN) {
io_set_control_state();
-
- /* if we have an arming state update, handle it */
- if ((fds[1].revents & POLLIN) || (fds[2].revents & POLLIN))
- io_set_arming_state();
-
- /* if we have a vehicle command, handle it */
- if (fds[4].revents & POLLIN) {
- struct vehicle_command_s cmd;
- orb_copy(ORB_ID(vehicle_command), _t_vehicle_command, &cmd);
- // Check for a DSM pairing command
- if ((cmd.command == VEHICLE_CMD_START_RX_PAIR) && (cmd.param1== 0.0f)) {
- dsm_bind_ioctl((int)cmd.param2);
- }
}
- /*
- * If it's time for another tick of the polling status machine,
- * try it now.
- */
- if ((now - last_poll_time) >= 20000) {
+ if (now >= poll_last + IO_POLL_INTERVAL) {
+ /* run at 50Hz */
+ poll_last = now;
- /*
- * Pull status and alarms from IO.
- */
+ /* pull status and alarms from IO */
io_get_status();
- /*
- * Get raw R/C input from IO.
- */
+ /* get raw R/C input from IO */
io_publish_raw_rc();
- /*
- * Fetch mixed servo controls and PWM outputs from IO.
- *
- * XXX We could do this at a reduced rate in many/most cases.
- */
+ /* fetch mixed servo controls and PWM outputs from IO */
io_publish_mixed_controls();
io_publish_pwm_outputs();
+ }
+
+ if (now >= orb_check_last + ORB_CHECK_INTERVAL) {
+ /* run at 5Hz */
+ orb_check_last = now;
+
+ /* check updates on uORB topics and handle it */
+ bool updated = false;
+
+ /* arming state */
+ orb_check(_t_actuator_armed, &updated);
+
+ if (!updated) {
+ orb_check(_t_vehicle_control_mode, &updated);
+ }
+
+ if (updated) {
+ io_set_arming_state();
+ }
+
+ /* vehicle command */
+ orb_check(_t_vehicle_command, &updated);
+
+ if (updated) {
+ struct vehicle_command_s cmd;
+ orb_copy(ORB_ID(vehicle_command), _t_vehicle_command, &cmd);
+
+ // Check for a DSM pairing command
+ if ((cmd.command == VEHICLE_CMD_START_RX_PAIR) && (cmd.param1 == 0.0f)) {
+ dsm_bind_ioctl((int)cmd.param2);
+ }
+ }
/*
* If parameters have changed, re-send RC mappings to IO
*
* XXX this may be a bit spammy
*/
- if (fds[3].revents & POLLIN) {
+ orb_check(_t_param, &updated);
+
+ if (updated) {
parameter_update_s pupdate;
+ orb_copy(ORB_ID(parameter_update), _t_param, &pupdate);
+
int32_t dsm_bind_val;
param_t dsm_bind_param;
- // See if bind parameter has been set, and reset it to -1
+ /* see if bind parameter has been set, and reset it to -1 */
param_get(dsm_bind_param = param_find("RC_DSM_BIND"), &dsm_bind_val);
+
if (dsm_bind_val > -1) {
dsm_bind_ioctl(dsm_bind_val);
dsm_bind_val = -1;
param_set(dsm_bind_param, &dsm_bind_val);
}
- /* copy to reset the notification */
- orb_copy(ORB_ID(parameter_update), _t_param, &pupdate);
-
/* re-upload RC input config as it may have changed */
io_set_rc_config();
}
@@ -934,7 +944,7 @@ PX4IO::io_set_control_state()
/* get controls */
orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
- ORB_ID(actuator_controls_1), _t_actuators, &controls);
+ ORB_ID(actuator_controls_1), _t_actuators, &controls);
for (unsigned i = 0; i < _max_controls; i++)
regs[i] = FLOAT_TO_REG(controls.control[i]);
@@ -1007,17 +1017,21 @@ PX4IO::io_set_arming_state()
if (armed.armed && !armed.lockdown) {
set |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
+
} else {
clear |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
}
+
if (armed.ready_to_arm) {
set |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
+
} else {
clear |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
}
if (control_mode.flag_external_manual_override_ok) {
set |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
+
} else {
clear |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
}
@@ -1062,22 +1076,27 @@ PX4IO::io_set_rc_config()
* autopilots / GCS'.
*/
param_get(param_find("RC_MAP_ROLL"), &ichan);
+
if ((ichan >= 0) && (ichan < (int)_max_rc_input))
input_map[ichan - 1] = 0;
param_get(param_find("RC_MAP_PITCH"), &ichan);
+
if ((ichan >= 0) && (ichan < (int)_max_rc_input))
input_map[ichan - 1] = 1;
param_get(param_find("RC_MAP_YAW"), &ichan);
+
if ((ichan >= 0) && (ichan < (int)_max_rc_input))
input_map[ichan - 1] = 2;
param_get(param_find("RC_MAP_THROTTLE"), &ichan);
+
if ((ichan >= 0) && (ichan < (int)_max_rc_input))
input_map[ichan - 1] = 3;
ichan = 4;
+
for (unsigned i = 0; i < _max_rc_input; i++)
if (input_map[i] == -1)
input_map[i] = ichan++;
@@ -1132,6 +1151,7 @@ PX4IO::io_set_rc_config()
/* send channel config to IO */
ret = io_reg_set(PX4IO_PAGE_RC_CONFIG, offset, regs, PX4IO_P_RC_CONFIG_STRIDE);
+
if (ret != OK) {
log("rc config upload failed");
break;
@@ -1159,13 +1179,14 @@ PX4IO::io_handle_status(uint16_t status)
/* check for IO reset - force it back to armed if necessary */
if (_status & PX4IO_P_STATUS_FLAGS_SAFETY_OFF && !(status & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
- && !(status & PX4IO_P_STATUS_FLAGS_ARM_SYNC)) {
+ && !(status & PX4IO_P_STATUS_FLAGS_ARM_SYNC)) {
/* set the arming flag */
ret = io_reg_modify(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS, 0, PX4IO_P_STATUS_FLAGS_SAFETY_OFF | PX4IO_P_STATUS_FLAGS_ARM_SYNC);
/* set new status */
_status = status;
_status &= PX4IO_P_STATUS_FLAGS_SAFETY_OFF;
+
} else if (!(_status & PX4IO_P_STATUS_FLAGS_ARM_SYNC)) {
/* set the sync flag */
@@ -1189,6 +1210,7 @@ PX4IO::io_handle_status(uint16_t status)
if (status & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) {
safety.safety_off = true;
safety.safety_switch_available = true;
+
} else {
safety.safety_off = false;
safety.safety_switch_available = true;
@@ -1197,6 +1219,7 @@ PX4IO::io_handle_status(uint16_t status)
/* lazily publish the safety status */
if (_to_safety > 0) {
orb_publish(ORB_ID(safety), _to_safety, &safety);
+
} else {
_to_safety = orb_advertise(ORB_ID(safety), &safety);
}
@@ -1210,13 +1233,14 @@ PX4IO::dsm_bind_ioctl(int dsmMode)
if (!(_status & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)) {
/* 0: dsm2, 1:dsmx */
if ((dsmMode == 0) || (dsmMode == 1)) {
- mavlink_log_info(_thread_mavlink_fd, "[IO] binding dsm%c rx", (dsmMode == 0) ? '2' : 'x');
- ioctl(nullptr, DSM_BIND_START, (dsmMode == 0) ? DSM2_BIND_PULSES : DSMX_BIND_PULSES);
+ mavlink_log_info(_thread_mavlink_fd, "[IO] binding dsm%s rx", (dsmMode == 0) ? "2" : ((dsmMode == 1) ? "x" : "x8"));
+ ioctl(nullptr, DSM_BIND_START, (dsmMode == 0) ? DSM2_BIND_PULSES : ((dsmMode == 1) ? DSMX_BIND_PULSES : DSMX8_BIND_PULSES));
} else {
mavlink_log_info(_thread_mavlink_fd, "[IO] invalid dsm bind mode, bind request rejected");
}
+
} else {
- mavlink_log_info(_thread_mavlink_fd, "[IO] system armed, bind request rejected");
+ mavlink_log_info(_thread_mavlink_fd, "[IO] system armed, bind request rejected");
}
}
@@ -1252,22 +1276,24 @@ PX4IO::io_handle_battery(uint16_t vbatt, uint16_t ibatt)
ibatt contains the raw ADC count, as 12 bit ADC
value, with full range being 3.3v
*/
- battery_status.current_a = ibatt * (3.3f/4096.0f) * _battery_amp_per_volt;
+ battery_status.current_a = ibatt * (3.3f / 4096.0f) * _battery_amp_per_volt;
battery_status.current_a += _battery_amp_bias;
/*
integrate battery over time to get total mAh used
*/
if (_battery_last_timestamp != 0) {
- _battery_mamphour_total += battery_status.current_a *
- (battery_status.timestamp - _battery_last_timestamp) * 1.0e-3f / 3600;
+ _battery_mamphour_total += battery_status.current_a *
+ (battery_status.timestamp - _battery_last_timestamp) * 1.0e-3f / 3600;
}
+
battery_status.discharged_mah = _battery_mamphour_total;
_battery_last_timestamp = battery_status.timestamp;
-
+
/* lazily publish the battery voltage */
if (_to_battery > 0) {
orb_publish(ORB_ID(battery_status), _to_battery, &battery_status);
+
} else {
_to_battery = orb_advertise(ORB_ID(battery_status), &battery_status);
}
@@ -1282,10 +1308,11 @@ PX4IO::io_handle_vservo(uint16_t vservo, uint16_t vrssi)
/* voltage is scaled to mV */
servorail_status.voltage_v = vservo * 0.001f;
servorail_status.rssi_v = vrssi * 0.001f;
-
+
/* lazily publish the servorail voltages */
if (_to_servorail > 0) {
orb_publish(ORB_ID(servorail_status), _to_servorail, &servorail_status);
+
} else {
_to_servorail = orb_advertise(ORB_ID(servorail_status), &servorail_status);
}
@@ -1299,6 +1326,7 @@ PX4IO::io_get_status()
/* get STATUS_FLAGS, STATUS_ALARMS, STATUS_VBATT, STATUS_IBATT in that order */
ret = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS, &regs[0], sizeof(regs) / sizeof(regs[0]));
+
if (ret != OK)
return ret;
@@ -1324,7 +1352,7 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
/* we don't have the status bits, so input_source has to be set elsewhere */
input_rc.input_source = RC_INPUT_SOURCE_UNKNOWN;
-
+
static const unsigned prolog = (PX4IO_P_RAW_RC_BASE - PX4IO_P_RAW_RC_COUNT);
uint16_t regs[RC_INPUT_MAX_CHANNELS + prolog];
@@ -1335,6 +1363,7 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
*/
input_rc.timestamp = hrt_absolute_time();
ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_COUNT, &regs[0], prolog + 9);
+
if (ret != OK)
return ret;
@@ -1343,8 +1372,10 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
* channel count once.
*/
channel_count = regs[0];
+
if (channel_count > 9) {
ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE + 9, &regs[prolog + 9], channel_count - 9);
+
if (ret != OK)
return ret;
}
@@ -1367,16 +1398,20 @@ PX4IO::io_publish_raw_rc()
rc_val.timestamp = hrt_absolute_time();
int ret = io_get_raw_rc_input(rc_val);
+
if (ret != OK)
return ret;
/* sort out the source of the values */
if (_status & PX4IO_P_STATUS_FLAGS_RC_PPM) {
rc_val.input_source = RC_INPUT_SOURCE_PX4IO_PPM;
+
} else if (_status & PX4IO_P_STATUS_FLAGS_RC_DSM) {
rc_val.input_source = RC_INPUT_SOURCE_PX4IO_SPEKTRUM;
+
} else if (_status & PX4IO_P_STATUS_FLAGS_RC_SBUS) {
rc_val.input_source = RC_INPUT_SOURCE_PX4IO_SBUS;
+
} else {
rc_val.input_source = RC_INPUT_SOURCE_UNKNOWN;
}
@@ -1384,7 +1419,8 @@ PX4IO::io_publish_raw_rc()
/* lazily advertise on first publication */
if (_to_input_rc == 0) {
_to_input_rc = orb_advertise(ORB_ID(input_rc), &rc_val);
- } else {
+
+ } else {
orb_publish(ORB_ID(input_rc), _to_input_rc, &rc_val);
}
@@ -1409,6 +1445,7 @@ PX4IO::io_publish_mixed_controls()
/* get actuator controls from IO */
uint16_t act[_max_actuators];
int ret = io_reg_get(PX4IO_PAGE_ACTUATORS, 0, act, _max_actuators);
+
if (ret != OK)
return ret;
@@ -1418,16 +1455,17 @@ PX4IO::io_publish_mixed_controls()
/* laxily advertise on first publication */
if (_to_actuators_effective == 0) {
- _to_actuators_effective =
- orb_advertise((_primary_pwm_device ?
- ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE :
- ORB_ID(actuator_controls_effective_1)),
- &controls_effective);
+ _to_actuators_effective =
+ orb_advertise((_primary_pwm_device ?
+ ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE :
+ ORB_ID(actuator_controls_effective_1)),
+ &controls_effective);
+
} else {
- orb_publish((_primary_pwm_device ?
- ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE :
- ORB_ID(actuator_controls_effective_1)),
- _to_actuators_effective, &controls_effective);
+ orb_publish((_primary_pwm_device ?
+ ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE :
+ ORB_ID(actuator_controls_effective_1)),
+ _to_actuators_effective, &controls_effective);
}
return OK;
@@ -1447,26 +1485,29 @@ PX4IO::io_publish_pwm_outputs()
/* get servo values from IO */
uint16_t ctl[_max_actuators];
int ret = io_reg_get(PX4IO_PAGE_SERVOS, 0, ctl, _max_actuators);
+
if (ret != OK)
return ret;
/* convert from register format to float */
for (unsigned i = 0; i < _max_actuators; i++)
outputs.output[i] = ctl[i];
+
outputs.noutputs = _max_actuators;
/* lazily advertise on first publication */
if (_to_outputs == 0) {
_to_outputs = orb_advertise((_primary_pwm_device ?
- ORB_ID_VEHICLE_CONTROLS :
- ORB_ID(actuator_outputs_1)),
- &outputs);
+ ORB_ID_VEHICLE_CONTROLS :
+ ORB_ID(actuator_outputs_1)),
+ &outputs);
+
} else {
orb_publish((_primary_pwm_device ?
- ORB_ID_VEHICLE_CONTROLS :
- ORB_ID(actuator_outputs_1)),
- _to_outputs,
- &outputs);
+ ORB_ID_VEHICLE_CONTROLS :
+ ORB_ID(actuator_outputs_1)),
+ _to_outputs,
+ &outputs);
}
return OK;
@@ -1482,10 +1523,12 @@ PX4IO::io_reg_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned
}
int ret = _interface->write((page << 8) | offset, (void *)values, num_values);
+
if (ret != (int)num_values) {
debug("io_reg_set(%u,%u,%u): error %d", page, offset, num_values, ret);
return -1;
}
+
return OK;
}
@@ -1505,10 +1548,12 @@ PX4IO::io_reg_get(uint8_t page, uint8_t offset, uint16_t *values, unsigned num_v
}
int ret = _interface->read((page << 8) | offset, reinterpret_cast<void *>(values), num_values);
+
if (ret != (int)num_values) {
debug("io_reg_get(%u,%u,%u): data error %d", page, offset, num_values, ret);
return -1;
}
+
return OK;
}
@@ -1530,8 +1575,10 @@ PX4IO::io_reg_modify(uint8_t page, uint8_t offset, uint16_t clearbits, uint16_t
uint16_t value;
ret = io_reg_get(page, offset, &value, 1);
+
if (ret != OK)
return ret;
+
value &= ~clearbits;
value |= setbits;
@@ -1563,6 +1610,7 @@ PX4IO::print_debug()
do {
count = ::read(io_fd, buf, sizeof(buf) - 1);
+
if (count > 0) {
/* enforce null termination */
buf[count] = '\0';
@@ -1575,6 +1623,7 @@ PX4IO::print_debug()
::close(io_fd);
return 0;
}
+
#endif
return 1;
@@ -1606,6 +1655,7 @@ PX4IO::mixer_send(const char *buf, unsigned buflen, unsigned retries)
memcpy(&msg->text[0], buf, count);
buf += count;
buflen -= count;
+
} else {
continue;
}
@@ -1618,6 +1668,7 @@ PX4IO::mixer_send(const char *buf, unsigned buflen, unsigned retries)
* even.
*/
unsigned total_len = sizeof(px4io_mixdata) + count;
+
if (total_len % 2) {
msg->text[count] = '\0';
total_len++;
@@ -1673,48 +1724,48 @@ PX4IO::print_status()
{
/* basic configuration */
printf("protocol %u hardware %u bootloader %u buffer %uB\n",
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_PROTOCOL_VERSION),
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_HARDWARE_VERSION),
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_BOOTLOADER_VERSION),
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_MAX_TRANSFER));
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_PROTOCOL_VERSION),
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_HARDWARE_VERSION),
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_BOOTLOADER_VERSION),
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_MAX_TRANSFER));
printf("%u controls %u actuators %u R/C inputs %u analog inputs %u relays\n",
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_CONTROL_COUNT),
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_ACTUATOR_COUNT),
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_RC_INPUT_COUNT),
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_ADC_INPUT_COUNT),
- io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_RELAY_COUNT));
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_CONTROL_COUNT),
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_ACTUATOR_COUNT),
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_RC_INPUT_COUNT),
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_ADC_INPUT_COUNT),
+ io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_RELAY_COUNT));
/* status */
printf("%u bytes free\n",
- io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FREEMEM));
+ io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FREEMEM));
uint16_t flags = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS);
printf("status 0x%04x%s%s%s%s%s%s%s%s%s%s%s%s%s\n",
- flags,
- ((flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED) ? " OUTPUTS_ARMED" : ""),
- ((flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ? " SAFETY_OFF" : " SAFETY_SAFE"),
- ((flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) ? " OVERRIDE" : ""),
- ((flags & PX4IO_P_STATUS_FLAGS_RC_OK) ? " RC_OK" : " RC_FAIL"),
- ((flags & PX4IO_P_STATUS_FLAGS_RC_PPM) ? " PPM" : ""),
- (((flags & PX4IO_P_STATUS_FLAGS_RC_DSM) && (!(flags & PX4IO_P_STATUS_FLAGS_RC_DSM11))) ? " DSM10" : ""),
- (((flags & PX4IO_P_STATUS_FLAGS_RC_DSM) && (flags & PX4IO_P_STATUS_FLAGS_RC_DSM11)) ? " DSM11" : ""),
- ((flags & PX4IO_P_STATUS_FLAGS_RC_SBUS) ? " SBUS" : ""),
- ((flags & PX4IO_P_STATUS_FLAGS_FMU_OK) ? " FMU_OK" : " FMU_FAIL"),
- ((flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) ? " RAW_PWM_PASSTHROUGH" : ""),
- ((flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) ? " MIXER_OK" : " MIXER_FAIL"),
- ((flags & PX4IO_P_STATUS_FLAGS_ARM_SYNC) ? " ARM_SYNC" : " ARM_NO_SYNC"),
- ((flags & PX4IO_P_STATUS_FLAGS_INIT_OK) ? " INIT_OK" : " INIT_FAIL"),
- ((flags & PX4IO_P_STATUS_FLAGS_FAILSAFE) ? " FAILSAFE" : ""));
+ flags,
+ ((flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED) ? " OUTPUTS_ARMED" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ? " SAFETY_OFF" : " SAFETY_SAFE"),
+ ((flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) ? " OVERRIDE" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_RC_OK) ? " RC_OK" : " RC_FAIL"),
+ ((flags & PX4IO_P_STATUS_FLAGS_RC_PPM) ? " PPM" : ""),
+ (((flags & PX4IO_P_STATUS_FLAGS_RC_DSM) && (!(flags & PX4IO_P_STATUS_FLAGS_RC_DSM11))) ? " DSM10" : ""),
+ (((flags & PX4IO_P_STATUS_FLAGS_RC_DSM) && (flags & PX4IO_P_STATUS_FLAGS_RC_DSM11)) ? " DSM11" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_RC_SBUS) ? " SBUS" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_FMU_OK) ? " FMU_OK" : " FMU_FAIL"),
+ ((flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) ? " RAW_PWM_PASSTHROUGH" : ""),
+ ((flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) ? " MIXER_OK" : " MIXER_FAIL"),
+ ((flags & PX4IO_P_STATUS_FLAGS_ARM_SYNC) ? " ARM_SYNC" : " ARM_NO_SYNC"),
+ ((flags & PX4IO_P_STATUS_FLAGS_INIT_OK) ? " INIT_OK" : " INIT_FAIL"),
+ ((flags & PX4IO_P_STATUS_FLAGS_FAILSAFE) ? " FAILSAFE" : ""));
uint16_t alarms = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS);
printf("alarms 0x%04x%s%s%s%s%s%s%s%s\n",
- alarms,
- ((alarms & PX4IO_P_STATUS_ALARMS_VBATT_LOW) ? " VBATT_LOW" : ""),
- ((alarms & PX4IO_P_STATUS_ALARMS_TEMPERATURE) ? " TEMPERATURE" : ""),
- ((alarms & PX4IO_P_STATUS_ALARMS_SERVO_CURRENT) ? " SERVO_CURRENT" : ""),
- ((alarms & PX4IO_P_STATUS_ALARMS_ACC_CURRENT) ? " ACC_CURRENT" : ""),
- ((alarms & PX4IO_P_STATUS_ALARMS_FMU_LOST) ? " FMU_LOST" : ""),
- ((alarms & PX4IO_P_STATUS_ALARMS_RC_LOST) ? " RC_LOST" : ""),
- ((alarms & PX4IO_P_STATUS_ALARMS_PWM_ERROR) ? " PWM_ERROR" : ""),
- ((alarms & PX4IO_P_STATUS_ALARMS_VSERVO_FAULT) ? " VSERVO_FAULT" : ""));
+ alarms,
+ ((alarms & PX4IO_P_STATUS_ALARMS_VBATT_LOW) ? " VBATT_LOW" : ""),
+ ((alarms & PX4IO_P_STATUS_ALARMS_TEMPERATURE) ? " TEMPERATURE" : ""),
+ ((alarms & PX4IO_P_STATUS_ALARMS_SERVO_CURRENT) ? " SERVO_CURRENT" : ""),
+ ((alarms & PX4IO_P_STATUS_ALARMS_ACC_CURRENT) ? " ACC_CURRENT" : ""),
+ ((alarms & PX4IO_P_STATUS_ALARMS_FMU_LOST) ? " FMU_LOST" : ""),
+ ((alarms & PX4IO_P_STATUS_ALARMS_RC_LOST) ? " RC_LOST" : ""),
+ ((alarms & PX4IO_P_STATUS_ALARMS_PWM_ERROR) ? " PWM_ERROR" : ""),
+ ((alarms & PX4IO_P_STATUS_ALARMS_VSERVO_FAULT) ? " VSERVO_FAULT" : ""));
/* now clear alarms */
io_reg_set(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS, 0xFFFF);
@@ -1727,87 +1778,107 @@ PX4IO::print_status()
(double)_battery_amp_per_volt,
(double)_battery_amp_bias,
(double)_battery_mamphour_total);
+
} else if (_hardware == 2) {
printf("vservo %u mV vservo scale %u\n",
io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_VSERVO),
io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_VSERVO_SCALE));
printf("vrssi %u\n", io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_VRSSI));
}
+
printf("actuators");
+
for (unsigned i = 0; i < _max_actuators; i++)
printf(" %u", io_reg_get(PX4IO_PAGE_ACTUATORS, i));
+
printf("\n");
printf("servos");
+
for (unsigned i = 0; i < _max_actuators; i++)
printf(" %u", io_reg_get(PX4IO_PAGE_SERVOS, i));
+
printf("\n");
uint16_t raw_inputs = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_COUNT);
printf("%d raw R/C inputs", raw_inputs);
+
for (unsigned i = 0; i < raw_inputs; i++)
printf(" %u", io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE + i));
+
printf("\n");
uint16_t mapped_inputs = io_reg_get(PX4IO_PAGE_RC_INPUT, PX4IO_P_RC_VALID);
printf("mapped R/C inputs 0x%04x", mapped_inputs);
+
for (unsigned i = 0; i < _max_rc_input; i++) {
if (mapped_inputs & (1 << i))
printf(" %u:%d", i, REG_TO_SIGNED(io_reg_get(PX4IO_PAGE_RC_INPUT, PX4IO_P_RC_BASE + i)));
}
+
printf("\n");
uint16_t adc_inputs = io_reg_get(PX4IO_PAGE_CONFIG, PX4IO_P_CONFIG_ADC_INPUT_COUNT);
printf("ADC inputs");
+
for (unsigned i = 0; i < adc_inputs; i++)
printf(" %u", io_reg_get(PX4IO_PAGE_RAW_ADC_INPUT, i));
+
printf("\n");
/* setup and state */
printf("features 0x%04x\n", io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES));
uint16_t arming = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING);
printf("arming 0x%04x%s%s%s%s%s%s\n",
- arming,
- ((arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) ? " FMU_ARMED" : " FMU_DISARMED"),
- ((arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK) ? " IO_ARM_OK" : " IO_ARM_DENIED"),
- ((arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) ? " MANUAL_OVERRIDE_OK" : ""),
- ((arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) ? " FAILSAFE_CUSTOM" : ""),
- ((arming & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) ? " INAIR_RESTART_OK" : ""),
- ((arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE) ? " ALWAYS_PWM_ENABLE" : ""));
+ arming,
+ ((arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) ? " FMU_ARMED" : " FMU_DISARMED"),
+ ((arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK) ? " IO_ARM_OK" : " IO_ARM_DENIED"),
+ ((arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) ? " MANUAL_OVERRIDE_OK" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) ? " FAILSAFE_CUSTOM" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) ? " INAIR_RESTART_OK" : ""),
+ ((arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE) ? " ALWAYS_PWM_ENABLE" : ""));
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
printf("rates 0x%04x default %u alt %u relays 0x%04x\n",
- io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES),
- io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_DEFAULTRATE),
- io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE),
- io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS));
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES),
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_DEFAULTRATE),
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE),
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS));
#endif
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
printf("rates 0x%04x default %u alt %u\n",
- io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES),
- io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_DEFAULTRATE),
- io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE));
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES),
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_DEFAULTRATE),
+ io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE));
#endif
printf("debuglevel %u\n", io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_SET_DEBUG));
printf("controls");
+
for (unsigned i = 0; i < _max_controls; i++)
printf(" %u", io_reg_get(PX4IO_PAGE_CONTROLS, i));
+
printf("\n");
+
for (unsigned i = 0; i < _max_rc_input; i++) {
unsigned base = PX4IO_P_RC_CONFIG_STRIDE * i;
uint16_t options = io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_OPTIONS);
printf("input %u min %u center %u max %u deadzone %u assigned %u options 0x%04x%s%s\n",
- i,
- io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MIN),
- io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_CENTER),
- io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MAX),
- io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_DEADZONE),
- io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_ASSIGNMENT),
- options,
- ((options & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) ? " ENABLED" : ""),
- ((options & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE) ? " REVERSED" : ""));
+ i,
+ io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MIN),
+ io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_CENTER),
+ io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MAX),
+ io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_DEADZONE),
+ io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_ASSIGNMENT),
+ options,
+ ((options & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) ? " ENABLED" : ""),
+ ((options & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE) ? " REVERSED" : ""));
}
+
printf("failsafe");
+
for (unsigned i = 0; i < _max_actuators; i++)
printf(" %u", io_reg_get(PX4IO_PAGE_FAILSAFE_PWM, i));
+
printf("\nidle values");
+
for (unsigned i = 0; i < _max_actuators; i++)
printf(" %u", io_reg_get(PX4IO_PAGE_IDLE_PWM, i));
+
printf("\n");
}
@@ -1846,31 +1917,33 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
case PWM_SERVO_SELECT_UPDATE_RATE: {
- /* blindly clear the PWM update alarm - might be set for some other reason */
- io_reg_set(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS, PX4IO_P_STATUS_ALARMS_PWM_ERROR);
+ /* blindly clear the PWM update alarm - might be set for some other reason */
+ io_reg_set(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS, PX4IO_P_STATUS_ALARMS_PWM_ERROR);
- /* attempt to set the rate map */
- io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES, arg);
+ /* attempt to set the rate map */
+ io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES, arg);
- /* check that the changes took */
- uint16_t alarms = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS);
- if (alarms & PX4IO_P_STATUS_ALARMS_PWM_ERROR) {
- ret = -EINVAL;
- io_reg_set(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS, PX4IO_P_STATUS_ALARMS_PWM_ERROR);
+ /* check that the changes took */
+ uint16_t alarms = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS);
+
+ if (alarms & PX4IO_P_STATUS_ALARMS_PWM_ERROR) {
+ ret = -EINVAL;
+ io_reg_set(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_ALARMS, PX4IO_P_STATUS_ALARMS_PWM_ERROR);
+ }
+
+ break;
}
- break;
- }
case PWM_SERVO_GET_COUNT:
*(unsigned *)arg = _max_actuators;
break;
case DSM_BIND_START:
- io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down);
+ io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down);
usleep(500000);
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_set_rx_out);
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up);
- usleep(50000);
+ usleep(72000);
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4));
usleep(50000);
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart);
@@ -1882,68 +1955,80 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
case PWM_SERVO_SET(0) ... PWM_SERVO_SET(PWM_OUTPUT_MAX_CHANNELS - 1): {
- /* TODO: we could go lower for e.g. TurboPWM */
- unsigned channel = cmd - PWM_SERVO_SET(0);
- if ((channel >= _max_actuators) || (arg < 900) || (arg > 2100)) {
- ret = -EINVAL;
- } else {
- /* send a direct PWM value */
- ret = io_reg_set(PX4IO_PAGE_DIRECT_PWM, channel, arg);
- }
+ /* TODO: we could go lower for e.g. TurboPWM */
+ unsigned channel = cmd - PWM_SERVO_SET(0);
- break;
- }
+ if ((channel >= _max_actuators) || (arg < 900) || (arg > 2100)) {
+ ret = -EINVAL;
+
+ } else {
+ /* send a direct PWM value */
+ ret = io_reg_set(PX4IO_PAGE_DIRECT_PWM, channel, arg);
+ }
+
+ break;
+ }
case PWM_SERVO_GET(0) ... PWM_SERVO_GET(PWM_OUTPUT_MAX_CHANNELS - 1): {
- unsigned channel = cmd - PWM_SERVO_GET(0);
+ unsigned channel = cmd - PWM_SERVO_GET(0);
+
+ if (channel >= _max_actuators) {
+ ret = -EINVAL;
- if (channel >= _max_actuators) {
- ret = -EINVAL;
- } else {
- /* fetch a current PWM value */
- uint32_t value = io_reg_get(PX4IO_PAGE_SERVOS, channel);
- if (value == _io_reg_get_error) {
- ret = -EIO;
} else {
- *(servo_position_t *)arg = value;
+ /* fetch a current PWM value */
+ uint32_t value = io_reg_get(PX4IO_PAGE_SERVOS, channel);
+
+ if (value == _io_reg_get_error) {
+ ret = -EIO;
+
+ } else {
+ *(servo_position_t *)arg = value;
+ }
}
+
+ break;
}
- break;
- }
case PWM_SERVO_GET_RATEGROUP(0) ... PWM_SERVO_GET_RATEGROUP(PWM_OUTPUT_MAX_CHANNELS - 1): {
- unsigned channel = cmd - PWM_SERVO_GET_RATEGROUP(0);
+ unsigned channel = cmd - PWM_SERVO_GET_RATEGROUP(0);
- *(uint32_t *)arg = io_reg_get(PX4IO_PAGE_PWM_INFO, PX4IO_RATE_MAP_BASE + channel);
- if (*(uint32_t *)arg == _io_reg_get_error)
- ret = -EIO;
- break;
- }
+ *(uint32_t *)arg = io_reg_get(PX4IO_PAGE_PWM_INFO, PX4IO_RATE_MAP_BASE + channel);
+
+ if (*(uint32_t *)arg == _io_reg_get_error)
+ ret = -EIO;
+
+ break;
+ }
case GPIO_RESET: {
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
- uint32_t bits = (1 << _max_relays) - 1;
- /* don't touch relay1 if it's controlling RX vcc */
- if (_dsm_vcc_ctl)
- bits &= ~PX4IO_P_SETUP_RELAYS_POWER1;
- ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, bits, 0);
+ uint32_t bits = (1 << _max_relays) - 1;
+
+ /* don't touch relay1 if it's controlling RX vcc */
+ if (_dsm_vcc_ctl)
+ bits &= ~PX4IO_P_SETUP_RELAYS_POWER1;
+
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, bits, 0);
#endif
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
- ret = -EINVAL;
+ ret = -EINVAL;
#endif
- break;
- }
+ break;
+ }
case GPIO_SET:
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
arg &= ((1 << _max_relays) - 1);
+
/* don't touch relay1 if it's controlling RX vcc */
if (_dsm_vcc_ctl & (arg & PX4IO_P_SETUP_RELAYS_POWER1)) {
ret = -EINVAL;
break;
}
+
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, 0, arg);
#endif
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
@@ -1954,12 +2039,14 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
case GPIO_CLEAR:
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
arg &= ((1 << _max_relays) - 1);
+
/* don't touch relay1 if it's controlling RX vcc */
if (_dsm_vcc_ctl & (arg & PX4IO_P_SETUP_RELAYS_POWER1)) {
ret = -EINVAL;
break;
}
- ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, arg, 0);
+
+ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS, arg, 0);
#endif
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
ret = -EINVAL;
@@ -1969,8 +2056,10 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
case GPIO_GET:
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
*(uint32_t *)arg = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS);
+
if (*(uint32_t *)arg == _io_reg_get_error)
ret = -EIO;
+
#endif
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
ret = -EINVAL;
@@ -1986,40 +2075,44 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
break;
case MIXERIOCLOADBUF: {
- const char *buf = (const char *)arg;
- ret = mixer_send(buf, strnlen(buf, 2048));
- break;
- }
+ const char *buf = (const char *)arg;
+ ret = mixer_send(buf, strnlen(buf, 2048));
+ break;
+ }
case RC_INPUT_GET: {
- uint16_t status;
- rc_input_values *rc_val = (rc_input_values *)arg;
+ uint16_t status;
+ rc_input_values *rc_val = (rc_input_values *)arg;
- ret = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS, &status, 1);
- if (ret != OK)
- break;
+ ret = io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_FLAGS, &status, 1);
- /* if no R/C input, don't try to fetch anything */
- if (!(status & PX4IO_P_STATUS_FLAGS_RC_OK)) {
- ret = -ENOTCONN;
- break;
- }
+ if (ret != OK)
+ break;
- /* sort out the source of the values */
- if (status & PX4IO_P_STATUS_FLAGS_RC_PPM) {
- rc_val->input_source = RC_INPUT_SOURCE_PX4IO_PPM;
- } else if (status & PX4IO_P_STATUS_FLAGS_RC_DSM) {
- rc_val->input_source = RC_INPUT_SOURCE_PX4IO_SPEKTRUM;
- } else if (status & PX4IO_P_STATUS_FLAGS_RC_SBUS) {
- rc_val->input_source = RC_INPUT_SOURCE_PX4IO_SBUS;
- } else {
- rc_val->input_source = RC_INPUT_SOURCE_UNKNOWN;
- }
+ /* if no R/C input, don't try to fetch anything */
+ if (!(status & PX4IO_P_STATUS_FLAGS_RC_OK)) {
+ ret = -ENOTCONN;
+ break;
+ }
- /* read raw R/C input values */
- ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE, &(rc_val->values[0]), _max_rc_input);
- break;
- }
+ /* sort out the source of the values */
+ if (status & PX4IO_P_STATUS_FLAGS_RC_PPM) {
+ rc_val->input_source = RC_INPUT_SOURCE_PX4IO_PPM;
+
+ } else if (status & PX4IO_P_STATUS_FLAGS_RC_DSM) {
+ rc_val->input_source = RC_INPUT_SOURCE_PX4IO_SPEKTRUM;
+
+ } else if (status & PX4IO_P_STATUS_FLAGS_RC_SBUS) {
+ rc_val->input_source = RC_INPUT_SOURCE_PX4IO_SBUS;
+
+ } else {
+ rc_val->input_source = RC_INPUT_SOURCE_UNKNOWN;
+ }
+
+ /* read raw R/C input values */
+ ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE, &(rc_val->values[0]), _max_rc_input);
+ break;
+ }
case PX4IO_SET_DEBUG:
/* set the debug level */
@@ -2027,12 +2120,15 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
break;
case PX4IO_INAIR_RESTART_ENABLE:
+
/* set/clear the 'in-air restart' bit */
if (arg) {
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, 0, PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK);
+
} else {
ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK, 0);
}
+
break;
default:
@@ -2051,11 +2147,14 @@ PX4IO::write(file * /*filp*/, const char *buffer, size_t len)
if (count > _max_actuators)
count = _max_actuators;
+
if (count > 0) {
int ret = io_reg_set(PX4IO_PAGE_DIRECT_PWM, 0, (uint16_t *)buffer, count);
+
if (ret != OK)
return ret;
}
+
return count * 2;
}
@@ -2063,6 +2162,7 @@ int
PX4IO::set_update_rate(int rate)
{
int interval_ms = 1000 / rate;
+
if (interval_ms < UPDATE_INTERVAL_MIN) {
interval_ms = UPDATE_INTERVAL_MIN;
warnx("update rate too high, limiting interval to %d ms (%d Hz).", interval_ms, 1000 / interval_ms);
@@ -2095,22 +2195,27 @@ get_interface()
device::Device *interface = nullptr;
#ifndef CONFIG_ARCH_BOARD_PX4FMU_V1
+
/* try for a serial interface */
if (PX4IO_serial_interface != nullptr)
interface = PX4IO_serial_interface();
+
if (interface != nullptr)
goto got;
+
#endif
/* try for an I2C interface if we haven't got a serial one */
if (PX4IO_i2c_interface != nullptr)
interface = PX4IO_i2c_interface();
+
if (interface != nullptr)
goto got;
errx(1, "cannot alloc interface");
got:
+
if (interface->init() != OK) {
delete interface;
errx(1, "interface init failed");
@@ -2144,7 +2249,7 @@ start(int argc, char *argv[])
if (argc > 1) {
if (!strcmp(argv[1], "norc")) {
- if(g_dev->disable_rc_handling())
+ if (g_dev->disable_rc_handling())
warnx("Failed disabling RC handling");
} else {
@@ -2161,6 +2266,7 @@ start(int argc, char *argv[])
g_dev->ioctl(nullptr, DSM_BIND_POWER_UP, 0);
}
}
+
#endif
exit(0);
}
@@ -2188,6 +2294,7 @@ detect(int argc, char *argv[])
if (ret) {
/* nonzero, error */
exit(1);
+
} else {
exit(0);
}
@@ -2202,8 +2309,10 @@ bind(int argc, char *argv[])
errx(1, "px4io must be started first");
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+
if (!g_dev->get_dsm_vcc_ctl())
errx(1, "DSM bind feature not enabled");
+
#endif
if (argc < 3)
@@ -2213,8 +2322,13 @@ bind(int argc, char *argv[])
pulses = DSM2_BIND_PULSES;
else if (!strcmp(argv[2], "dsmx"))
pulses = DSMX_BIND_PULSES;
+ else if (!strcmp(argv[2], "dsmx8"))
+ pulses = DSMX8_BIND_PULSES;
else
errx(1, "unknown parameter %s, use dsm2 or dsmx", argv[2]);
+ // Test for custom pulse parameter
+ if (argc > 3)
+ pulses = atoi(argv[3]);
if (g_dev->system_status() & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)
errx(1, "system must not be armed");
@@ -2246,6 +2360,7 @@ test(void)
/* tell IO that its ok to disable its safety with the switch */
ret = ioctl(fd, PWM_SERVO_SET_ARM_OK, 0);
+
if (ret != OK)
err(1, "PWM_SERVO_SET_ARM_OK");
@@ -2262,22 +2377,27 @@ test(void)
/* sweep all servos between 1000..2000 */
servo_position_t servos[servo_count];
+
for (unsigned i = 0; i < servo_count; i++)
servos[i] = pwm_value;
ret = write(fd, servos, sizeof(servos));
+
if (ret != (int)sizeof(servos))
err(1, "error writing PWM servo data, wrote %u got %d", sizeof(servos), ret);
if (direction > 0) {
if (pwm_value < 2000) {
pwm_value++;
+
} else {
direction = -1;
}
+
} else {
if (pwm_value > 1000) {
pwm_value--;
+
} else {
direction = 1;
}
@@ -2289,6 +2409,7 @@ test(void)
if (ioctl(fd, PWM_SERVO_GET(i), (unsigned long)&value))
err(1, "error reading PWM servo %d", i);
+
if (value != servos[i])
errx(1, "servo %d readback error, got %u expected %u", i, value, servos[i]);
}
@@ -2296,9 +2417,11 @@ test(void)
/* Check if user wants to quit */
char c;
ret = poll(&fds, 1, 0);
+
if (ret > 0) {
read(0, &c, 1);
+
if (c == 0x03 || c == 0x63 || c == 'q') {
warnx("User abort\n");
exit(0);
@@ -2338,6 +2461,7 @@ monitor(void)
(void)g_dev->print_status();
(void)g_dev->print_debug();
printf("[ Use 'px4io debug <N>' for more output. Hit <enter> three times to exit monitor mode ]\n");
+
} else {
errx(1, "driver not loaded, exiting");
}
@@ -2446,20 +2570,24 @@ px4io_main(int argc, char *argv[])
if ((argc > 2)) {
g_dev->set_update_rate(atoi(argv[2]));
+
} else {
errx(1, "missing argument (50 - 500 Hz)");
return 1;
}
+
exit(0);
}
if (!strcmp(argv[1], "current")) {
if ((argc > 3)) {
g_dev->set_battery_current_scaling(atof(argv[2]), atof(argv[3]));
+
} else {
errx(1, "missing argument (apm_per_volt, amp_offset)");
return 1;
}
+
exit(0);
}
@@ -2476,10 +2604,12 @@ px4io_main(int argc, char *argv[])
/* set channel to commandline argument or to 900 for non-provided channels */
if (argc > i + 2) {
- failsafe[i] = atoi(argv[i+2]);
+ failsafe[i] = atoi(argv[i + 2]);
+
if (failsafe[i] < 800 || failsafe[i] > 2200) {
errx(1, "value out of range of 800 < value < 2200. Aborting.");
}
+
} else {
/* a zero value will result in stopping to output any pulse */
failsafe[i] = 0;
@@ -2490,6 +2620,7 @@ px4io_main(int argc, char *argv[])
if (ret != OK)
errx(ret, "failed setting failsafe values");
+
exit(0);
}
@@ -2504,14 +2635,15 @@ px4io_main(int argc, char *argv[])
/* set values for first 8 channels, fill unassigned channels with 900. */
uint16_t min[8];
- for (unsigned i = 0; i < sizeof(min) / sizeof(min[0]); i++)
- {
+ for (unsigned i = 0; i < sizeof(min) / sizeof(min[0]); i++) {
/* set channel to commanline argument or to 900 for non-provided channels */
if (argc > i + 2) {
- min[i] = atoi(argv[i+2]);
+ min[i] = atoi(argv[i + 2]);
+
if (min[i] < 900 || min[i] > 1200) {
errx(1, "value out of range of 900 < value < 1200. Aborting.");
}
+
} else {
/* a zero value will the default */
min[i] = 0;
@@ -2522,9 +2654,11 @@ px4io_main(int argc, char *argv[])
if (ret != OK)
errx(ret, "failed setting min values");
+
} else {
errx(1, "not loaded");
}
+
exit(0);
}
@@ -2539,14 +2673,15 @@ px4io_main(int argc, char *argv[])
/* set values for first 8 channels, fill unassigned channels with 2100. */
uint16_t max[8];
- for (unsigned i = 0; i < sizeof(max) / sizeof(max[0]); i++)
- {
+ for (unsigned i = 0; i < sizeof(max) / sizeof(max[0]); i++) {
/* set channel to commanline argument or to 2100 for non-provided channels */
if (argc > i + 2) {
- max[i] = atoi(argv[i+2]);
+ max[i] = atoi(argv[i + 2]);
+
if (max[i] < 1800 || max[i] > 2100) {
errx(1, "value out of range of 1800 < value < 2100. Aborting.");
}
+
} else {
/* a zero value will the default */
max[i] = 0;
@@ -2557,9 +2692,11 @@ px4io_main(int argc, char *argv[])
if (ret != OK)
errx(ret, "failed setting max values");
+
} else {
errx(1, "not loaded");
}
+
exit(0);
}
@@ -2574,14 +2711,15 @@ px4io_main(int argc, char *argv[])
/* set values for first 8 channels, fill unassigned channels with 0. */
uint16_t idle[8];
- for (unsigned i = 0; i < sizeof(idle) / sizeof(idle[0]); i++)
- {
+ for (unsigned i = 0; i < sizeof(idle) / sizeof(idle[0]); i++) {
/* set channel to commanline argument or to 0 for non-provided channels */
if (argc > i + 2) {
- idle[i] = atoi(argv[i+2]);
+ idle[i] = atoi(argv[i + 2]);
+
if (idle[i] < 900 || idle[i] > 2100) {
errx(1, "value out of range of 900 < value < 2100. Aborting.");
}
+
} else {
/* a zero value will the default */
idle[i] = 0;
@@ -2592,9 +2730,11 @@ px4io_main(int argc, char *argv[])
if (ret != OK)
errx(ret, "failed setting idle values");
+
} else {
errx(1, "not loaded");
}
+
exit(0);
}
@@ -2603,7 +2743,7 @@ px4io_main(int argc, char *argv[])
/*
* Enable in-air restart support.
* We can cheat and call the driver directly, as it
- * doesn't reference filp in ioctl()
+ * doesn't reference filp in ioctl()
*/
g_dev->ioctl(NULL, PX4IO_INAIR_RESTART_ENABLE, 1);
exit(0);
@@ -2630,19 +2770,23 @@ px4io_main(int argc, char *argv[])
printf("usage: px4io debug LEVEL\n");
exit(1);
}
+
if (g_dev == nullptr) {
printf("px4io is not started\n");
exit(1);
}
+
uint8_t level = atoi(argv[2]);
/* we can cheat and call the driver directly, as it
* doesn't reference filp in ioctl()
*/
int ret = g_dev->ioctl(nullptr, PX4IO_SET_DEBUG, level);
+
if (ret != 0) {
printf("SET_DEBUG failed - %d\n", ret);
exit(1);
}
+
printf("SET_DEBUG %u OK\n", (unsigned)level);
exit(0);
}
@@ -2663,6 +2807,6 @@ px4io_main(int argc, char *argv[])
if (!strcmp(argv[1], "bind"))
bind(argc, argv);
- out:
+out:
errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug',\n 'recovery', 'limit', 'current', 'failsafe', 'min, 'max',\n 'idle', 'bind' or 'update'");
}
diff --git a/src/modules/att_pos_estimator_ekf/KalmanNav.hpp b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp
index f01ee0355..799fc2fb9 100644
--- a/src/modules/att_pos_estimator_ekf/KalmanNav.hpp
+++ b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp
@@ -166,19 +166,19 @@ protected:
double lat, lon; /**< lat, lon radians */
float alt; /**< altitude, meters */
// parameters
- control::BlockParam<float> _vGyro; /**< gyro process noise */
- control::BlockParam<float> _vAccel; /**< accelerometer process noise */
- control::BlockParam<float> _rMag; /**< magnetometer measurement noise */
- control::BlockParam<float> _rGpsVel; /**< gps velocity measurement noise */
- control::BlockParam<float> _rGpsPos; /**< gps position measurement noise */
- control::BlockParam<float> _rGpsAlt; /**< gps altitude measurement noise */
- control::BlockParam<float> _rPressAlt; /**< press altitude measurement noise */
- control::BlockParam<float> _rAccel; /**< accelerometer measurement noise */
- control::BlockParam<float> _magDip; /**< magnetic inclination with level */
- control::BlockParam<float> _magDec; /**< magnetic declination, clockwise rotation */
- control::BlockParam<float> _g; /**< gravitational constant */
- control::BlockParam<float> _faultPos; /**< fault detection threshold for position */
- control::BlockParam<float> _faultAtt; /**< fault detection threshold for attitude */
+ control::BlockParamFloat _vGyro; /**< gyro process noise */
+ control::BlockParamFloat _vAccel; /**< accelerometer process noise */
+ control::BlockParamFloat _rMag; /**< magnetometer measurement noise */
+ control::BlockParamFloat _rGpsVel; /**< gps velocity measurement noise */
+ control::BlockParamFloat _rGpsPos; /**< gps position measurement noise */
+ control::BlockParamFloat _rGpsAlt; /**< gps altitude measurement noise */
+ control::BlockParamFloat _rPressAlt; /**< press altitude measurement noise */
+ control::BlockParamFloat _rAccel; /**< accelerometer measurement noise */
+ control::BlockParamFloat _magDip; /**< magnetic inclination with level */
+ control::BlockParamFloat _magDec; /**< magnetic declination, clockwise rotation */
+ control::BlockParamFloat _g; /**< gravitational constant */
+ control::BlockParamFloat _faultPos; /**< fault detection threshold for position */
+ control::BlockParamFloat _faultAtt; /**< fault detection threshold for attitude */
// status
bool _attitudeInitialized;
bool _positionInitialized;
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 0c3546b95..2ef509980 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -1193,31 +1193,19 @@ int commander_thread_main(int argc, char *argv[])
bool main_state_changed = check_main_state_changed();
bool navigation_state_changed = check_navigation_state_changed();
- if (arming_state_changed || main_state_changed || navigation_state_changed) {
- mavlink_log_info(mavlink_fd, "[cmd] state: arm %d, main %d, nav %d", status.arming_state, status.main_state, status.navigation_state);
- status_changed = true;
- }
-
hrt_abstime t1 = hrt_absolute_time();
- /* publish arming state */
- if (arming_state_changed) {
- armed.timestamp = t1;
- orb_publish(ORB_ID(actuator_armed), armed_pub, &armed);
- }
-
- /* publish control mode */
if (navigation_state_changed || arming_state_changed) {
- /* publish new navigation state */
control_mode.flag_armed = armed.armed; // copy armed state to vehicle_control_mode topic
- control_mode.counter++;
- control_mode.timestamp = t1;
- orb_publish(ORB_ID(vehicle_control_mode), control_mode_pub, &control_mode);
+ }
+
+ if (arming_state_changed || main_state_changed || navigation_state_changed) {
+ mavlink_log_info(mavlink_fd, "[cmd] state: arm %d, main %d, nav %d", status.arming_state, status.main_state, status.navigation_state);
+ status_changed = true;
}
/* publish states (armed, control mode, vehicle status) at least with 5 Hz */
if (counter % (200000 / COMMANDER_MONITORING_INTERVAL) == 0 || status_changed) {
- status.counter++;
status.timestamp = t1;
orb_publish(ORB_ID(vehicle_status), status_pub, &status);
control_mode.timestamp = t1;
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index efe12be57..490fc8fc6 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -504,7 +504,6 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
if (valid_transition) {
current_status->hil_state = new_state;
- current_status->counter++;
current_status->timestamp = hrt_absolute_time();
orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
diff --git a/src/modules/controllib/block/BlockParam.hpp b/src/modules/controllib/block/BlockParam.hpp
index 58a9bfc0d..36bc8c24b 100644
--- a/src/modules/controllib/block/BlockParam.hpp
+++ b/src/modules/controllib/block/BlockParam.hpp
@@ -69,22 +69,39 @@ protected:
/**
* Parameters that are tied to blocks for updating and nameing.
*/
-template<class T>
-class __EXPORT BlockParam : public BlockParamBase
+
+class __EXPORT BlockParamFloat : public BlockParamBase
+{
+public:
+ BlockParamFloat(Block *block, const char *name, bool parent_prefix=true) :
+ BlockParamBase(block, name, parent_prefix),
+ _val() {
+ update();
+ }
+ float get() { return _val; }
+ void set(float val) { _val = val; }
+ void update() {
+ if (_handle != PARAM_INVALID) param_get(_handle, &_val);
+ }
+protected:
+ float _val;
+};
+
+class __EXPORT BlockParamInt : public BlockParamBase
{
public:
- BlockParam(Block *block, const char *name, bool parent_prefix=true) :
+ BlockParamInt(Block *block, const char *name, bool parent_prefix=true) :
BlockParamBase(block, name, parent_prefix),
_val() {
update();
}
- T get() { return _val; }
- void set(T val) { _val = val; }
+ int get() { return _val; }
+ void set(int val) { _val = val; }
void update() {
if (_handle != PARAM_INVALID) param_get(_handle, &_val);
}
protected:
- T _val;
+ int _val;
};
} // namespace control
diff --git a/src/modules/controllib/blocks.hpp b/src/modules/controllib/blocks.hpp
index fefe99702..66e929038 100644
--- a/src/modules/controllib/blocks.hpp
+++ b/src/modules/controllib/blocks.hpp
@@ -74,8 +74,8 @@ public:
float getMax() { return _max.get(); }
protected:
// attributes
- BlockParam<float> _min;
- BlockParam<float> _max;
+ control::BlockParamFloat _min;
+ control::BlockParamFloat _max;
};
int __EXPORT blockLimitTest();
@@ -99,7 +99,7 @@ public:
float getMax() { return _max.get(); }
protected:
// attributes
- BlockParam<float> _max;
+ control::BlockParamFloat _max;
};
int __EXPORT blockLimitSymTest();
@@ -126,7 +126,7 @@ public:
protected:
// attributes
float _state;
- BlockParam<float> _fCut;
+ control::BlockParamFloat _fCut;
};
int __EXPORT blockLowPassTest();
@@ -157,7 +157,7 @@ protected:
// attributes
float _u; /**< previous input */
float _y; /**< previous output */
- BlockParam<float> _fCut; /**< cut-off frequency, Hz */
+ control::BlockParamFloat _fCut; /**< cut-off frequency, Hz */
};
int __EXPORT blockHighPassTest();
@@ -273,7 +273,7 @@ public:
// accessors
float getKP() { return _kP.get(); }
protected:
- BlockParam<float> _kP;
+ control::BlockParamFloat _kP;
};
int __EXPORT blockPTest();
@@ -303,8 +303,8 @@ public:
BlockIntegral &getIntegral() { return _integral; }
private:
BlockIntegral _integral;
- BlockParam<float> _kP;
- BlockParam<float> _kI;
+ control::BlockParamFloat _kP;
+ control::BlockParamFloat _kI;
};
int __EXPORT blockPITest();
@@ -334,8 +334,8 @@ public:
BlockDerivative &getDerivative() { return _derivative; }
private:
BlockDerivative _derivative;
- BlockParam<float> _kP;
- BlockParam<float> _kD;
+ control::BlockParamFloat _kP;
+ control::BlockParamFloat _kD;
};
int __EXPORT blockPDTest();
@@ -372,9 +372,9 @@ private:
// attributes
BlockIntegral _integral;
BlockDerivative _derivative;
- BlockParam<float> _kP;
- BlockParam<float> _kI;
- BlockParam<float> _kD;
+ control::BlockParamFloat _kP;
+ control::BlockParamFloat _kI;
+ control::BlockParamFloat _kD;
};
int __EXPORT blockPIDTest();
@@ -404,7 +404,7 @@ public:
float get() { return _val; }
private:
// attributes
- BlockParam<float> _trim;
+ control::BlockParamFloat _trim;
BlockLimit _limit;
float _val;
};
@@ -439,8 +439,8 @@ public:
float getMax() { return _max.get(); }
private:
// attributes
- BlockParam<float> _min;
- BlockParam<float> _max;
+ control::BlockParamFloat _min;
+ control::BlockParamFloat _max;
};
int __EXPORT blockRandUniformTest();
@@ -486,8 +486,8 @@ public:
float getStdDev() { return _stdDev.get(); }
private:
// attributes
- BlockParam<float> _mean;
- BlockParam<float> _stdDev;
+ control::BlockParamFloat _mean;
+ control::BlockParamFloat _stdDev;
};
int __EXPORT blockRandGaussTest();
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 7dd9e321f..8243748dc 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -167,6 +167,7 @@ handle_message(mavlink_message_t *msg)
/* check if topic is advertised */
if (cmd_pub <= 0) {
cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
+
} else {
/* publish */
orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
@@ -437,9 +438,11 @@ handle_message(mavlink_message_t *msg)
if (pub_hil_airspeed < 0) {
pub_hil_airspeed = orb_advertise(ORB_ID(airspeed), &airspeed);
+
} else {
orb_publish(ORB_ID(airspeed), pub_hil_airspeed, &airspeed);
}
+
//warnx("SENSOR: IAS: %6.2f TAS: %6.2f", airspeed.indicated_airspeed_m_s, airspeed.true_airspeed_m_s);
/* individual sensor publications */
@@ -455,49 +458,72 @@ handle_message(mavlink_message_t *msg)
if (pub_hil_gyro < 0) {
pub_hil_gyro = orb_advertise(ORB_ID(sensor_gyro), &gyro);
+
} else {
orb_publish(ORB_ID(sensor_gyro), pub_hil_gyro, &gyro);
}
struct accel_report accel;
+
accel.x_raw = imu.xacc / mg2ms2;
+
accel.y_raw = imu.yacc / mg2ms2;
+
accel.z_raw = imu.zacc / mg2ms2;
+
accel.x = imu.xacc;
+
accel.y = imu.yacc;
+
accel.z = imu.zacc;
+
accel.temperature = imu.temperature;
+
accel.timestamp = hrt_absolute_time();
if (pub_hil_accel < 0) {
pub_hil_accel = orb_advertise(ORB_ID(sensor_accel), &accel);
+
} else {
orb_publish(ORB_ID(sensor_accel), pub_hil_accel, &accel);
}
struct mag_report mag;
+
mag.x_raw = imu.xmag / mga2ga;
+
mag.y_raw = imu.ymag / mga2ga;
+
mag.z_raw = imu.zmag / mga2ga;
+
mag.x = imu.xmag;
+
mag.y = imu.ymag;
+
mag.z = imu.zmag;
+
mag.timestamp = hrt_absolute_time();
if (pub_hil_mag < 0) {
pub_hil_mag = orb_advertise(ORB_ID(sensor_mag), &mag);
+
} else {
orb_publish(ORB_ID(sensor_mag), pub_hil_mag, &mag);
}
struct baro_report baro;
+
baro.pressure = imu.abs_pressure;
+
baro.altitude = imu.pressure_alt;
+
baro.temperature = imu.temperature;
+
baro.timestamp = hrt_absolute_time();
if (pub_hil_baro < 0) {
pub_hil_baro = orb_advertise(ORB_ID(sensor_baro), &baro);
+
} else {
orb_publish(ORB_ID(sensor_baro), pub_hil_baro, &baro);
}
@@ -505,6 +531,7 @@ handle_message(mavlink_message_t *msg)
/* publish combined sensor topic */
if (pub_hil_sensors > 0) {
orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors);
+
} else {
pub_hil_sensors = orb_advertise(ORB_ID(sensor_combined), &hil_sensors);
}
@@ -517,6 +544,7 @@ handle_message(mavlink_message_t *msg)
/* lazily publish the battery voltage */
if (pub_hil_battery > 0) {
orb_publish(ORB_ID(battery_status), pub_hil_battery, &hil_battery_status);
+
} else {
pub_hil_battery = orb_advertise(ORB_ID(battery_status), &hil_battery_status);
}
@@ -527,7 +555,7 @@ handle_message(mavlink_message_t *msg)
// output
if ((timestamp - old_timestamp) > 10000000) {
- printf("receiving hil sensor at %d hz\n", hil_frames/10);
+ printf("receiving hil sensor at %d hz\n", hil_frames / 10);
old_timestamp = timestamp;
hil_frames = 0;
}
@@ -552,9 +580,11 @@ handle_message(mavlink_message_t *msg)
/* gps.cog is in degrees 0..360 * 100, heading is -PI..+PI */
float heading_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f;
+
/* go back to -PI..PI */
if (heading_rad > M_PI_F)
heading_rad -= 2.0f * M_PI_F;
+
hil_gps.vel_n_m_s = gps.vn * 1e-2f; // from cm to m
hil_gps.vel_e_m_s = gps.ve * 1e-2f; // from cm to m
hil_gps.vel_d_m_s = gps.vd * 1e-2f; // from cm to m
@@ -567,6 +597,7 @@ handle_message(mavlink_message_t *msg)
/* publish GPS measurement data */
if (pub_hil_gps > 0) {
orb_publish(ORB_ID(vehicle_gps_position), pub_hil_gps, &hil_gps);
+
} else {
pub_hil_gps = orb_advertise(ORB_ID(vehicle_gps_position), &hil_gps);
}
@@ -585,6 +616,7 @@ handle_message(mavlink_message_t *msg)
if (pub_hil_airspeed < 0) {
pub_hil_airspeed = orb_advertise(ORB_ID(airspeed), &airspeed);
+
} else {
orb_publish(ORB_ID(airspeed), pub_hil_airspeed, &airspeed);
}
@@ -602,6 +634,7 @@ handle_message(mavlink_message_t *msg)
if (pub_hil_global_pos > 0) {
orb_publish(ORB_ID(vehicle_global_position), pub_hil_global_pos, &hil_global_pos);
+
} else {
pub_hil_global_pos = orb_advertise(ORB_ID(vehicle_global_position), &hil_global_pos);
}
@@ -613,8 +646,8 @@ handle_message(mavlink_message_t *msg)
/* set rotation matrix */
for (int i = 0; i < 3; i++) for (int j = 0; j < 3; j++)
- hil_attitude.R[i][j] = C_nb(i, j);
-
+ hil_attitude.R[i][j] = C_nb(i, j);
+
hil_attitude.R_valid = true;
/* set quaternion */
@@ -636,22 +669,32 @@ handle_message(mavlink_message_t *msg)
if (pub_hil_attitude > 0) {
orb_publish(ORB_ID(vehicle_attitude), pub_hil_attitude, &hil_attitude);
+
} else {
pub_hil_attitude = orb_advertise(ORB_ID(vehicle_attitude), &hil_attitude);
}
struct accel_report accel;
+
accel.x_raw = hil_state.xacc / 9.81f * 1e3f;
+
accel.y_raw = hil_state.yacc / 9.81f * 1e3f;
+
accel.z_raw = hil_state.zacc / 9.81f * 1e3f;
+
accel.x = hil_state.xacc;
+
accel.y = hil_state.yacc;
+
accel.z = hil_state.zacc;
+
accel.temperature = 25.0f;
+
accel.timestamp = hrt_absolute_time();
if (pub_hil_accel < 0) {
pub_hil_accel = orb_advertise(ORB_ID(sensor_accel), &accel);
+
} else {
orb_publish(ORB_ID(sensor_accel), pub_hil_accel, &accel);
}
@@ -664,6 +707,7 @@ handle_message(mavlink_message_t *msg)
/* lazily publish the battery voltage */
if (pub_hil_battery > 0) {
orb_publish(ORB_ID(battery_status), pub_hil_battery, &hil_battery_status);
+
} else {
pub_hil_battery = orb_advertise(ORB_ID(battery_status), &hil_battery_status);
}
@@ -733,17 +777,23 @@ receive_thread(void *arg)
mavlink_message_t msg;
- prctl(PR_SET_NAME, "mavlink uart rcv", getpid());
+ prctl(PR_SET_NAME, "mavlink_uart_rcv", getpid());
- while (!thread_should_exit) {
+ struct pollfd fds[1];
+ fds[0].fd = uart_fd;
+ fds[0].events = POLLIN;
- struct pollfd fds[1];
- fds[0].fd = uart_fd;
- fds[0].events = POLLIN;
+ ssize_t nread = 0;
+ while (!thread_should_exit) {
if (poll(fds, 1, timeout) > 0) {
+ if (nread < sizeof(buf)) {
+ /* to avoid reading very small chunks wait for data before reading */
+ usleep(1000);
+ }
+
/* non-blocking read. read may return negative values */
- ssize_t nread = read(uart_fd, buf, sizeof(buf));
+ nread = read(uart_fd, buf, sizeof(buf));
/* if read failed, this loop won't execute */
for (ssize_t i = 0; i < nread; i++) {
@@ -751,10 +801,10 @@ receive_thread(void *arg)
/* handle generic messages and commands */
handle_message(&msg);
- /* Handle packet with waypoint component */
+ /* handle packet with waypoint component */
mavlink_wpm_message_handler(&msg, &global_pos, &local_pos);
- /* Handle packet with parameter component */
+ /* handle packet with parameter component */
mavlink_pm_message_handler(MAVLINK_COMM_0, &msg);
}
}
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c
index 0e0ce2723..f6860930c 100644
--- a/src/modules/mavlink/orb_listener.c
+++ b/src/modules/mavlink/orb_listener.c
@@ -711,7 +711,7 @@ static void *
uorb_receive_thread(void *arg)
{
/* Set thread name */
- prctl(PR_SET_NAME, "mavlink orb rcv", getpid());
+ prctl(PR_SET_NAME, "mavlink_orb_rcv", getpid());
/*
* set up poll to block for new data,
diff --git a/src/modules/mavlink_onboard/mavlink.c b/src/modules/mavlink_onboard/mavlink.c
index e71344982..0edb53a3e 100644
--- a/src/modules/mavlink_onboard/mavlink.c
+++ b/src/modules/mavlink_onboard/mavlink.c
@@ -167,12 +167,12 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf
case 921600: speed = B921600; break;
default:
- fprintf(stderr, "[mavlink] ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600\n\n", baud);
+ warnx("ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\n\t9600\n19200\n38400\n57600\n115200\n230400\n460800\n921600", baud);
return -EINVAL;
}
/* open uart */
- printf("[mavlink] UART is %s, baudrate is %d\n", uart_name, baud);
+ warnx("UART is %s, baudrate is %d", uart_name, baud);
uart = open(uart_name, O_RDWR | O_NOCTTY);
/* Try to set baud rate */
@@ -183,7 +183,7 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf
if (strcmp(uart_name, "/dev/ttyACM0") != OK) {
/* Back up the original uart configuration to restore it after exit */
if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) {
- fprintf(stderr, "[mavlink] ERROR getting baudrate / termios config for %s: %d\n", uart_name, termios_state);
+ warnx("ERROR getting baudrate / termios config for %s: %d", uart_name, termios_state);
close(uart);
return -1;
}
@@ -196,14 +196,14 @@ int mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_conf
/* Set baud rate */
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
- fprintf(stderr, "[mavlink] ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state);
+ warnx("ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)", uart_name, termios_state);
close(uart);
return -1;
}
if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) {
- fprintf(stderr, "[mavlink] ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name);
+ warnx("ERROR setting baudrate / termios config for %s (tcsetattr)", uart_name);
close(uart);
return -1;
}
@@ -481,9 +481,9 @@ int mavlink_thread_main(int argc, char *argv[])
static void
usage()
{
- fprintf(stderr, "usage: mavlink start [-d <devicename>] [-b <baud rate>]\n"
- " mavlink stop\n"
- " mavlink status\n");
+ fprintf(stderr, "usage: mavlink_onboard start [-d <devicename>] [-b <baud rate>]\n"
+ " mavlink_onboard stop\n"
+ " mavlink_onboard status\n");
exit(1);
}
@@ -499,7 +499,7 @@ int mavlink_onboard_main(int argc, char *argv[])
/* this is not an error */
if (thread_running)
- errx(0, "mavlink already running\n");
+ errx(0, "already running");
thread_should_exit = false;
mavlink_task = task_spawn_cmd("mavlink_onboard",
@@ -516,7 +516,7 @@ int mavlink_onboard_main(int argc, char *argv[])
while (thread_running) {
usleep(200000);
}
- warnx("terminated.");
+ warnx("terminated");
exit(0);
}
diff --git a/src/modules/mavlink_onboard/mavlink_receiver.c b/src/modules/mavlink_onboard/mavlink_receiver.c
index 0236e6126..4658bcc1d 100644
--- a/src/modules/mavlink_onboard/mavlink_receiver.c
+++ b/src/modules/mavlink_onboard/mavlink_receiver.c
@@ -100,11 +100,11 @@ handle_message(mavlink_message_t *msg)
mavlink_msg_command_long_decode(msg, &cmd_mavlink);
if (cmd_mavlink.target_system == mavlink_system.sysid && ((cmd_mavlink.target_component == mavlink_system.compid)
- || (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) {
+ || (cmd_mavlink.target_component == MAV_COMP_ID_ALL))) {
//check for MAVLINK terminate command
if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) {
/* This is the link shutdown command, terminate mavlink */
- printf("[mavlink] Terminating .. \n");
+ warnx("terminating...");
fflush(stdout);
usleep(50000);
@@ -132,6 +132,7 @@ handle_message(mavlink_message_t *msg)
if (cmd_pub <= 0) {
cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
}
+
/* publish */
orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
}
@@ -156,6 +157,7 @@ handle_message(mavlink_message_t *msg)
/* check if topic is advertised */
if (flow_pub <= 0) {
flow_pub = orb_advertise(ORB_ID(optical_flow), &f);
+
} else {
/* publish */
orb_publish(ORB_ID(optical_flow), flow_pub, &f);
@@ -186,6 +188,7 @@ handle_message(mavlink_message_t *msg)
/* check if topic is advertised */
if (cmd_pub <= 0) {
cmd_pub = orb_advertise(ORB_ID(vehicle_command), &vcmd);
+
} else {
/* create command */
orb_publish(ORB_ID(vehicle_command), cmd_pub, &vcmd);
@@ -203,6 +206,7 @@ handle_message(mavlink_message_t *msg)
if (vicon_position_pub <= 0) {
vicon_position_pub = orb_advertise(ORB_ID(vehicle_vicon_position), &vicon_position);
+
} else {
orb_publish(ORB_ID(vehicle_vicon_position), vicon_position_pub, &vicon_position);
}
@@ -219,7 +223,7 @@ handle_message(mavlink_message_t *msg)
/* switch to a receiving link mode */
gcs_link = false;
- /*
+ /*
* rate control mode - defined by MAVLink
*/
@@ -227,33 +231,37 @@ handle_message(mavlink_message_t *msg)
bool ml_armed = false;
switch (quad_motors_setpoint.mode) {
- case 0:
- ml_armed = false;
- break;
- case 1:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES;
- ml_armed = true;
-
- break;
- case 2:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE;
- ml_armed = true;
-
- break;
- case 3:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY;
- break;
- case 4:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION;
- break;
+ case 0:
+ ml_armed = false;
+ break;
+
+ case 1:
+ ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES;
+ ml_armed = true;
+
+ break;
+
+ case 2:
+ ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE;
+ ml_armed = true;
+
+ break;
+
+ case 3:
+ ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY;
+ break;
+
+ case 4:
+ ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION;
+ break;
}
- offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid-1] / (float)INT16_MAX;
- offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid-1] / (float)INT16_MAX;
- offboard_control_sp.p3= (float)quad_motors_setpoint.yaw[mavlink_system.sysid-1] / (float)INT16_MAX;
- offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid-1]/(float)UINT16_MAX;
+ offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / (float)INT16_MAX;
+ offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / (float)INT16_MAX;
+ offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / (float)INT16_MAX;
+ offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX;
- if (quad_motors_setpoint.thrust[mavlink_system.sysid-1] == 0) {
+ if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) {
ml_armed = false;
}
@@ -265,6 +273,7 @@ handle_message(mavlink_message_t *msg)
/* check if topic has to be advertised */
if (offboard_control_sp_pub <= 0) {
offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp);
+
} else {
/* Publish */
orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp);
@@ -281,31 +290,36 @@ handle_message(mavlink_message_t *msg)
static void *
receive_thread(void *arg)
{
- int uart_fd = *((int*)arg);
+ int uart_fd = *((int *)arg);
const int timeout = 1000;
- uint8_t ch;
+ uint8_t buf[32];
mavlink_message_t msg;
- prctl(PR_SET_NAME, "mavlink offb rcv", getpid());
+ prctl(PR_SET_NAME, "mavlink_onboard_rcv", getpid());
- while (!thread_should_exit) {
+ struct pollfd fds[] = { { .fd = uart_fd, .events = POLLIN } };
- struct pollfd fds[] = { { .fd = uart_fd, .events = POLLIN } };
+ ssize_t nread = 0;
+ while (!thread_should_exit) {
if (poll(fds, 1, timeout) > 0) {
- /* non-blocking read until buffer is empty */
- int nread = 0;
+ if (nread < sizeof(buf)) {
+ /* to avoid reading very small chunks wait for data before reading */
+ usleep(1000);
+ }
- do {
- nread = read(uart_fd, &ch, 1);
+ /* non-blocking read. read may return negative values */
+ nread = read(uart_fd, buf, sizeof(buf));
- if (mavlink_parse_char(chan, ch, &msg, &status)) { //parse the char
+ /* if read failed, this loop won't execute */
+ for (ssize_t i = 0; i < nread; i++) {
+ if (mavlink_parse_char(chan, buf[i], &msg, &status)) {
/* handle generic messages and commands */
handle_message(&msg);
}
- } while (nread > 0);
+ }
}
}
@@ -319,8 +333,8 @@ receive_start(int uart)
pthread_attr_init(&receiveloop_attr);
struct sched_param param;
- param.sched_priority = SCHED_PRIORITY_MAX - 40;
- (void)pthread_attr_setschedparam(&receiveloop_attr, &param);
+ param.sched_priority = SCHED_PRIORITY_MAX - 40;
+ (void)pthread_attr_setschedparam(&receiveloop_attr, &param);
pthread_attr_setstacksize(&receiveloop_attr, 2048);
diff --git a/src/modules/multirotor_att_control/multirotor_att_control_main.c b/src/modules/multirotor_att_control/multirotor_att_control_main.c
index 04582f2a4..44f8f664b 100644
--- a/src/modules/multirotor_att_control/multirotor_att_control_main.c
+++ b/src/modules/multirotor_att_control/multirotor_att_control_main.c
@@ -89,18 +89,18 @@ static int
mc_thread_main(int argc, char *argv[])
{
/* declare and safely initialize all structs */
- struct vehicle_control_mode_s control_mode;
- memset(&control_mode, 0, sizeof(control_mode));
struct vehicle_attitude_s att;
memset(&att, 0, sizeof(att));
struct vehicle_attitude_setpoint_s att_sp;
memset(&att_sp, 0, sizeof(att_sp));
- struct manual_control_setpoint_s manual;
- memset(&manual, 0, sizeof(manual));
- struct sensor_combined_s raw;
- memset(&raw, 0, sizeof(raw));
struct offboard_control_setpoint_s offboard_sp;
memset(&offboard_sp, 0, sizeof(offboard_sp));
+ struct vehicle_control_mode_s control_mode;
+ memset(&control_mode, 0, sizeof(control_mode));
+ struct manual_control_setpoint_s manual;
+ memset(&manual, 0, sizeof(manual));
+ struct sensor_combined_s sensor;
+ memset(&sensor, 0, sizeof(sensor));
struct vehicle_rates_setpoint_s rates_sp;
memset(&rates_sp, 0, sizeof(rates_sp));
struct vehicle_status_s status;
@@ -108,29 +108,16 @@ mc_thread_main(int argc, char *argv[])
struct actuator_controls_s actuators;
memset(&actuators, 0, sizeof(actuators));
- /* subscribe to attitude, motor setpoints and system state */
- int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- int param_sub = orb_subscribe(ORB_ID(parameter_update));
- int att_setpoint_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
- int setpoint_sub = orb_subscribe(ORB_ID(offboard_control_setpoint));
- int control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
- int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
- int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
- int rates_sp_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint));
- int status_sub = orb_subscribe(ORB_ID(vehicle_status));
-
- /*
- * Do not rate-limit the loop to prevent aliasing
- * if rate-limiting would be desired later, the line below would
- * enable it.
- *
- * rate-limit the attitude subscription to 200Hz to pace our loop
- * orb_set_interval(att_sub, 5);
- */
- struct pollfd fds[2] = {
- { .fd = att_sub, .events = POLLIN },
- { .fd = param_sub, .events = POLLIN }
- };
+ /* subscribe */
+ int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update));
+ int vehicle_attitude_setpoint_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
+ int offboard_control_setpoint_sub = orb_subscribe(ORB_ID(offboard_control_setpoint));
+ int vehicle_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
+ int manual_control_setpoint_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
+ int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
+ int vehicle_rates_setpoint_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint));
+ int vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
/* publish actuator controls */
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++) {
@@ -146,233 +133,246 @@ mc_thread_main(int argc, char *argv[])
perf_counter_t mc_interval_perf = perf_alloc(PC_INTERVAL, "multirotor_att_control_interval");
perf_counter_t mc_err_perf = perf_alloc(PC_COUNT, "multirotor_att_control_err");
- /* welcome user */
warnx("starting");
/* store last control mode to detect mode switches */
bool control_yaw_position = true;
bool reset_yaw_sp = true;
+ struct pollfd fds[1] = {
+ { .fd = vehicle_attitude_sub, .events = POLLIN },
+ };
+
while (!thread_should_exit) {
/* wait for a sensor update, check for exit condition every 500 ms */
- int ret = poll(fds, 2, 500);
+ int ret = poll(fds, 1, 500);
if (ret < 0) {
/* poll error, count it in perf */
perf_count(mc_err_perf);
- } else if (ret == 0) {
- /* no return value, ignore */
- } else {
+ } else if (ret > 0) {
+ /* only run controller if attitude changed */
+ perf_begin(mc_loop_perf);
- /* only update parameters if they changed */
- if (fds[1].revents & POLLIN) {
- /* read from param to clear updated flag */
- struct parameter_update_s update;
- orb_copy(ORB_ID(parameter_update), param_sub, &update);
+ /* attitude */
+ orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
+
+ bool updated;
+
+ /* parameters */
+ orb_check(parameter_update_sub, &updated);
+ if (updated) {
+ struct parameter_update_s update;
+ orb_copy(ORB_ID(parameter_update), parameter_update_sub, &update);
/* update parameters */
}
- /* only run controller if attitude changed */
- if (fds[0].revents & POLLIN) {
+ /* control mode */
+ orb_check(vehicle_control_mode_sub, &updated);
- perf_begin(mc_loop_perf);
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_control_mode), vehicle_control_mode_sub, &control_mode);
+ }
- /* get a local copy of system state */
- bool updated;
- orb_check(control_mode_sub, &updated);
+ /* manual control setpoint */
+ orb_check(manual_control_setpoint_sub, &updated);
- if (updated) {
- orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
- }
+ if (updated) {
+ orb_copy(ORB_ID(manual_control_setpoint), manual_control_setpoint_sub, &manual);
+ }
- /* get a local copy of manual setpoint */
- orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual);
- /* get a local copy of attitude */
- orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
- /* get a local copy of attitude setpoint */
- orb_copy(ORB_ID(vehicle_attitude_setpoint), att_setpoint_sub, &att_sp);
- /* get a local copy of rates setpoint */
- orb_check(setpoint_sub, &updated);
-
- if (updated) {
- orb_copy(ORB_ID(offboard_control_setpoint), setpoint_sub, &offboard_sp);
- }
+ /* attitude setpoint */
+ orb_check(vehicle_attitude_setpoint_sub, &updated);
- /* get a local copy of status */
- orb_check(status_sub, &updated);
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_attitude_setpoint), vehicle_attitude_setpoint_sub, &att_sp);
+ }
- if (updated) {
- orb_copy(ORB_ID(vehicle_status), status_sub, &status);
- }
+ /* offboard control setpoint */
+ orb_check(offboard_control_setpoint_sub, &updated);
- /* get a local copy of the current sensor values */
- orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw);
+ if (updated) {
+ orb_copy(ORB_ID(offboard_control_setpoint), offboard_control_setpoint_sub, &offboard_sp);
+ }
- /* set flag to safe value */
- control_yaw_position = true;
+ /* vehicle status */
+ orb_check(vehicle_status_sub, &updated);
- /* reset yaw setpoint if not armed */
- if (!control_mode.flag_armed) {
- reset_yaw_sp = true;
- }
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &status);
+ }
- /* define which input is the dominating control input */
- if (control_mode.flag_control_offboard_enabled) {
- /* offboard inputs */
- if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES) {
- rates_sp.roll = offboard_sp.p1;
- rates_sp.pitch = offboard_sp.p2;
- rates_sp.yaw = offboard_sp.p3;
- rates_sp.thrust = offboard_sp.p4;
- rates_sp.timestamp = hrt_absolute_time();
- orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
+ /* sensors */
+ orb_check(sensor_combined_sub, &updated);
- } else if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) {
- att_sp.roll_body = offboard_sp.p1;
- att_sp.pitch_body = offboard_sp.p2;
- att_sp.yaw_body = offboard_sp.p3;
- att_sp.thrust = offboard_sp.p4;
- att_sp.timestamp = hrt_absolute_time();
- /* publish the result to the vehicle actuators */
- orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
- }
+ if (updated) {
+ orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
+ }
- /* reset yaw setpoint after offboard control */
- reset_yaw_sp = true;
+ /* set flag to safe value */
+ control_yaw_position = true;
- } else if (control_mode.flag_control_manual_enabled) {
- /* manual input */
- if (control_mode.flag_control_attitude_enabled) {
- /* control attitude, update attitude setpoint depending on mode */
- if (att_sp.thrust < 0.1f) {
- /* no thrust, don't try to control yaw */
- rates_sp.yaw = 0.0f;
- control_yaw_position = false;
+ /* reset yaw setpoint if not armed */
+ if (!control_mode.flag_armed) {
+ reset_yaw_sp = true;
+ }
- if (status.condition_landed) {
- /* reset yaw setpoint if on ground */
- reset_yaw_sp = true;
- }
+ /* define which input is the dominating control input */
+ if (control_mode.flag_control_offboard_enabled) {
+ /* offboard inputs */
+ if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES) {
+ rates_sp.roll = offboard_sp.p1;
+ rates_sp.pitch = offboard_sp.p2;
+ rates_sp.yaw = offboard_sp.p3;
+ rates_sp.thrust = offboard_sp.p4;
+ rates_sp.timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
- } else {
- /* only move yaw setpoint if manual input is != 0 */
- if (manual.yaw < -yaw_deadzone || yaw_deadzone < manual.yaw) {
- /* control yaw rate */
- control_yaw_position = false;
- rates_sp.yaw = manual.yaw;
- reset_yaw_sp = true; // has no effect on control, just for beautiful log
-
- } else {
- control_yaw_position = true;
- }
- }
+ } else if (offboard_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) {
+ att_sp.roll_body = offboard_sp.p1;
+ att_sp.pitch_body = offboard_sp.p2;
+ att_sp.yaw_body = offboard_sp.p3;
+ att_sp.thrust = offboard_sp.p4;
+ att_sp.timestamp = hrt_absolute_time();
+ /* publish the result to the vehicle actuators */
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
+ }
- if (!control_mode.flag_control_velocity_enabled) {
- /* update attitude setpoint if not in position control mode */
- att_sp.roll_body = manual.roll;
- att_sp.pitch_body = manual.pitch;
+ /* reset yaw setpoint after offboard control */
+ reset_yaw_sp = true;
- if (!control_mode.flag_control_climb_rate_enabled) {
- /* pass throttle directly if not in altitude control mode */
- att_sp.thrust = manual.throttle;
- }
+ } else if (control_mode.flag_control_manual_enabled) {
+ /* manual input */
+ if (control_mode.flag_control_attitude_enabled) {
+ /* control attitude, update attitude setpoint depending on mode */
+ if (att_sp.thrust < 0.1f) {
+ /* no thrust, don't try to control yaw */
+ rates_sp.yaw = 0.0f;
+ control_yaw_position = false;
+
+ if (status.condition_landed) {
+ /* reset yaw setpoint if on ground */
+ reset_yaw_sp = true;
}
- /* reset yaw setpint to current position if needed */
- if (reset_yaw_sp) {
- att_sp.yaw_body = att.yaw;
- reset_yaw_sp = false;
- }
+ } else {
+ /* only move yaw setpoint if manual input is != 0 */
+ if (manual.yaw < -yaw_deadzone || yaw_deadzone < manual.yaw) {
+ /* control yaw rate */
+ control_yaw_position = false;
+ rates_sp.yaw = manual.yaw;
+ reset_yaw_sp = true; // has no effect on control, just for beautiful log
- if (motor_test_mode) {
- printf("testmode");
- att_sp.roll_body = 0.0f;
- att_sp.pitch_body = 0.0f;
- att_sp.yaw_body = 0.0f;
- att_sp.thrust = 0.1f;
+ } else {
+ control_yaw_position = true;
}
+ }
- att_sp.timestamp = hrt_absolute_time();
-
- /* publish the attitude setpoint */
- orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
+ if (!control_mode.flag_control_velocity_enabled) {
+ /* update attitude setpoint if not in position control mode */
+ att_sp.roll_body = manual.roll;
+ att_sp.pitch_body = manual.pitch;
- } else {
- /* manual rate inputs (ACRO), from RC control or joystick */
- if (control_mode.flag_control_rates_enabled) {
- rates_sp.roll = manual.roll;
- rates_sp.pitch = manual.pitch;
- rates_sp.yaw = manual.yaw;
- rates_sp.thrust = manual.throttle;
- rates_sp.timestamp = hrt_absolute_time();
+ if (!control_mode.flag_control_climb_rate_enabled) {
+ /* pass throttle directly if not in altitude control mode */
+ att_sp.thrust = manual.throttle;
}
+ }
+
+ /* reset yaw setpint to current position if needed */
+ if (reset_yaw_sp) {
+ att_sp.yaw_body = att.yaw;
+ reset_yaw_sp = false;
+ }
- /* reset yaw setpoint after ACRO */
- reset_yaw_sp = true;
+ if (motor_test_mode) {
+ printf("testmode");
+ att_sp.roll_body = 0.0f;
+ att_sp.pitch_body = 0.0f;
+ att_sp.yaw_body = 0.0f;
+ att_sp.thrust = 0.1f;
}
+ att_sp.timestamp = hrt_absolute_time();
+
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
+
} else {
- if (!control_mode.flag_control_auto_enabled) {
- /* no control, try to stay on place */
- if (!control_mode.flag_control_velocity_enabled) {
- /* no velocity control, reset attitude setpoint */
- att_sp.roll_body = 0.0f;
- att_sp.pitch_body = 0.0f;
- att_sp.timestamp = hrt_absolute_time();
- orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
- }
+ /* manual rate inputs (ACRO), from RC control or joystick */
+ if (control_mode.flag_control_rates_enabled) {
+ rates_sp.roll = manual.roll;
+ rates_sp.pitch = manual.pitch;
+ rates_sp.yaw = manual.yaw;
+ rates_sp.thrust = manual.throttle;
+ rates_sp.timestamp = hrt_absolute_time();
}
- /* reset yaw setpoint after non-manual control */
+ /* reset yaw setpoint after ACRO */
reset_yaw_sp = true;
}
- /* check if we should we reset integrals */
- bool reset_integral = !control_mode.flag_armed || att_sp.thrust < 0.1f; // TODO use landed status instead of throttle
-
- /* run attitude controller if needed */
- if (control_mode.flag_control_attitude_enabled) {
- multirotor_control_attitude(&att_sp, &att, &rates_sp, control_yaw_position, reset_integral);
- orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
+ } else {
+ if (!control_mode.flag_control_auto_enabled) {
+ /* no control, try to stay on place */
+ if (!control_mode.flag_control_velocity_enabled) {
+ /* no velocity control, reset attitude setpoint */
+ att_sp.roll_body = 0.0f;
+ att_sp.pitch_body = 0.0f;
+ att_sp.timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
+ }
}
- /* measure in what intervals the controller runs */
- perf_count(mc_interval_perf);
+ /* reset yaw setpoint after non-manual control */
+ reset_yaw_sp = true;
+ }
- /* run rates controller if needed */
- if (control_mode.flag_control_rates_enabled) {
- /* get current rate setpoint */
- bool rates_sp_updated = false;
- orb_check(rates_sp_sub, &rates_sp_updated);
+ /* check if we should we reset integrals */
+ bool reset_integral = !control_mode.flag_armed || att_sp.thrust < 0.1f; // TODO use landed status instead of throttle
- if (rates_sp_updated) {
- orb_copy(ORB_ID(vehicle_rates_setpoint), rates_sp_sub, &rates_sp);
- }
+ /* run attitude controller if needed */
+ if (control_mode.flag_control_attitude_enabled) {
+ multirotor_control_attitude(&att_sp, &att, &rates_sp, control_yaw_position, reset_integral);
+ orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp);
+ }
- /* apply controller */
- float rates[3];
- rates[0] = att.rollspeed;
- rates[1] = att.pitchspeed;
- rates[2] = att.yawspeed;
- multirotor_control_rates(&rates_sp, rates, &actuators, reset_integral);
+ /* measure in what intervals the controller runs */
+ perf_count(mc_interval_perf);
- } else {
- /* rates controller disabled, set actuators to zero for safety */
- actuators.control[0] = 0.0f;
- actuators.control[1] = 0.0f;
- actuators.control[2] = 0.0f;
- actuators.control[3] = 0.0f;
+ /* run rates controller if needed */
+ if (control_mode.flag_control_rates_enabled) {
+ /* get current rate setpoint */
+ bool rates_sp_updated = false;
+ orb_check(vehicle_rates_setpoint_sub, &rates_sp_updated);
+
+ if (rates_sp_updated) {
+ orb_copy(ORB_ID(vehicle_rates_setpoint), vehicle_rates_setpoint_sub, &rates_sp);
}
- actuators.timestamp = hrt_absolute_time();
- orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
+ /* apply controller */
+ float rates[3];
+ rates[0] = att.rollspeed;
+ rates[1] = att.pitchspeed;
+ rates[2] = att.yawspeed;
+ multirotor_control_rates(&rates_sp, rates, &actuators, reset_integral);
+
+ } else {
+ /* rates controller disabled, set actuators to zero for safety */
+ actuators.control[0] = 0.0f;
+ actuators.control[1] = 0.0f;
+ actuators.control[2] = 0.0f;
+ actuators.control[3] = 0.0f;
+ }
+
+ actuators.timestamp = hrt_absolute_time();
+ orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
- perf_end(mc_loop_perf);
- } /* end of poll call for attitude updates */
- } /* end of poll return value check */
+ perf_end(mc_loop_perf);
+ }
}
warnx("stopping, disarming motors");
@@ -383,10 +383,9 @@ mc_thread_main(int argc, char *argv[])
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
-
- close(att_sub);
- close(control_mode_sub);
- close(manual_sub);
+ close(vehicle_attitude_sub);
+ close(vehicle_control_mode_sub);
+ close(manual_control_setpoint_sub);
close(actuator_pub);
close(att_sp_pub);
diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c
index 433976656..fd3b72015 100644
--- a/src/modules/px4iofirmware/dsm.c
+++ b/src/modules/px4iofirmware/dsm.c
@@ -285,10 +285,10 @@ dsm_bind(uint16_t cmd, int pulses)
/*Pulse RX pin a number of times*/
for (int i = 0; i < pulses; i++) {
+ up_udelay(25);
stm32_gpiowrite(usart1RxAsOutp, false);
up_udelay(25);
stm32_gpiowrite(usart1RxAsOutp, true);
- up_udelay(25);
}
break;
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 9ef0d3c83..3fcacaf8f 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -68,7 +68,6 @@
#include <systemlib/err.h>
#include <systemlib/perf_counter.h>
-#include <systemlib/ppm_decode.h>
#include <systemlib/airspeed.h>
#include <uORB/uORB.h>
@@ -105,22 +104,22 @@
* IN13 - aux1
* IN14 - aux2
* IN15 - pressure sensor
- *
+ *
* IO:
* IN4 - servo supply rail
* IN5 - analog RSSI
*/
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
- #define ADC_BATTERY_VOLTAGE_CHANNEL 10
- #define ADC_AIRSPEED_VOLTAGE_CHANNEL 11
+#define ADC_BATTERY_VOLTAGE_CHANNEL 10
+#define ADC_AIRSPEED_VOLTAGE_CHANNEL 11
#endif
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
- #define ADC_BATTERY_VOLTAGE_CHANNEL 2
- #define ADC_BATTERY_CURRENT_CHANNEL 3
- #define ADC_5V_RAIL_SENSE 4
- #define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
+#define ADC_BATTERY_VOLTAGE_CHANNEL 2
+#define ADC_BATTERY_CURRENT_CHANNEL 3
+#define ADC_5V_RAIL_SENSE 4
+#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
#endif
#define BAT_VOL_INITIAL 0.f
@@ -134,8 +133,6 @@
*/
#define PCB_TEMP_ESTIMATE_DEG 5.0f
-#define PPM_INPUT_TIMEOUT_INTERVAL 50000 /**< 50 ms timeout / 20 Hz */
-
#define limit_minus_one_to_one(arg) (arg < -1.0f) ? -1.0f : ((arg > 1.0f) ? 1.0f : arg)
/**
@@ -143,70 +140,68 @@
* This enum maps from board attitude to airframe attitude.
*/
enum Rotation {
- ROTATION_NONE = 0,
- ROTATION_YAW_45 = 1,
- ROTATION_YAW_90 = 2,
- ROTATION_YAW_135 = 3,
- ROTATION_YAW_180 = 4,
- ROTATION_YAW_225 = 5,
- ROTATION_YAW_270 = 6,
- ROTATION_YAW_315 = 7,
- ROTATION_ROLL_180 = 8,
- ROTATION_ROLL_180_YAW_45 = 9,
- ROTATION_ROLL_180_YAW_90 = 10,
- ROTATION_ROLL_180_YAW_135 = 11,
- ROTATION_PITCH_180 = 12,
- ROTATION_ROLL_180_YAW_225 = 13,
- ROTATION_ROLL_180_YAW_270 = 14,
- ROTATION_ROLL_180_YAW_315 = 15,
- ROTATION_ROLL_90 = 16,
- ROTATION_ROLL_90_YAW_45 = 17,
- ROTATION_ROLL_90_YAW_90 = 18,
- ROTATION_ROLL_90_YAW_135 = 19,
- ROTATION_ROLL_270 = 20,
- ROTATION_ROLL_270_YAW_45 = 21,
- ROTATION_ROLL_270_YAW_90 = 22,
- ROTATION_ROLL_270_YAW_135 = 23,
- ROTATION_PITCH_90 = 24,
- ROTATION_PITCH_270 = 25,
- ROTATION_MAX
+ ROTATION_NONE = 0,
+ ROTATION_YAW_45 = 1,
+ ROTATION_YAW_90 = 2,
+ ROTATION_YAW_135 = 3,
+ ROTATION_YAW_180 = 4,
+ ROTATION_YAW_225 = 5,
+ ROTATION_YAW_270 = 6,
+ ROTATION_YAW_315 = 7,
+ ROTATION_ROLL_180 = 8,
+ ROTATION_ROLL_180_YAW_45 = 9,
+ ROTATION_ROLL_180_YAW_90 = 10,
+ ROTATION_ROLL_180_YAW_135 = 11,
+ ROTATION_PITCH_180 = 12,
+ ROTATION_ROLL_180_YAW_225 = 13,
+ ROTATION_ROLL_180_YAW_270 = 14,
+ ROTATION_ROLL_180_YAW_315 = 15,
+ ROTATION_ROLL_90 = 16,
+ ROTATION_ROLL_90_YAW_45 = 17,
+ ROTATION_ROLL_90_YAW_90 = 18,
+ ROTATION_ROLL_90_YAW_135 = 19,
+ ROTATION_ROLL_270 = 20,
+ ROTATION_ROLL_270_YAW_45 = 21,
+ ROTATION_ROLL_270_YAW_90 = 22,
+ ROTATION_ROLL_270_YAW_135 = 23,
+ ROTATION_PITCH_90 = 24,
+ ROTATION_PITCH_270 = 25,
+ ROTATION_MAX
};
-typedef struct
-{
- uint16_t roll;
- uint16_t pitch;
- uint16_t yaw;
+typedef struct {
+ uint16_t roll;
+ uint16_t pitch;
+ uint16_t yaw;
} rot_lookup_t;
-const rot_lookup_t rot_lookup[] =
-{
- { 0, 0, 0 },
- { 0, 0, 45 },
- { 0, 0, 90 },
- { 0, 0, 135 },
- { 0, 0, 180 },
- { 0, 0, 225 },
- { 0, 0, 270 },
- { 0, 0, 315 },
- {180, 0, 0 },
- {180, 0, 45 },
- {180, 0, 90 },
- {180, 0, 135 },
- { 0, 180, 0 },
- {180, 0, 225 },
- {180, 0, 270 },
- {180, 0, 315 },
- { 90, 0, 0 },
- { 90, 0, 45 },
- { 90, 0, 90 },
- { 90, 0, 135 },
- {270, 0, 0 },
- {270, 0, 45 },
- {270, 0, 90 },
- {270, 0, 135 },
- { 0, 90, 0 },
- { 0, 270, 0 }
+const rot_lookup_t rot_lookup[] = {
+ { 0, 0, 0 },
+ { 0, 0, 45 },
+ { 0, 0, 90 },
+ { 0, 0, 135 },
+ { 0, 0, 180 },
+ { 0, 0, 225 },
+ { 0, 0, 270 },
+ { 0, 0, 315 },
+ {180, 0, 0 },
+ {180, 0, 45 },
+ {180, 0, 90 },
+ {180, 0, 135 },
+ { 0, 180, 0 },
+ {180, 0, 225 },
+ {180, 0, 270 },
+ {180, 0, 315 },
+ { 90, 0, 0 },
+ { 90, 0, 45 },
+ { 90, 0, 90 },
+ { 90, 0, 135 },
+ {270, 0, 0 },
+ {270, 0, 45 },
+ {270, 0, 90 },
+ {270, 0, 135 },
+ { 0, 90, 0 },
+ { 0, 270, 0 }
};
/**
@@ -239,12 +234,12 @@ public:
private:
static const unsigned _rc_max_chan_count = RC_CHANNELS_MAX; /**< maximum number of r/c channels we handle */
- hrt_abstime _ppm_last_valid; /**< last time we got a valid ppm signal */
+ hrt_abstime _rc_last_valid; /**< last time we got a valid RC signal */
/**
- * Gather and publish PPM input data.
+ * Gather and publish RC input data.
*/
- void ppm_poll();
+ void rc_poll();
/* XXX should not be here - should be own driver */
int _fd_adc; /**< ADC driver handle */
@@ -501,7 +496,7 @@ Sensors *g_sensors = nullptr;
}
Sensors::Sensors() :
- _ppm_last_valid(0),
+ _rc_last_valid(0),
_fd_adc(-1),
_last_adc(0),
@@ -532,8 +527,8 @@ Sensors::Sensors() :
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "sensor task update")),
- _board_rotation(3,3),
- _external_mag_rotation(3,3),
+ _board_rotation(3, 3),
+ _external_mag_rotation(3, 3),
_mag_is_external(false)
{
@@ -660,9 +655,9 @@ int
Sensors::parameters_update()
{
bool rc_valid = true;
- float tmpScaleFactor = 0.0f;
- float tmpRevFactor = 0.0f;
-
+ float tmpScaleFactor = 0.0f;
+ float tmpRevFactor = 0.0f;
+
/* rc values */
for (unsigned int i = 0; i < RC_CHANNELS_MAX; i++) {
@@ -674,19 +669,19 @@ Sensors::parameters_update()
tmpScaleFactor = (1.0f / ((_parameters.max[i] - _parameters.min[i]) / 2.0f) * _parameters.rev[i]);
tmpRevFactor = tmpScaleFactor * _parameters.rev[i];
-
+
/* handle blowup in the scaling factor calculation */
if (!isfinite(tmpScaleFactor) ||
(tmpRevFactor < 0.000001f) ||
- (tmpRevFactor > 0.2f) ) {
+ (tmpRevFactor > 0.2f)) {
warnx("RC chan %u not sane, scaling: %8.6f, rev: %d", i, tmpScaleFactor, (int)(_parameters.rev[i]));
/* scaling factors do not make sense, lock them down */
_parameters.scaling_factor[i] = 0.0f;
rc_valid = false;
+
+ } else {
+ _parameters.scaling_factor[i] = tmpScaleFactor;
}
- else {
- _parameters.scaling_factor[i] = tmpScaleFactor;
- }
}
/* handle wrong values */
@@ -812,7 +807,7 @@ void
Sensors::get_rot_matrix(enum Rotation rot, math::Matrix *rot_matrix)
{
/* first set to zero */
- rot_matrix->Matrix::zero(3,3);
+ rot_matrix->Matrix::zero(3, 3);
float roll = M_DEG_TO_RAD_F * (float)rot_lookup[rot].roll;
float pitch = M_DEG_TO_RAD_F * (float)rot_lookup[rot].pitch;
@@ -823,7 +818,7 @@ Sensors::get_rot_matrix(enum Rotation rot, math::Matrix *rot_matrix)
math::Dcm R(euler);
for (int i = 0; i < 3; i++) for (int j = 0; j < 3; j++)
- (*rot_matrix)(i,j) = R(i, j);
+ (*rot_matrix)(i, j) = R(i, j);
}
void
@@ -841,7 +836,7 @@ Sensors::accel_init()
// XXX do the check more elegantly
- #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
/* set the accel internal sampling rate up to at leat 1000Hz */
ioctl(fd, ACCELIOCSSAMPLERATE, 1000);
@@ -849,7 +844,7 @@ Sensors::accel_init()
/* set the driver to poll at 1000Hz */
ioctl(fd, SENSORIOCSPOLLRATE, 1000);
- #elif CONFIG_ARCH_BOARD_PX4FMU_V2
+#elif CONFIG_ARCH_BOARD_PX4FMU_V2
/* set the accel internal sampling rate up to at leat 800Hz */
ioctl(fd, ACCELIOCSSAMPLERATE, 800);
@@ -857,10 +852,10 @@ Sensors::accel_init()
/* set the driver to poll at 800Hz */
ioctl(fd, SENSORIOCSPOLLRATE, 800);
- #else
- #error Need a board configuration, either CONFIG_ARCH_BOARD_PX4FMU_V1 or CONFIG_ARCH_BOARD_PX4FMU_V2
+#else
+#error Need a board configuration, either CONFIG_ARCH_BOARD_PX4FMU_V1 or CONFIG_ARCH_BOARD_PX4FMU_V2
- #endif
+#endif
warnx("using system accel");
close(fd);
@@ -882,7 +877,7 @@ Sensors::gyro_init()
// XXX do the check more elegantly
- #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
/* set the gyro internal sampling rate up to at least 1000Hz */
if (ioctl(fd, GYROIOCSSAMPLERATE, 1000) != OK)
@@ -892,7 +887,7 @@ Sensors::gyro_init()
if (ioctl(fd, SENSORIOCSPOLLRATE, 1000) != OK)
ioctl(fd, SENSORIOCSPOLLRATE, 800);
- #else
+#else
/* set the gyro internal sampling rate up to at least 760Hz */
ioctl(fd, GYROIOCSSAMPLERATE, 760);
@@ -900,7 +895,7 @@ Sensors::gyro_init()
/* set the driver to poll at 760Hz */
ioctl(fd, SENSORIOCSPOLLRATE, 760);
- #endif
+#endif
warnx("using system gyro");
close(fd);
@@ -924,23 +919,28 @@ Sensors::mag_init()
ret = ioctl(fd, MAGIOCSSAMPLERATE, 150);
+
if (ret == OK) {
/* set the pollrate accordingly */
ioctl(fd, SENSORIOCSPOLLRATE, 150);
+
} else {
ret = ioctl(fd, MAGIOCSSAMPLERATE, 100);
+
/* if the slower sampling rate still fails, something is wrong */
if (ret == OK) {
/* set the driver to poll also at the slower rate */
ioctl(fd, SENSORIOCSPOLLRATE, 100);
+
} else {
errx(1, "FATAL: mag sampling rate could not be set");
}
}
-
+
ret = ioctl(fd, MAGIOCGEXTERNAL, 0);
+
if (ret < 0)
errx(1, "FATAL: unknown if magnetometer is external or onboard");
else if (ret == 1)
@@ -993,7 +993,7 @@ Sensors::accel_poll(struct sensor_combined_s &raw)
orb_copy(ORB_ID(sensor_accel), _accel_sub, &accel_report);
math::Vector3 vect = {accel_report.x, accel_report.y, accel_report.z};
- vect = _board_rotation*vect;
+ vect = _board_rotation * vect;
raw.accelerometer_m_s2[0] = vect(0);
raw.accelerometer_m_s2[1] = vect(1);
@@ -1019,7 +1019,7 @@ Sensors::gyro_poll(struct sensor_combined_s &raw)
orb_copy(ORB_ID(sensor_gyro), _gyro_sub, &gyro_report);
math::Vector3 vect = {gyro_report.x, gyro_report.y, gyro_report.z};
- vect = _board_rotation*vect;
+ vect = _board_rotation * vect;
raw.gyro_rad_s[0] = vect(0);
raw.gyro_rad_s[1] = vect(1);
@@ -1047,9 +1047,9 @@ Sensors::mag_poll(struct sensor_combined_s &raw)
math::Vector3 vect = {mag_report.x, mag_report.y, mag_report.z};
if (_mag_is_external)
- vect = _external_mag_rotation*vect;
+ vect = _external_mag_rotation * vect;
else
- vect = _board_rotation*vect;
+ vect = _board_rotation * vect;
raw.magnetometer_ga[0] = vect(0);
raw.magnetometer_ga[1] = vect(1);
@@ -1094,8 +1094,8 @@ Sensors::diff_pres_poll(struct sensor_combined_s &raw)
raw.differential_pressure_counter++;
_airspeed.indicated_airspeed_m_s = calc_indicated_airspeed(_diff_pres.differential_pressure_pa);
- _airspeed.true_airspeed_m_s = calc_true_airspeed(_diff_pres.differential_pressure_pa + raw.baro_pres_mbar*1e2f,
- raw.baro_pres_mbar*1e2f, raw.baro_temp_celcius - PCB_TEMP_ESTIMATE_DEG);
+ _airspeed.true_airspeed_m_s = calc_true_airspeed(_diff_pres.differential_pressure_pa + raw.baro_pres_mbar * 1e2f,
+ raw.baro_pres_mbar * 1e2f, raw.baro_temp_celcius - PCB_TEMP_ESTIMATE_DEG);
/* announce the airspeed if needed, just publish else */
if (_airspeed_pub > 0) {
@@ -1236,12 +1236,12 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
int ret = read(_fd_adc, &buf_adc, sizeof(buf_adc));
for (unsigned i = 0; i < sizeof(buf_adc) / sizeof(buf_adc[0]); i++) {
-
+
if (ret >= (int)sizeof(buf_adc[0])) {
/* Save raw voltage values */
if (i < (sizeof(raw.adc_voltage_v)) / sizeof(raw.adc_voltage_v[0])) {
- raw.adc_voltage_v[i] = buf_adc[i].am_data / (4096.0f / 3.3f);
+ raw.adc_voltage_v[i] = buf_adc[i].am_data / (4096.0f / 3.3f);
}
/* look for specific channels and process the raw voltage to measurement data */
@@ -1269,12 +1269,12 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
} else {
_battery_pub = orb_advertise(ORB_ID(battery_status), &_battery_status);
}
- }
+ }
} else if (ADC_AIRSPEED_VOLTAGE_CHANNEL == buf_adc[i].am_channel) {
/* calculate airspeed, raw is the difference from */
- float voltage = (float)(buf_adc[i].am_data ) * 3.3f / 4096.0f * 2.0f; //V_ref/4096 * (voltage divider factor)
+ float voltage = (float)(buf_adc[i].am_data) * 3.3f / 4096.0f * 2.0f; //V_ref/4096 * (voltage divider factor)
/**
* The voltage divider pulls the signal down, only act on
@@ -1306,17 +1306,13 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
}
void
-Sensors::ppm_poll()
+Sensors::rc_poll()
{
+ bool rc_updated;
+ orb_check(_rc_sub, &rc_updated);
- /* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */
- struct pollfd fds[1];
- fds[0].fd = _rc_sub;
- fds[0].events = POLLIN;
- /* check non-blocking for new data */
- int poll_ret = poll(fds, 1, 0);
-
- if (poll_ret > 0) {
+ if (rc_updated) {
+ /* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */
struct rc_input_values rc_input;
orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input);
@@ -1352,7 +1348,7 @@ Sensors::ppm_poll()
channel_limit = _rc_max_chan_count;
/* we are accepting this message */
- _ppm_last_valid = rc_input.timestamp;
+ _rc_last_valid = rc_input.timestamp;
/* Read out values from raw message */
for (unsigned int i = 0; i < channel_limit; i++) {
@@ -1362,6 +1358,7 @@ Sensors::ppm_poll()
*/
if (rc_input.values[i] < _parameters.min[i])
rc_input.values[i] = _parameters.min[i];
+
if (rc_input.values[i] > _parameters.max[i])
rc_input.values[i] = _parameters.max[i];
@@ -1622,7 +1619,7 @@ Sensors::task_main()
orb_publish(ORB_ID(sensor_combined), _sensor_pub, &raw);
/* Look for new r/c input data */
- ppm_poll();
+ rc_poll();
perf_end(_loop_perf);
}
@@ -1640,11 +1637,11 @@ Sensors::start()
/* start the task */
_sensors_task = task_spawn_cmd("sensors_task",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 5,
- 2048,
- (main_t)&Sensors::task_main_trampoline,
- nullptr);
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 2048,
+ (main_t)&Sensors::task_main_trampoline,
+ nullptr);
if (_sensors_task < 0) {
warn("task start failed");
diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h
index 093c6775d..38fb74c9b 100644
--- a/src/modules/uORB/topics/vehicle_control_mode.h
+++ b/src/modules/uORB/topics/vehicle_control_mode.h
@@ -61,7 +61,6 @@
*/
struct vehicle_control_mode_s
{
- uint16_t counter; /**< incremented by the writing thread every time new data is stored */
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
bool flag_armed;