2016-10-28 19:06:52 -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/>.
|
|
|
|
*/
|
|
|
|
/*
|
|
|
|
simple Gripper (Servo) simulation class
|
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
2018-07-31 09:33:23 -03:00
|
|
|
#include "stdint.h"
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
#include "SITL_Input.h"
|
2016-10-28 19:06:52 -03:00
|
|
|
|
|
|
|
namespace SITL {
|
|
|
|
|
|
|
|
class Gripper_Servo {
|
|
|
|
public:
|
2018-07-31 09:33:23 -03:00
|
|
|
Gripper_Servo() {
|
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
};
|
2016-10-28 19:06:52 -03:00
|
|
|
|
|
|
|
// update Gripper state
|
2018-07-31 09:33:23 -03:00
|
|
|
void update(const struct sitl_input &input);
|
2016-10-28 19:06:52 -03:00
|
|
|
|
2016-11-22 20:50:01 -04:00
|
|
|
float payload_mass() const; // kg
|
|
|
|
|
2018-07-31 09:33:23 -03:00
|
|
|
void set_alt(float alt) {altitude = alt;};
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
bool is_enabled() const {return static_cast<bool>(gripper_enable);}
|
2018-08-09 13:51:17 -03:00
|
|
|
bool is_jaw_open() const {return jaw_open;}
|
2016-11-22 20:50:01 -04:00
|
|
|
|
2016-10-28 19:06:52 -03:00
|
|
|
private:
|
2018-08-09 13:51:17 -03:00
|
|
|
static constexpr int16_t SIM_GRIPPER_GRAB_PWM_DEFAULT = 2000;
|
|
|
|
static constexpr int16_t SIM_GRIPPER_RELEASE_PWM_DEFAULT = 1000;
|
2018-07-31 09:33:23 -03:00
|
|
|
AP_Int8 gripper_enable; // enable gripper sim
|
|
|
|
AP_Int8 gripper_servo_pin;
|
2018-08-09 13:51:17 -03:00
|
|
|
AP_Int16 grab_pwm; // PWM value sent to Gripper to initiate grabbing the cargo
|
|
|
|
AP_Int16 release_pwm; // PWM value sent to Gripper to release the cargo
|
|
|
|
AP_Int8 reverse; // reverse closing direction
|
2016-10-28 19:06:52 -03:00
|
|
|
const uint32_t report_interval = 1000000; // microseconds
|
|
|
|
uint64_t last_report_us;
|
2018-08-09 13:51:17 -03:00
|
|
|
bool jaw_open = false;
|
2016-10-28 19:06:52 -03:00
|
|
|
const float gap = 30; // mm
|
2018-07-31 09:33:23 -03:00
|
|
|
float altitude;
|
2016-10-28 19:06:52 -03:00
|
|
|
float position; // percentage
|
2016-11-23 01:15:12 -04:00
|
|
|
float position_slew_rate = 35; // percentage
|
2016-10-28 19:06:52 -03:00
|
|
|
float reported_position = -1; // unlikely
|
|
|
|
|
|
|
|
uint64_t last_update_us;
|
|
|
|
|
2021-02-01 12:37:57 -04:00
|
|
|
bool should_report() const;
|
2016-11-22 20:50:01 -04:00
|
|
|
|
|
|
|
// dangle load from a string:
|
|
|
|
const float string_length = 2.0f; // metres
|
2016-11-23 01:15:12 -04:00
|
|
|
float load_mass = 0.0f; // kilograms
|
2016-10-28 19:06:52 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
}
|