HIL testing / cleanup for fixed wing and multirotors

This commit is contained in:
Lorenz Meier 2012-11-07 00:08:04 +01:00
parent 7d76a8a57b
commit 88800b38f8
2 changed files with 10 additions and 35 deletions

View File

@ -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 */

View File

@ -459,29 +459,9 @@ l_manual_control_setpoint(struct listener *l)
void
l_vehicle_attitude_controls(struct listener *l)
{
struct actuator_controls_s actuators;
struct actuator_outputs_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]);
}
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);
}