Copter: #ifdef scripting specific functions

This commit is contained in:
Iampete1 2021-07-18 18:36:22 +01:00 committed by Andrew Tridgell
parent 88d4ada96d
commit c2a6377c53
2 changed files with 4 additions and 0 deletions

View File

@ -270,6 +270,7 @@ void Copter::fast_loop()
AP_Vehicle::fast_loop();
}
#ifdef ENABLE_SCRIPTING
// start takeoff to given altitude (for use by scripting)
bool Copter::start_takeoff(float alt)
{
@ -336,6 +337,7 @@ bool Copter::set_target_angle_and_climbrate(float roll_deg, float pitch_deg, flo
mode_guided.set_angle(q, climb_rate_ms*100, use_yaw_rate, radians(yaw_rate_degs), false);
return true;
}
#endif // ENABLE_SCRIPTING
// rc_loops - reads user input from transmitter/receiver

View File

@ -643,11 +643,13 @@ private:
uint8_t &task_count,
uint32_t &log_bit) override;
void fast_loop() override;
#ifdef ENABLE_SCRIPTING
bool start_takeoff(float alt) override;
bool set_target_location(const Location& target_loc) override;
bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) override;
bool set_target_velocity_NED(const Vector3f& vel_ned) override;
bool set_target_angle_and_climbrate(float roll_deg, float pitch_deg, float yaw_deg, float climb_rate_ms, bool use_yaw_rate, float yaw_rate_degs) override;
#endif // ENABLE_SCRIPTING
void rc_loop();
void throttle_loop();
void update_batt_compass(void);