mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_Camera: add handle_command_long
This commit is contained in:
parent
3bc42b888f
commit
9ccf08a0f8
@ -204,6 +204,27 @@ void AP_Camera::handle_message(mavlink_channel_t chan, const mavlink_message_t &
|
||||
}
|
||||
}
|
||||
|
||||
// handle command_long mavlink messages
|
||||
MAV_RESULT AP_Camera::handle_command_long(const mavlink_command_long_t &packet)
|
||||
{
|
||||
switch (packet.command) {
|
||||
case MAV_CMD_DO_DIGICAM_CONFIGURE:
|
||||
configure(packet.param1, packet.param2, packet.param3, packet.param4, packet.param5, packet.param6, packet.param7);
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
case MAV_CMD_DO_DIGICAM_CONTROL:
|
||||
control(packet.param1, packet.param2, packet.param3, packet.param4, packet.param5, packet.param6);
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
||||
set_trigger_distance(packet.param1);
|
||||
if (is_equal(packet.param3, 1.0f)) {
|
||||
take_picture();
|
||||
}
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
default:
|
||||
return MAV_RESULT_UNSUPPORTED;
|
||||
}
|
||||
}
|
||||
|
||||
// set camera trigger distance in a mission
|
||||
void AP_Camera::set_trigger_distance(uint8_t instance, float distance_m)
|
||||
{
|
||||
|
@ -73,6 +73,7 @@ public:
|
||||
|
||||
// MAVLink methods
|
||||
void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg);
|
||||
MAV_RESULT handle_command_long(const mavlink_command_long_t &packet);
|
||||
void send_feedback(mavlink_channel_t chan) const;
|
||||
|
||||
// configure camera
|
||||
|
Loading…
Reference in New Issue
Block a user