mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 14:13:42 -04:00
1915244960
In file included from ../../libraries/SITL/SIM_last_letter.cpp:19: ../../libraries/SITL/SIM_last_letter.h:74:17: warning: private field 'frame_str' is not used [-Wunused-private-field] const char *frame_str; SITL: correct compiler warning In file included from ../../libraries/SITL/SIM_Sprayer.cpp:19: ../../libraries/SITL/SIM_Sprayer.h:55:14: warning: private field 'start_time_us' is not used [-Wunused-private-field] uint64_t start_time_us; SITL: correct compiler warnings In file included from ../../libraries/SITL/SIM_Gripper_Servo.cpp:19: ../../libraries/SITL/SIM_Gripper_Servo.h:56:10: warning: private field 'zero_report_done' is not used [-Wunused-private-field] bool zero_report_done = false; SITL: correct compiler warnings In file included from ../../libraries/SITL/SIM_ADSB.cpp:19: ../../libraries/SITL/SIM_ADSB.h:49:28: warning: private field 'fdm' is not used [-Wunused-private-field] const struct sitl_fdm &fdm;
63 lines
1.6 KiB
C++
63 lines
1.6 KiB
C++
/*
|
|
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/>.
|
|
*/
|
|
/*
|
|
simple Gripper (Servo) simulation class
|
|
*/
|
|
|
|
#pragma once
|
|
|
|
#include "SIM_Aircraft.h"
|
|
|
|
namespace SITL {
|
|
|
|
class Gripper_Servo {
|
|
public:
|
|
const uint8_t gripper_servo;
|
|
|
|
Gripper_Servo(const uint8_t _gripper_servo) :
|
|
gripper_servo(_gripper_servo)
|
|
{}
|
|
|
|
// update Gripper state
|
|
void update(const struct Aircraft::sitl_input &input);
|
|
|
|
float payload_mass() const; // kg
|
|
|
|
void set_aircraft(Aircraft *_aircraft) { aircraft = _aircraft; }
|
|
|
|
private:
|
|
|
|
Aircraft *aircraft;
|
|
|
|
const uint32_t report_interval = 1000000; // microseconds
|
|
uint64_t last_report_us;
|
|
|
|
const float gap = 30; // mm
|
|
|
|
float position; // percentage
|
|
float position_slew_rate = 35; // percentage
|
|
float reported_position = -1; // unlikely
|
|
|
|
uint64_t last_update_us;
|
|
|
|
bool should_report();
|
|
|
|
// dangle load from a string:
|
|
const float string_length = 2.0f; // metres
|
|
float load_mass = 0.0f; // kilograms
|
|
};
|
|
|
|
}
|