mirror of https://github.com/ArduPilot/ardupilot
AP_Camera: use corrected version of send_to_components
This commit is contained in:
parent
616c129f57
commit
6e8ef0d10e
|
@ -211,7 +211,6 @@ void AP_Camera::configure(float shooting_mode, float shutter_speed, float apertu
|
|||
// we cannot process the configure command so convert to mavlink message
|
||||
// and send to all components in case they and process it
|
||||
|
||||
mavlink_message_t msg;
|
||||
mavlink_command_long_t mav_cmd_long = {};
|
||||
|
||||
// convert mission command to mavlink command_long
|
||||
|
@ -224,11 +223,8 @@ void AP_Camera::configure(float shooting_mode, float shutter_speed, float apertu
|
|||
mav_cmd_long.param6 = cmd_id;
|
||||
mav_cmd_long.param7 = engine_cutoff_time;
|
||||
|
||||
// Encode Command long into MAVLINK msg
|
||||
mavlink_msg_command_long_encode(0, 0, &msg, &mav_cmd_long);
|
||||
|
||||
// send to all components
|
||||
GCS_MAVLINK::send_to_components(msg);
|
||||
GCS_MAVLINK::send_to_components(MAVLINK_MSG_ID_COMMAND_LONG, (char*)&mav_cmd_long, sizeof(mav_cmd_long));
|
||||
|
||||
if (_type == AP_Camera::CAMERA_TYPE_BMMCC) {
|
||||
// Set a trigger for the additional functions that are flip controlled (so far just ISO and Record Start / Stop use this method, will add others if required)
|
||||
|
@ -261,7 +257,6 @@ void AP_Camera::control(float session, float zoom_pos, float zoom_step, float fo
|
|||
trigger_pic();
|
||||
}
|
||||
|
||||
mavlink_message_t msg;
|
||||
mavlink_command_long_t mav_cmd_long = {};
|
||||
|
||||
// convert command to mavlink command long
|
||||
|
@ -273,11 +268,8 @@ void AP_Camera::control(float session, float zoom_pos, float zoom_step, float fo
|
|||
mav_cmd_long.param5 = shooting_cmd;
|
||||
mav_cmd_long.param6 = cmd_id;
|
||||
|
||||
// Encode Command long into MAVLINK msg
|
||||
mavlink_msg_command_long_encode(0, 0, &msg, &mav_cmd_long);
|
||||
|
||||
// send to all components
|
||||
GCS_MAVLINK::send_to_components(msg);
|
||||
GCS_MAVLINK::send_to_components(MAVLINK_MSG_ID_COMMAND_LONG, (char*)&mav_cmd_long, sizeof(mav_cmd_long));
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -431,16 +423,12 @@ void AP_Camera::take_picture()
|
|||
trigger_pic();
|
||||
|
||||
// tell all of our components to take a picture:
|
||||
mavlink_command_long_t cmd_msg;
|
||||
memset(&cmd_msg, 0, sizeof(cmd_msg));
|
||||
mavlink_command_long_t cmd_msg {};
|
||||
cmd_msg.command = MAV_CMD_DO_DIGICAM_CONTROL;
|
||||
cmd_msg.param5 = 1;
|
||||
// create message
|
||||
mavlink_message_t msg;
|
||||
mavlink_msg_command_long_encode(0, 0, &msg, &cmd_msg);
|
||||
|
||||
// forward to all components
|
||||
GCS_MAVLINK::send_to_components(msg);
|
||||
GCS_MAVLINK::send_to_components(MAVLINK_MSG_ID_COMMAND_LONG, (char*)&cmd_msg, sizeof(cmd_msg));
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue