aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-11-07 00:08:04 +0100
committerLorenz Meier <lm@inf.ethz.ch>2012-11-07 00:08:04 +0100
commit88800b38f8035143c443fbba6bbce368ccc42594 (patch)
tree07c62c896f1d7411f178201438e36f3eaa717845
parent7d76a8a57b41c82db0712dd0544e67d1ce97d89c (diff)
downloadpx4-firmware-88800b38f8035143c443fbba6bbce368ccc42594.tar.gz
px4-firmware-88800b38f8035143c443fbba6bbce368ccc42594.tar.bz2
px4-firmware-88800b38f8035143c443fbba6bbce368ccc42594.zip
HIL testing / cleanup for fixed wing and multirotors
-rw-r--r--apps/mavlink/mavlink.c5
-rw-r--r--apps/mavlink/orb_listener.c42
2 files changed, 11 insertions, 36 deletions
diff --git a/apps/mavlink/mavlink.c b/apps/mavlink/mavlink.c
index 9b2cfcbba..6b4643ec7 100644
--- a/apps/mavlink/mavlink.c
+++ b/apps/mavlink/mavlink.c
@@ -143,15 +143,10 @@ set_hil_on_off(bool hil_enabled)
/* Enable HIL */
if (hil_enabled && !mavlink_hil_enabled) {
- //printf("\n HIL ON \n");
-
/* Advertise topics */
pub_hil_attitude = orb_advertise(ORB_ID(vehicle_attitude), &hil_attitude);
pub_hil_global_pos = orb_advertise(ORB_ID(vehicle_global_position), &hil_global_pos);
- printf("\n pub_hil_attitude :%i\n", pub_hil_attitude);
- printf("\n pub_hil_global_pos :%i\n", pub_hil_global_pos);
-
mavlink_hil_enabled = true;
/* ramp up some HIL-related subscriptions */
diff --git a/apps/mavlink/orb_listener.c b/apps/mavlink/orb_listener.c
index 683964a0d..6342ce979 100644
--- a/apps/mavlink/orb_listener.c
+++ b/apps/mavlink/orb_listener.c
@@ -459,29 +459,9 @@ l_manual_control_setpoint(struct listener *l)
void
l_vehicle_attitude_controls(struct listener *l)
{
- struct actuator_controls_s actuators;
-
- orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, mavlink_subs.actuators_sub, &actuators);
-
- if (gcs_link) {
- /* send, add spaces so that string buffer is at least 10 chars long */
- mavlink_msg_named_value_float_send(MAVLINK_COMM_0,
- last_sensor_timestamp / 1000,
- "ctrl0 ",
- actuators.control[0]);
- mavlink_msg_named_value_float_send(MAVLINK_COMM_0,
- last_sensor_timestamp / 1000,
- "ctrl1 ",
- actuators.control[1]);
- mavlink_msg_named_value_float_send(MAVLINK_COMM_0,
- last_sensor_timestamp / 1000,
- "ctrl2 ",
- actuators.control[2]);
- mavlink_msg_named_value_float_send(MAVLINK_COMM_0,
- last_sensor_timestamp / 1000,
- "ctrl3 ",
- actuators.control[3]);
- }
+ struct actuator_outputs_s actuators;
+
+ orb_copy(ORB_ID_VEHICLE_CONTROLS, mavlink_subs.act_0_sub, &actuators);
/* Only send in HIL mode */
if (mavlink_hil_enabled) {
@@ -494,14 +474,14 @@ l_vehicle_attitude_controls(struct listener *l)
/* HIL message as per MAVLink spec */
mavlink_msg_hil_controls_send(chan,
hrt_absolute_time(),
- actuators.control[0],
- actuators.control[1],
- actuators.control[2],
- actuators.control[3],
- 0,
- 0,
- 0,
- 0,
+ actuators.output[0],
+ actuators.output[1],
+ actuators.output[2],
+ actuators.output[3],
+ actuators.output[4],
+ actuators.output[5],
+ actuators.output[6],
+ actuators.output[7],
mavlink_mode,
0);
}