2021-06-20 03:02:12 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <GCS_MAVLink/GCS.h>
|
2021-08-18 08:42:18 -03:00
|
|
|
#if HAL_GCS_ENABLED
|
2021-06-20 03:02:12 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
* GCS backend used for many examples and tools
|
|
|
|
*/
|
|
|
|
class GCS_MAVLINK_Periph : public GCS_MAVLINK
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
|
|
|
|
using GCS_MAVLINK::GCS_MAVLINK;
|
|
|
|
|
|
|
|
private:
|
|
|
|
|
|
|
|
uint32_t telem_delay() const override { return 0; }
|
|
|
|
void handleMessage(const mavlink_message_t &msg) override { handle_common_message(msg); }
|
|
|
|
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override { return true; }
|
2022-09-13 21:46:55 -03:00
|
|
|
MAV_RESULT handle_preflight_reboot(const mavlink_command_long_t &packet, const mavlink_message_t &msg) override;
|
2023-06-01 20:23:21 -03:00
|
|
|
uint8_t sysid_my_gcs() const override;
|
2021-06-20 03:02:12 -03:00
|
|
|
|
|
|
|
protected:
|
|
|
|
|
|
|
|
// Periph information:
|
|
|
|
MAV_MODE base_mode() const override { return (MAV_MODE)MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; }
|
|
|
|
MAV_STATE vehicle_system_status() const override { return MAV_STATE_CALIBRATING; }
|
|
|
|
|
|
|
|
bool set_home_to_current_location(bool _lock) override { return false; }
|
|
|
|
bool set_home(const Location& loc, bool _lock) override { return false; }
|
|
|
|
|
|
|
|
void send_nav_controller_output() const override {};
|
|
|
|
void send_pid_tuning() override {};
|
|
|
|
};
|
|
|
|
|
|
|
|
/*
|
|
|
|
* a GCS singleton used for many example sketches and tools
|
|
|
|
*/
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
class GCS_Periph : public GCS
|
|
|
|
{
|
|
|
|
public:
|
|
|
|
|
|
|
|
using GCS::GCS;
|
|
|
|
|
|
|
|
protected:
|
|
|
|
|
2021-07-11 03:38:42 -03:00
|
|
|
uint8_t sysid_this_mav() const override;
|
2021-06-20 03:02:12 -03:00
|
|
|
|
|
|
|
GCS_MAVLINK_Periph *new_gcs_mavlink_backend(GCS_MAVLINK_Parameters ¶ms,
|
|
|
|
AP_HAL::UARTDriver &uart) override {
|
|
|
|
return new GCS_MAVLINK_Periph(params, uart);
|
|
|
|
}
|
|
|
|
|
|
|
|
private:
|
2022-12-13 21:14:18 -04:00
|
|
|
// the following define expands to a pair of methods to retrieve a
|
|
|
|
// pointer to an object of the correct subclass for the link at
|
|
|
|
// offset ofs. These are of the form:
|
|
|
|
// GCS_MAVLINK_XXXX *chan(const uint8_t ofs) override;
|
|
|
|
// const GCS_MAVLINK_XXXX *chan(const uint8_t ofs) override const;
|
|
|
|
GCS_MAVLINK_CHAN_METHOD_DEFINITIONS(GCS_MAVLINK_Periph);
|
2021-06-20 03:02:12 -03:00
|
|
|
|
|
|
|
MAV_TYPE frame_type() const override { return MAV_TYPE_GENERIC; }
|
|
|
|
uint32_t custom_mode() const override { return 3; } // magic number
|
|
|
|
};
|
2021-08-18 08:42:18 -03:00
|
|
|
#endif // HAL_GCS_ENABLED
|