GCS_MAVLink: send OPTICAL_FLOW messages to optical flow driver
This commit is contained in:
parent
97b5c2b031
commit
bbd051b246
@ -427,6 +427,8 @@ protected:
|
||||
MAV_RESULT handle_command_get_home_position(const mavlink_command_long_t &packet);
|
||||
MAV_RESULT handle_command_do_fence_enable(const mavlink_command_long_t &packet);
|
||||
|
||||
void handle_optical_flow(const mavlink_message_t* msg);
|
||||
|
||||
// vehicle-overridable message send function
|
||||
virtual bool try_send_message(enum ap_message id);
|
||||
virtual void send_global_position_int();
|
||||
|
@ -30,6 +30,7 @@
|
||||
#include <AP_Mount/AP_Mount.h>
|
||||
#include <AP_Common/AP_FWVersion.h>
|
||||
#include <AP_VisualOdom/AP_VisualOdom.h>
|
||||
#include <AP_OpticalFlow/OpticalFlow.h>
|
||||
|
||||
#include "GCS.h"
|
||||
|
||||
@ -3014,6 +3015,17 @@ void GCS_MAVLINK::handle_rc_channels_override(const mavlink_message_t *msg)
|
||||
RC_Channels::set_override(15, packet.chan16_raw, tnow);
|
||||
}
|
||||
|
||||
// allow override of RC channel values for HIL or for complete GCS
|
||||
// control of switch position and RC PWM values.
|
||||
void GCS_MAVLINK::handle_optical_flow(const mavlink_message_t *msg)
|
||||
{
|
||||
OpticalFlow *optflow = AP::opticalflow();
|
||||
if (optflow == nullptr) {
|
||||
return;
|
||||
}
|
||||
optflow->handle_msg(msg);
|
||||
}
|
||||
|
||||
/*
|
||||
handle messages which don't require vehicle specific data
|
||||
*/
|
||||
@ -3179,6 +3191,10 @@ void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg)
|
||||
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
|
||||
handle_rc_channels_override(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_OPTICAL_FLOW:
|
||||
handle_optical_flow(msg);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user