aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-11-05 08:42:20 +0100
committerLorenz Meier <lm@inf.ethz.ch>2013-11-05 08:42:20 +0100
commitd7064884dbba80514fee6946ead41613466fa571 (patch)
tree856e985c61794537867165cfae59cfcd2588e4a2 /src/modules
parent5a5d758ce4dc72d3eb5809124134247c4cc0038f (diff)
parent1358d4cb88e70370014410353faf3e51afb1ceb6 (diff)
downloadpx4-firmware-d7064884dbba80514fee6946ead41613466fa571.tar.gz
px4-firmware-d7064884dbba80514fee6946ead41613466fa571.tar.bz2
px4-firmware-d7064884dbba80514fee6946ead41613466fa571.zip
Merge branch 'master' into fw_autoland
nored, and an empty message aborts
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/att_pos_estimator_ekf/KalmanNav.cpp9
-rw-r--r--src/modules/commander/commander.cpp18
-rw-r--r--src/modules/commander/mag_calibration.cpp29
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp67
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp5
-rw-r--r--src/modules/px4iofirmware/registers.c28
-rw-r--r--src/modules/systemlib/mixer/mixer.h1
-rw-r--r--src/modules/systemlib/mixer/mixer_multirotor.cpp15
-rwxr-xr-xsrc/modules/systemlib/mixer/multi_tables13
-rw-r--r--src/modules/uORB/uORB.cpp4
10 files changed, 116 insertions, 73 deletions
diff --git a/src/modules/att_pos_estimator_ekf/KalmanNav.cpp b/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
index 33879892e..18fb6dcbc 100644
--- a/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
+++ b/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
@@ -34,7 +34,7 @@
/**
* @file KalmanNav.cpp
*
- * kalman filter navigation code
+ * Kalman filter navigation code
*/
#include <poll.h>
@@ -228,10 +228,7 @@ void KalmanNav::update()
updateSubscriptions();
// initialize attitude when sensors online
- if (!_attitudeInitialized && sensorsUpdate &&
- _sensors.accelerometer_counter > 10 &&
- _sensors.gyro_counter > 10 &&
- _sensors.magnetometer_counter > 10) {
+ if (!_attitudeInitialized && sensorsUpdate) {
if (correctAtt() == ret_ok) _attitudeInitCounter++;
if (_attitudeInitCounter > 100) {
@@ -643,7 +640,7 @@ int KalmanNav::correctAtt()
if (beta > _faultAtt.get()) {
warnx("fault in attitude: beta = %8.4f", (double)beta);
- warnx("y:\n"); y.print();
+ warnx("y:"); y.print();
}
// update quaternions from euler
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 44a144296..ed090271c 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -199,7 +199,7 @@ void handle_command(struct vehicle_status_s *status, struct vehicle_control_mode
*/
int commander_thread_main(int argc, char *argv[]);
-void control_status_leds(vehicle_status_s *status, actuator_armed_s *armed, bool changed);
+void control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_armed, bool changed);
void check_valid(hrt_abstime timestamp, hrt_abstime timeout, bool valid_in, bool *valid_out, bool *changed);
@@ -843,6 +843,12 @@ int commander_thread_main(int argc, char *argv[])
if (updated) {
orb_copy(ORB_ID(safety), safety_sub, &safety);
+
+ // XXX this would be the right approach to do it, but do we *WANT* this?
+ // /* disarm if safety is now on and still armed */
+ // if (safety.safety_switch_available && !safety.safety_off) {
+ // (void)arming_state_transition(&status, &safety, &control_mode, ARMING_STATE_STANDBY, &armed);
+ // }
}
/* update global position estimate */
@@ -1219,7 +1225,7 @@ int commander_thread_main(int argc, char *argv[])
}
/* play arming and battery warning tunes */
- if (!arm_tune_played && armed.armed) {
+ if (!arm_tune_played && armed.armed && (!safety.safety_switch_available || (safety.safety_switch_available && safety.safety_off))) {
/* play tune when armed */
if (tune_arm() == OK)
arm_tune_played = true;
@@ -1240,7 +1246,7 @@ int commander_thread_main(int argc, char *argv[])
}
/* reset arm_tune_played when disarmed */
- if (!(armed.armed && (!safety.safety_switch_available || (safety.safety_off && safety.safety_switch_available)))) {
+ if (status.arming_state != ARMING_STATE_ARMED || (safety.safety_switch_available && !safety.safety_off)) {
arm_tune_played = false;
}
@@ -1309,7 +1315,7 @@ check_valid(hrt_abstime timestamp, hrt_abstime timeout, bool valid_in, bool *val
}
void
-control_status_leds(vehicle_status_s *status, actuator_armed_s *armed, bool changed)
+control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_armed, bool changed)
{
/* driving rgbled */
if (changed) {
@@ -1356,11 +1362,11 @@ control_status_leds(vehicle_status_s *status, actuator_armed_s *armed, bool chan
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
/* this runs at around 20Hz, full cycle is 16 ticks = 10/16Hz */
- if (armed->armed) {
+ if (actuator_armed->armed) {
/* armed, solid */
led_on(LED_BLUE);
- } else if (armed->ready_to_arm) {
+ } else if (actuator_armed->ready_to_arm) {
/* ready to arm, blink at 1Hz */
if (leds_counter % 20 == 0)
led_toggle(LED_BLUE);
diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp
index 09f4104f8..4ebf266f4 100644
--- a/src/modules/commander/mag_calibration.cpp
+++ b/src/modules/commander/mag_calibration.cpp
@@ -73,7 +73,7 @@ int do_mag_calibration(int mavlink_fd)
/* maximum 500 values */
const unsigned int calibration_maxcount = 500;
- unsigned int calibration_counter = 0;
+ unsigned int calibration_counter;
struct mag_scale mscale_null = {
0.0f,
@@ -99,28 +99,34 @@ int do_mag_calibration(int mavlink_fd)
res = ioctl(fd, MAGIOCCALIBRATE, fd);
if (res != OK) {
- mavlink_log_critical(mavlink_fd, "ERROR: failed to calibrate scale");
+ mavlink_log_critical(mavlink_fd, "Skipped scale calibration");
+ /* this is non-fatal - mark it accordingly */
+ res = OK;
}
}
close(fd);
- float *x;
- float *y;
- float *z;
+ float *x = NULL;
+ float *y = NULL;
+ float *z = NULL;
if (res == OK) {
/* allocate memory */
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20);
- x = (float *)malloc(sizeof(float) * calibration_maxcount);
- y = (float *)malloc(sizeof(float) * calibration_maxcount);
- z = (float *)malloc(sizeof(float) * calibration_maxcount);
+ x = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_maxcount));
+ y = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_maxcount));
+ z = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_maxcount));
if (x == NULL || y == NULL || z == NULL) {
mavlink_log_critical(mavlink_fd, "ERROR: out of memory");
res = ERROR;
+ return res;
}
+ } else {
+ /* exit */
+ return ERROR;
}
if (res == OK) {
@@ -136,6 +142,8 @@ int do_mag_calibration(int mavlink_fd)
mavlink_log_info(mavlink_fd, "rotate in a figure 8 around all axis");
+ calibration_counter = 0;
+
while (hrt_absolute_time() < calibration_deadline &&
calibration_counter < calibration_maxcount) {
@@ -178,6 +186,7 @@ int do_mag_calibration(int mavlink_fd)
float sphere_radius;
if (res == OK) {
+
/* sphere fit */
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 70);
sphere_fit_least_squares(x, y, z, calibration_counter, 100, 0.0f, &sphere_x, &sphere_y, &sphere_z, &sphere_radius);
@@ -270,7 +279,7 @@ int do_mag_calibration(int mavlink_fd)
} else {
mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
}
-
- return res;
}
+
+ return res;
}
diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp
index eb67874db..00a0dcd61 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -279,20 +279,20 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_parameter_handles.p_i = param_find("FW_P_I");
_parameter_handles.p_rmax_pos = param_find("FW_P_RMAX_POS");
_parameter_handles.p_rmax_neg = param_find("FW_P_RMAX_NEG");
- _parameter_handles.p_integrator_max = param_find("FW_P_integrator_max");
+ _parameter_handles.p_integrator_max = param_find("FW_P_IMAX");
_parameter_handles.p_roll_feedforward = param_find("FW_P_ROLLFF");
_parameter_handles.r_p = param_find("FW_R_P");
_parameter_handles.r_d = param_find("FW_R_D");
_parameter_handles.r_i = param_find("FW_R_I");
- _parameter_handles.r_integrator_max = param_find("FW_R_integrator_max");
+ _parameter_handles.r_integrator_max = param_find("FW_R_IMAX");
_parameter_handles.r_rmax = param_find("FW_R_RMAX");
_parameter_handles.y_p = param_find("FW_Y_P");
_parameter_handles.y_i = param_find("FW_Y_I");
_parameter_handles.y_d = param_find("FW_Y_D");
_parameter_handles.y_roll_feedforward = param_find("FW_Y_ROLLFF");
- _parameter_handles.y_integrator_max = param_find("FW_Y_integrator_max");
+ _parameter_handles.y_integrator_max = param_find("FW_Y_IMAX");
_parameter_handles.airspeed_min = param_find("FW_AIRSPD_MIN");
_parameter_handles.airspeed_trim = param_find("FW_AIRSPD_TRIM");
@@ -635,43 +635,46 @@ FixedwingAttitudeControl::task_main()
}
}
- float roll_rad = _roll_ctrl.control(roll_sp, _att.roll, _att.rollspeed,
- airspeed_scaling, lock_integrator, _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
- _actuators.control[0] = (isfinite(roll_rad)) ? roll_rad * actuator_scaling : 0.0f;
+ if (isfinite(roll_sp) && isfinite(pitch_sp)) {
- float pitch_rad = _pitch_ctrl.control(pitch_sp, _att.pitch, _att.pitchspeed, _att.roll, airspeed_scaling,
- lock_integrator, _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
- _actuators.control[1] = (isfinite(pitch_rad)) ? pitch_rad * actuator_scaling : 0.0f;
+ float roll_rad = _roll_ctrl.control(roll_sp, _att.roll, _att.rollspeed,
+ airspeed_scaling, lock_integrator, _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
+ _actuators.control[0] = (isfinite(roll_rad)) ? roll_rad * actuator_scaling : 0.0f;
- float yaw_rad = _yaw_ctrl.control(_att.roll, _att.yawspeed, _accel.y, airspeed_scaling, lock_integrator,
- _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
- _actuators.control[2] = (isfinite(yaw_rad)) ? yaw_rad * actuator_scaling : 0.0f;
+ float pitch_rad = _pitch_ctrl.control(pitch_sp, _att.pitch, _att.pitchspeed, _att.roll, airspeed_scaling,
+ lock_integrator, _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
+ _actuators.control[1] = (isfinite(pitch_rad)) ? pitch_rad * actuator_scaling : 0.0f;
- /* throttle passed through */
- _actuators.control[3] = (isfinite(throttle_sp)) ? throttle_sp : 0.0f;
+ float yaw_rad = _yaw_ctrl.control(_att.roll, _att.yawspeed, _accel.y, airspeed_scaling, lock_integrator,
+ _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
+ _actuators.control[2] = (isfinite(yaw_rad)) ? yaw_rad * actuator_scaling : 0.0f;
- // warnx("aspd: %s: %6.2f, aspd scaling: %6.2f, controls: %5.2f %5.2f %5.2f %5.2f", (_airspeed_valid) ? "valid" : "unknown",
- // airspeed, airspeed_scaling, _actuators.control[0], _actuators.control[1],
- // _actuators.control[2], _actuators.control[3]);
+ /* throttle passed through */
+ _actuators.control[3] = (isfinite(throttle_sp)) ? throttle_sp : 0.0f;
- /*
- * Lazily publish the rate setpoint (for analysis, the actuators are published below)
- * only once available
- */
- vehicle_rates_setpoint_s rates_sp;
- rates_sp.roll = _roll_ctrl.get_desired_rate();
- rates_sp.pitch = _pitch_ctrl.get_desired_rate();
- rates_sp.yaw = 0.0f; // XXX not yet implemented
+ // warnx("aspd: %s: %6.2f, aspd scaling: %6.2f, controls: %5.2f %5.2f %5.2f %5.2f", (_airspeed_valid) ? "valid" : "unknown",
+ // airspeed, airspeed_scaling, _actuators.control[0], _actuators.control[1],
+ // _actuators.control[2], _actuators.control[3]);
- rates_sp.timestamp = hrt_absolute_time();
+ /*
+ * Lazily publish the rate setpoint (for analysis, the actuators are published below)
+ * only once available
+ */
+ vehicle_rates_setpoint_s rates_sp;
+ rates_sp.roll = _roll_ctrl.get_desired_rate();
+ rates_sp.pitch = _pitch_ctrl.get_desired_rate();
+ rates_sp.yaw = 0.0f; // XXX not yet implemented
- if (_rate_sp_pub > 0) {
- /* publish the attitude setpoint */
- orb_publish(ORB_ID(vehicle_rates_setpoint), _rate_sp_pub, &rates_sp);
+ rates_sp.timestamp = hrt_absolute_time();
- } else {
- /* advertise and publish */
- _rate_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
+ if (_rate_sp_pub > 0) {
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(vehicle_rates_setpoint), _rate_sp_pub, &rates_sp);
+
+ } else {
+ /* advertise and publish */
+ _rate_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
+ }
}
} else {
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index 1a263b741..536380129 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -470,7 +470,7 @@ FixedwingPositionControl::parameters_update()
_tecs.set_speed_weight(_parameters.speed_weight);
_tecs.set_pitch_damping(_parameters.pitch_damping);
_tecs.set_indicated_airspeed_min(_parameters.airspeed_min);
- _tecs.set_indicated_airspeed_max(_parameters.airspeed_min);
+ _tecs.set_indicated_airspeed_max(_parameters.airspeed_max);
_tecs.set_max_climb_rate(_parameters.max_climb_rate);
/* sanity check parameters */
@@ -520,7 +520,6 @@ FixedwingPositionControl::vehicle_airspeed_poll()
orb_copy(ORB_ID(airspeed), _airspeed_sub, &_airspeed);
_airspeed_valid = true;
_airspeed_last_valid = hrt_absolute_time();
- return true;
} else {
@@ -533,7 +532,7 @@ FixedwingPositionControl::vehicle_airspeed_poll()
/* update TECS state */
_tecs.enable_airspeed(_airspeed_valid);
- return false;
+ return airspeed_updated;
}
void
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index 40597adf1..86a40bc22 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -207,7 +207,7 @@ uint16_t r_page_servo_failsafe[PX4IO_SERVO_COUNT] = { 0, 0, 0, 0, 0, 0, 0, 0 };
* minimum PWM values when armed
*
*/
-uint16_t r_page_servo_control_min[PX4IO_SERVO_COUNT] = { PWM_MIN, PWM_MIN, PWM_MIN, PWM_MIN, PWM_MIN, PWM_MIN, PWM_MIN, PWM_MIN };
+uint16_t r_page_servo_control_min[PX4IO_SERVO_COUNT] = { PWM_DEFAULT_MIN, PWM_DEFAULT_MIN, PWM_DEFAULT_MIN, PWM_DEFAULT_MIN, PWM_DEFAULT_MIN, PWM_DEFAULT_MIN, PWM_DEFAULT_MIN, PWM_DEFAULT_MIN };
/**
* PAGE 107
@@ -215,7 +215,7 @@ uint16_t r_page_servo_control_min[PX4IO_SERVO_COUNT] = { PWM_MIN, PWM_MIN, PWM_
* maximum PWM values when armed
*
*/
-uint16_t r_page_servo_control_max[PX4IO_SERVO_COUNT] = { PWM_MAX, PWM_MAX, PWM_MAX, PWM_MAX, PWM_MAX, PWM_MAX, PWM_MAX, PWM_MAX };
+uint16_t r_page_servo_control_max[PX4IO_SERVO_COUNT] = { PWM_DEFAULT_MAX, PWM_DEFAULT_MAX, PWM_DEFAULT_MAX, PWM_DEFAULT_MAX, PWM_DEFAULT_MAX, PWM_DEFAULT_MAX, PWM_DEFAULT_MAX, PWM_DEFAULT_MAX };
/**
* PAGE 108
@@ -278,10 +278,10 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
if (*values == 0) {
/* ignore 0 */
- } else if (*values < PWM_MIN) {
- r_page_servo_failsafe[offset] = PWM_MIN;
- } else if (*values > PWM_MAX) {
- r_page_servo_failsafe[offset] = PWM_MAX;
+ } else if (*values < PWM_LOWEST_MIN) {
+ r_page_servo_failsafe[offset] = PWM_LOWEST_MIN;
+ } else if (*values > PWM_HIGHEST_MAX) {
+ r_page_servo_failsafe[offset] = PWM_HIGHEST_MAX;
} else {
r_page_servo_failsafe[offset] = *values;
}
@@ -304,8 +304,8 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
/* ignore 0 */
} else if (*values > PWM_HIGHEST_MIN) {
r_page_servo_control_min[offset] = PWM_HIGHEST_MIN;
- } else if (*values < PWM_MIN) {
- r_page_servo_control_min[offset] = PWM_MIN;
+ } else if (*values < PWM_LOWEST_MIN) {
+ r_page_servo_control_min[offset] = PWM_LOWEST_MIN;
} else {
r_page_servo_control_min[offset] = *values;
}
@@ -323,8 +323,8 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
if (*values == 0) {
/* ignore 0 */
- } else if (*values > PWM_MAX) {
- r_page_servo_control_max[offset] = PWM_MAX;
+ } else if (*values > PWM_HIGHEST_MAX) {
+ r_page_servo_control_max[offset] = PWM_HIGHEST_MAX;
} else if (*values < PWM_LOWEST_MAX) {
r_page_servo_control_max[offset] = PWM_LOWEST_MAX;
} else {
@@ -348,11 +348,11 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
if (*values == 0) {
/* 0 means disabling always PWM */
r_page_servo_disarmed[offset] = 0;
- } else if (*values < PWM_MIN) {
- r_page_servo_disarmed[offset] = PWM_MIN;
+ } else if (*values < PWM_LOWEST_MIN) {
+ r_page_servo_disarmed[offset] = PWM_LOWEST_MIN;
all_disarmed_off = false;
- } else if (*values > PWM_MAX) {
- r_page_servo_disarmed[offset] = PWM_MAX;
+ } else if (*values > PWM_HIGHEST_MAX) {
+ r_page_servo_disarmed[offset] = PWM_HIGHEST_MAX;
all_disarmed_off = false;
} else {
r_page_servo_disarmed[offset] = *values;
diff --git a/src/modules/systemlib/mixer/mixer.h b/src/modules/systemlib/mixer/mixer.h
index 723bf9f3b..1c889a811 100644
--- a/src/modules/systemlib/mixer/mixer.h
+++ b/src/modules/systemlib/mixer/mixer.h
@@ -449,6 +449,7 @@ public:
HEX_PLUS, /**< hex in + configuration */
OCTA_X,
OCTA_PLUS,
+ OCTA_COX,
MAX_GEOMETRY
};
diff --git a/src/modules/systemlib/mixer/mixer_multirotor.cpp b/src/modules/systemlib/mixer/mixer_multirotor.cpp
index b89f341b6..bf77795d5 100644
--- a/src/modules/systemlib/mixer/mixer_multirotor.cpp
+++ b/src/modules/systemlib/mixer/mixer_multirotor.cpp
@@ -130,6 +130,16 @@ const MultirotorMixer::Rotor _config_octa_plus[] = {
{ 1.000000, 0.000000, -1.00 },
{ -1.000000, 0.000000, -1.00 },
};
+const MultirotorMixer::Rotor _config_octa_cox[] = {
+ { -0.707107, 0.707107, 1.00 },
+ { 0.707107, 0.707107, -1.00 },
+ { 0.707107, -0.707107, 1.00 },
+ { -0.707107, -0.707107, -1.00 },
+ { 0.707107, 0.707107, 1.00 },
+ { -0.707107, 0.707107, -1.00 },
+ { -0.707107, -0.707107, 1.00 },
+ { 0.707107, -0.707107, -1.00 },
+};
const MultirotorMixer::Rotor *_config_index[MultirotorMixer::MAX_GEOMETRY] = {
&_config_quad_x[0],
&_config_quad_plus[0],
@@ -139,6 +149,7 @@ const MultirotorMixer::Rotor *_config_index[MultirotorMixer::MAX_GEOMETRY] = {
&_config_hex_plus[0],
&_config_octa_x[0],
&_config_octa_plus[0],
+ &_config_octa_cox[0],
};
const unsigned _config_rotor_count[MultirotorMixer::MAX_GEOMETRY] = {
4, /* quad_x */
@@ -149,6 +160,7 @@ const unsigned _config_rotor_count[MultirotorMixer::MAX_GEOMETRY] = {
6, /* hex_plus */
8, /* octa_x */
8, /* octa_plus */
+ 8, /* octa_cox */
};
}
@@ -240,6 +252,9 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
} else if (!strcmp(geomname, "8x")) {
geometry = MultirotorMixer::OCTA_X;
+
+ } else if (!strcmp(geomname, "8c")) {
+ geometry = MultirotorMixer::OCTA_COX;
} else {
debug("unrecognised geometry '%s'", geomname);
diff --git a/src/modules/systemlib/mixer/multi_tables b/src/modules/systemlib/mixer/multi_tables
index 683c63040..050bf2f47 100755
--- a/src/modules/systemlib/mixer/multi_tables
+++ b/src/modules/systemlib/mixer/multi_tables
@@ -74,7 +74,18 @@ set octa_plus {
90 CW
}
-set tables {quad_x quad_plus quad_v quad_wide hex_x hex_plus octa_x octa_plus}
+set octa_cox {
+ 45 CCW
+ -45 CW
+ -135 CCW
+ 135 CW
+ -45 CCW
+ 45 CW
+ 135 CCW
+ -135 CW
+}
+
+set tables {quad_x quad_plus quad_v quad_wide hex_x hex_plus octa_x octa_plus octa_cox}
proc factors {a d} { puts [format "\t{ %9.6f, %9.6f, %5.2f }," [rcos [expr $a + 90]] [rcos $a] [expr -$d]]}
diff --git a/src/modules/uORB/uORB.cpp b/src/modules/uORB/uORB.cpp
index 7abbf42ae..149b8f6d2 100644
--- a/src/modules/uORB/uORB.cpp
+++ b/src/modules/uORB/uORB.cpp
@@ -249,8 +249,10 @@ ORBDevNode::close(struct file *filp)
} else {
SubscriberData *sd = filp_to_sd(filp);
- if (sd != nullptr)
+ if (sd != nullptr) {
+ hrt_cancel(&sd->update_call);
delete sd;
+ }
}
return CDev::close(filp);