aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-05-05 14:42:46 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-05-05 14:42:46 +0200
commit474a76b553c08d4995e8cf11080204959b300251 (patch)
tree288e48287c462eb50ef30e78f70fcf877d7868a8 /src/modules
parent775499321adc0b69d2845ffd24cb00a070ae09a0 (diff)
parent896d8a3acd0ea91858c7a23b2dbce174f7da7fba (diff)
downloadpx4-firmware-474a76b553c08d4995e8cf11080204959b300251.tar.gz
px4-firmware-474a76b553c08d4995e8cf11080204959b300251.tar.bz2
px4-firmware-474a76b553c08d4995e8cf11080204959b300251.zip
Merge remote-tracking branch 'upstream/master' into geo
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/commander/commander_helper.cpp16
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp10
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp4
-rw-r--r--src/modules/mc_att_control/mc_att_control_main.cpp3
-rw-r--r--src/modules/systemlib/mixer/mixer_load.c1
5 files changed, 13 insertions, 21 deletions
diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp
index fe6c9bfaa..0fd3c9e9e 100644
--- a/src/modules/commander/commander_helper.cpp
+++ b/src/modules/commander/commander_helper.cpp
@@ -199,15 +199,9 @@ int led_init()
}
/* the blue LED is only available on FMUv1 but not FMUv2 */
-#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
-
- if (ioctl(leds, LED_ON, LED_BLUE)) {
- warnx("Blue LED: ioctl fail\n");
- return ERROR;
- }
-
-#endif
+ (void)ioctl(leds, LED_ON, LED_BLUE);
+ /* we consider the amber led mandatory */
if (ioctl(leds, LED_ON, LED_AMBER)) {
warnx("Amber LED: ioctl fail\n");
return ERROR;
@@ -217,11 +211,7 @@ int led_init()
rgbleds = open(RGBLED_DEVICE_PATH, 0);
if (rgbleds == -1) {
-#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
- errx(1, "Unable to open " RGBLED_DEVICE_PATH);
-#else
- warnx("No RGB LED found");
-#endif
+ warnx("No RGB LED found at " RGBLED_DEVICE_PATH);
}
return 0;
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 678ce1645..bef8a5a55 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -819,11 +819,11 @@ protected:
void send(const hrt_abstime t)
{
- bool updated = status_sub->update(t);
- updated |= pos_sp_triplet_sub->update(t);
- updated |= act_sub->update(t);
+ bool updated = act_sub->update(t);
+ (void)pos_sp_triplet_sub->update(t);
+ (void)status_sub->update(t);
- if (updated) {
+ if (updated && (status->arming_state == ARMING_STATE_ARMED)) {
/* translate the current syste state to mavlink state and mode */
uint8_t mavlink_state;
uint8_t mavlink_base_mode;
@@ -1353,7 +1353,7 @@ protected:
uint8_t orientation = 0;
uint8_t covariance = 20;
- mavlink_msg_distance_sensor_send(_channel, range->timestamp / 1000, type, id, orientation,
+ mavlink_msg_distance_sensor_send(_channel, range->timestamp / 1000, type, id, orientation,
range->minimum_distance*100, range->maximum_distance*100, range->distance*100, covariance);
}
};
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index ddbf4fc69..1cfbde1d2 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -432,8 +432,8 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
memset(&manual, 0, sizeof(manual));
manual.timestamp = hrt_absolute_time();
- manual.roll = man.x / 1000.0f;
- manual.pitch = man.y / 1000.0f;
+ manual.pitch = man.x / 1000.0f;
+ manual.roll = man.y / 1000.0f;
manual.yaw = man.r / 1000.0f;
manual.throttle = man.z / 1000.0f;
diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp
index 6b0c44fb3..36d95bf06 100644
--- a/src/modules/mc_att_control/mc_att_control_main.cpp
+++ b/src/modules/mc_att_control/mc_att_control_main.cpp
@@ -496,7 +496,8 @@ MulticopterAttitudeControl::control_attitude(float dt)
//}
} else {
/* move yaw setpoint */
- _v_att_sp.yaw_body = _wrap_pi(_v_att_sp.yaw_body + _manual_control_sp.yaw * _params.man_yaw_max * dt);
+ yaw_sp_move_rate = _manual_control_sp.yaw * _params.man_yaw_max;
+ _v_att_sp.yaw_body = _wrap_pi(_v_att_sp.yaw_body + yaw_sp_move_rate * dt);
_v_att_sp.R_valid = false;
publish_att_sp = true;
}
diff --git a/src/modules/systemlib/mixer/mixer_load.c b/src/modules/systemlib/mixer/mixer_load.c
index b05273c0d..bf3428a50 100644
--- a/src/modules/systemlib/mixer/mixer_load.c
+++ b/src/modules/systemlib/mixer/mixer_load.c
@@ -41,6 +41,7 @@
#include <string.h>
#include <stdio.h>
#include <ctype.h>
+#include <systemlib/err.h>
#include "mixer_load.h"