Browse Source

Send camera command to all, use own sysid

sbg
Julian Oes 11 years ago
parent
commit
38c3e68976
  1. 6
      src/modules/mavlink/mavlink_messages.cpp

6
src/modules/mavlink/mavlink_messages.cpp

@ -1265,13 +1265,11 @@ protected:
|| status->arming_state == ARMING_STATE_ARMED_ERROR) { || status->arming_state == ARMING_STATE_ARMED_ERROR) {
/* send camera capture on */ /* send camera capture on */
/* XXX TODO: get param for system ID */ mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 1, 0, 0, 0);
mavlink_msg_command_long_send(_channel, 42, 250, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 1, 0, 0, 0);
} else { } else {
/* send camera capture off */ /* send camera capture off */
/* XXX TODO: get param for system ID */ mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 0, 0, 0, 0);
mavlink_msg_command_long_send(_channel, 42, 250, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 0, 0, 0, 0);
} }
} }
}; };

Loading…
Cancel
Save