2015-05-24 22:23:36 -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/>.
|
|
|
|
*/
|
|
|
|
/*
|
|
|
|
gimbal simulator class
|
2024-07-18 00:30:39 -03:00
|
|
|
|
|
|
|
./Tools/autotest/sim_vehicle.py -D -G -v ArduCopter --mavlink-gimbal
|
|
|
|
param set MNT1_TYPE 2
|
|
|
|
param set RC6_OPTION 213 # MOUNT1_PITCH
|
|
|
|
rc 6 1818 # for neutral pitch input
|
2015-05-24 22:23:36 -03:00
|
|
|
*/
|
|
|
|
|
2015-10-22 11:04:23 -03:00
|
|
|
#pragma once
|
2015-05-24 22:23:36 -03:00
|
|
|
|
2024-07-17 03:46:42 -03:00
|
|
|
#include "SIM_config.h"
|
2021-10-11 01:59:19 -03:00
|
|
|
|
2024-07-17 03:46:42 -03:00
|
|
|
#if AP_SIM_SOLOGIMBAL_ENABLED
|
2021-10-11 01:59:19 -03:00
|
|
|
|
2024-07-17 03:52:20 -03:00
|
|
|
#include "SIM_Gimbal.h"
|
|
|
|
|
2024-07-17 03:46:42 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
2023-12-25 22:21:11 -04:00
|
|
|
#include <AP_HAL/utility/Socket_native.h>
|
2015-05-24 22:23:36 -03:00
|
|
|
|
2015-10-22 10:04:42 -03:00
|
|
|
namespace SITL {
|
|
|
|
|
2024-07-17 03:46:42 -03:00
|
|
|
class SoloGimbal {
|
2015-05-24 22:23:36 -03:00
|
|
|
public:
|
|
|
|
|
2024-07-17 03:52:20 -03:00
|
|
|
SoloGimbal() {}
|
|
|
|
void update(const Aircraft &aicraft);
|
2015-05-24 22:23:36 -03:00
|
|
|
|
2024-07-17 03:52:20 -03:00
|
|
|
private:
|
2015-05-24 22:23:36 -03:00
|
|
|
|
2024-07-17 03:52:20 -03:00
|
|
|
const char *target_address = "127.0.0.1";
|
|
|
|
const uint16_t target_port = 5762;
|
2015-05-24 22:23:36 -03:00
|
|
|
|
2024-07-17 03:52:20 -03:00
|
|
|
// physic simulation of gimbal:
|
|
|
|
Gimbal gimbal;
|
2015-05-24 22:23:36 -03:00
|
|
|
|
|
|
|
// reporting variables. gimbal pushes these to vehicle code over
|
|
|
|
// MAVLink at approx 100Hz
|
|
|
|
|
|
|
|
// reporting period in ms
|
2024-07-17 03:52:20 -03:00
|
|
|
const float reporting_period_ms = 10;
|
2015-05-24 22:23:36 -03:00
|
|
|
|
|
|
|
uint32_t last_report_us;
|
|
|
|
uint32_t last_heartbeat_ms;
|
|
|
|
bool seen_heartbeat;
|
|
|
|
bool seen_gimbal_control;
|
|
|
|
uint8_t vehicle_system_id;
|
|
|
|
uint8_t vehicle_component_id;
|
|
|
|
|
2024-07-17 03:52:20 -03:00
|
|
|
SocketAPM_native mav_socket{false};
|
2015-05-24 22:23:36 -03:00
|
|
|
struct {
|
|
|
|
// socket to telem2 on aircraft
|
|
|
|
bool connected;
|
|
|
|
mavlink_message_t rxmsg;
|
|
|
|
mavlink_status_t status;
|
|
|
|
uint8_t seq;
|
|
|
|
} mavlink;
|
|
|
|
|
2018-11-21 19:15:34 -04:00
|
|
|
uint32_t param_send_last_ms;
|
|
|
|
uint8_t param_send_idx;
|
|
|
|
|
2024-07-17 22:22:56 -03:00
|
|
|
// component ID we send from:
|
|
|
|
const uint8_t gimbal_component_id = 154; // MAV_COMP_ID_GIMBAL
|
|
|
|
|
2015-05-24 22:23:36 -03:00
|
|
|
void send_report(void);
|
2018-11-21 19:15:34 -04:00
|
|
|
void param_send(const struct gimbal_param *p);
|
|
|
|
struct gimbal_param *param_find(const char *name);
|
2015-05-24 22:23:36 -03:00
|
|
|
};
|
2015-10-22 10:04:42 -03:00
|
|
|
|
|
|
|
} // namespace SITL
|
2021-10-11 01:59:19 -03:00
|
|
|
|
2024-07-17 03:46:42 -03:00
|
|
|
#endif // AP_SIM_SOLOGIMBAL_ENABLED
|
|
|
|
|