forked from Archive/PX4-Autopilot
Send camera command to all, use own sysid
This commit is contained in:
parent
bb3792bcdd
commit
38c3e68976
|
@ -1265,13 +1265,11 @@ protected:
|
|||
|| status->arming_state == ARMING_STATE_ARMED_ERROR) {
|
||||
|
||||
/* send camera capture on */
|
||||
/* XXX TODO: get param for system ID */
|
||||
mavlink_msg_command_long_send(_channel, 42, 250, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 1, 0, 0, 0);
|
||||
mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 1, 0, 0, 0);
|
||||
|
||||
} else {
|
||||
/* send camera capture off */
|
||||
/* XXX TODO: get param for system ID */
|
||||
mavlink_msg_command_long_send(_channel, 42, 250, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 0, 0, 0, 0);
|
||||
mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 0, 0, 0, 0);
|
||||
}
|
||||
}
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue