mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
SITL: quadplane updates
This commit is contained in:
parent
dcdd1707f7
commit
c0c61660b0
@ -84,6 +84,16 @@ public:
|
||||
// get frame rate of model in Hz
|
||||
float get_rate_hz(void) const { return rate_hz; }
|
||||
|
||||
// get number of motors for model
|
||||
uint16_t get_num_motors() const {
|
||||
return num_motors;
|
||||
}
|
||||
|
||||
// get motor offset for model
|
||||
virtual uint16_t get_motors_offset() const {
|
||||
return 0;
|
||||
}
|
||||
|
||||
const Vector3f &get_gyro(void) const {
|
||||
return gyro;
|
||||
}
|
||||
|
@ -34,6 +34,11 @@ public:
|
||||
/* update model by one time step */
|
||||
void update(const struct sitl_input &input) override;
|
||||
|
||||
// get motor offset for model
|
||||
virtual uint16_t get_motors_offset() const override {
|
||||
return frame->motor_offset;
|
||||
}
|
||||
|
||||
/* static object creator */
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new MultiCopter(frame_str);
|
||||
|
@ -38,6 +38,13 @@ public:
|
||||
static Aircraft *create(const char *frame_str) {
|
||||
return new QuadPlane(frame_str);
|
||||
}
|
||||
|
||||
// get motor offset for model
|
||||
virtual uint16_t get_motors_offset() const override {
|
||||
return frame->motor_offset;
|
||||
}
|
||||
|
||||
|
||||
private:
|
||||
Frame *frame;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user