Browse Source

AP_Motors: move from ENABLE_SCRIPTING to AP_SCRIPTING_ENABLED

gps-1.3.1
Peter Barker 3 years ago committed by Peter Barker
parent
commit
55cdbd208d
  1. 4
      libraries/AP_Motors/AP_MotorsMatrix.cpp
  2. 4
      libraries/AP_Motors/AP_MotorsMatrix.h
  3. 4
      libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.cpp
  4. 4
      libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.h
  5. 4
      libraries/AP_Motors/AP_MotorsMatrix_Scripting_Dynamic.cpp
  6. 4
      libraries/AP_Motors/AP_MotorsMatrix_Scripting_Dynamic.h

4
libraries/AP_Motors/AP_MotorsMatrix.cpp

@ -38,7 +38,7 @@ void AP_MotorsMatrix::init(motor_frame_class frame_class, motor_frame_type frame @@ -38,7 +38,7 @@ void AP_MotorsMatrix::init(motor_frame_class frame_class, motor_frame_type frame
set_update_rate(_speed_hz);
}
#if ENABLE_SCRIPTING
#if AP_SCRIPTING_ENABLED
// dedicated init for lua scripting
bool AP_MotorsMatrix::init(uint8_t expected_num_motors)
{
@ -109,7 +109,7 @@ bool AP_MotorsMatrix::set_throttle_factor(int8_t motor_num, float throttle_facto @@ -109,7 +109,7 @@ bool AP_MotorsMatrix::set_throttle_factor(int8_t motor_num, float throttle_facto
return true;
}
#endif // ENABLE_SCRIPTING
#endif // AP_SCRIPTING_ENABLED
// set update rate to motors - a value in hertz
void AP_MotorsMatrix::set_update_rate(uint16_t speed_hz)

4
libraries/AP_Motors/AP_MotorsMatrix.h

@ -32,14 +32,14 @@ public: @@ -32,14 +32,14 @@ public:
// init
virtual void init(motor_frame_class frame_class, motor_frame_type frame_type) override;
#if ENABLE_SCRIPTING
#if AP_SCRIPTING_ENABLED
// Init to be called from scripting
virtual bool init(uint8_t expected_num_motors);
// Set throttle factor from scripting
bool set_throttle_factor(int8_t motor_num, float throttle_factor);
#endif // ENABLE_SCRIPTING
#endif // AP_SCRIPTING_ENABLED
// set frame class (i.e. quad, hexa, heli) and type (i.e. x, plus)
void set_frame_class_and_type(motor_frame_class frame_class, motor_frame_type frame_type) override;

4
libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.cpp

@ -13,7 +13,7 @@ @@ -13,7 +13,7 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#if ENABLE_SCRIPTING
#if AP_SCRIPTING_ENABLED
#include <AP_HAL/AP_HAL.h>
#include "AP_MotorsMatrix_6DoF_Scripting.h"
@ -322,4 +322,4 @@ bool AP_MotorsMatrix_6DoF_Scripting::init(uint8_t expected_num_motors) { @@ -322,4 +322,4 @@ bool AP_MotorsMatrix_6DoF_Scripting::init(uint8_t expected_num_motors) {
// singleton instance
AP_MotorsMatrix_6DoF_Scripting *AP_MotorsMatrix_6DoF_Scripting::_singleton;
#endif // ENABLE_SCRIPTING
#endif // AP_SCRIPTING_ENABLED

4
libraries/AP_Motors/AP_MotorsMatrix_6DoF_Scripting.h

@ -1,5 +1,5 @@ @@ -1,5 +1,5 @@
#pragma once
#if ENABLE_SCRIPTING
#if AP_SCRIPTING_ENABLED
#include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h>
@ -64,4 +64,4 @@ private: @@ -64,4 +64,4 @@ private:
};
#endif // ENABLE_SCRIPTING
#endif // AP_SCRIPTING_ENABLED

4
libraries/AP_Motors/AP_MotorsMatrix_Scripting_Dynamic.cpp

@ -12,7 +12,7 @@ @@ -12,7 +12,7 @@
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#if ENABLE_SCRIPTING
#if AP_SCRIPTING_ENABLED
// This allows motor roll, pitch, yaw and throttle factors to be changed in flight, allowing vehicle geometry to be changed
@ -125,4 +125,4 @@ void AP_MotorsMatrix_Scripting_Dynamic::output_to_motors() @@ -125,4 +125,4 @@ void AP_MotorsMatrix_Scripting_Dynamic::output_to_motors()
// singleton instance
AP_MotorsMatrix_Scripting_Dynamic *AP_MotorsMatrix_Scripting_Dynamic::_singleton;
#endif // ENABLE_SCRIPTING
#endif // AP_SCRIPTING_ENABLED

4
libraries/AP_Motors/AP_MotorsMatrix_Scripting_Dynamic.h

@ -1,5 +1,5 @@ @@ -1,5 +1,5 @@
#pragma once
#if ENABLE_SCRIPTING
#if AP_SCRIPTING_ENABLED
#include "AP_MotorsMatrix.h"
@ -62,4 +62,4 @@ private: @@ -62,4 +62,4 @@ private:
static AP_MotorsMatrix_Scripting_Dynamic *_singleton;
};
#endif // ENABLE_SCRIPTING
#endif // AP_SCRIPTING_ENABLED

Loading…
Cancel
Save