mirror of https://github.com/ArduPilot/ardupilot
Tracker: use GCS_MAVLINK subclasses to handle set_mode
This commit is contained in:
parent
8eeae45300
commit
947bae2f86
|
@ -740,12 +740,6 @@ mission_failed:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_SET_MODE:
|
|
||||||
{
|
|
||||||
handle_set_mode(msg, FUNCTOR_BIND(&tracker, &Tracker::mavlink_set_mode, bool, uint8_t));
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
case MAVLINK_MSG_ID_SERIAL_CONTROL:
|
case MAVLINK_MSG_ID_SERIAL_CONTROL:
|
||||||
handle_serial_control(msg, tracker.gps);
|
handle_serial_control(msg, tracker.gps);
|
||||||
break;
|
break;
|
||||||
|
@ -831,6 +825,23 @@ Compass *GCS_MAVLINK_Tracker::get_compass() const
|
||||||
return &tracker.compass;
|
return &tracker.compass;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
set_mode() wrapper for MAVLink SET_MODE
|
||||||
|
*/
|
||||||
|
bool GCS_MAVLINK_Tracker::set_mode(uint8_t mode)
|
||||||
|
{
|
||||||
|
switch (mode) {
|
||||||
|
case AUTO:
|
||||||
|
case MANUAL:
|
||||||
|
case SCAN:
|
||||||
|
case SERVO_TEST:
|
||||||
|
case STOP:
|
||||||
|
tracker.set_mode((enum ControlMode)mode);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
/* dummy methods to avoid having to link against AP_Camera */
|
/* dummy methods to avoid having to link against AP_Camera */
|
||||||
void AP_Camera::control_msg(mavlink_message_t const*) {}
|
void AP_Camera::control_msg(mavlink_message_t const*) {}
|
||||||
void AP_Camera::configure(float, float, float, float, float, float, float) {}
|
void AP_Camera::configure(float, float, float, float, float, float, float) {}
|
||||||
|
|
|
@ -25,6 +25,8 @@ protected:
|
||||||
|
|
||||||
uint8_t sysid_my_gcs() const override;
|
uint8_t sysid_my_gcs() const override;
|
||||||
|
|
||||||
|
bool set_mode(uint8_t mode) override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
void handleMessage(mavlink_message_t * msg) override;
|
void handleMessage(mavlink_message_t * msg) override;
|
||||||
|
|
|
@ -241,7 +241,6 @@ private:
|
||||||
void disarm_servos();
|
void disarm_servos();
|
||||||
void prepare_servos();
|
void prepare_servos();
|
||||||
void set_mode(enum ControlMode mode);
|
void set_mode(enum ControlMode mode);
|
||||||
bool mavlink_set_mode(uint8_t mode);
|
|
||||||
void check_usb_mux(void);
|
void check_usb_mux(void);
|
||||||
void update_vehicle_pos_estimate();
|
void update_vehicle_pos_estimate();
|
||||||
void update_tracker_position();
|
void update_tracker_position();
|
||||||
|
|
|
@ -218,23 +218,6 @@ void Tracker::set_mode(enum ControlMode mode)
|
||||||
DataFlash.Log_Write_Mode(control_mode);
|
DataFlash.Log_Write_Mode(control_mode);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
set_mode() wrapper for MAVLink SET_MODE
|
|
||||||
*/
|
|
||||||
bool Tracker::mavlink_set_mode(uint8_t mode)
|
|
||||||
{
|
|
||||||
switch (mode) {
|
|
||||||
case AUTO:
|
|
||||||
case MANUAL:
|
|
||||||
case SCAN:
|
|
||||||
case SERVO_TEST:
|
|
||||||
case STOP:
|
|
||||||
set_mode((enum ControlMode)mode);
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
void Tracker::check_usb_mux(void)
|
void Tracker::check_usb_mux(void)
|
||||||
{
|
{
|
||||||
bool usb_check = hal.gpio->usb_connected();
|
bool usb_check = hal.gpio->usb_connected();
|
||||||
|
|
Loading…
Reference in New Issue