Skip to content
Snippets Groups Projects
Commit 28f2f87b authored by Randy Mackay's avatar Randy Mackay
Browse files

Copter Motors: minor formatting change

parent 2cb28076
No related branches found
No related tags found
No related merge requests found
...@@ -81,7 +81,7 @@ public: ...@@ -81,7 +81,7 @@ public:
virtual void set_frame_orientation( uint8_t new_orientation ) { _frame_orientation = new_orientation; }; virtual void set_frame_orientation( uint8_t new_orientation ) { _frame_orientation = new_orientation; };
// enable - starts allowing signals to be sent to motors // enable - starts allowing signals to be sent to motors
virtual void enable() {}; virtual void enable() = 0;
// arm, disarm or check status status of motors // arm, disarm or check status status of motors
bool armed() { return _armed; }; bool armed() { return _armed; };
...@@ -100,8 +100,7 @@ public: ...@@ -100,8 +100,7 @@ public:
}; };
// output_min - sends minimum values out to the motors // output_min - sends minimum values out to the motors
virtual void output_min() { virtual void output_min() = 0;
};
// reached_limits - return whether we hit the limits of the motors // reached_limits - return whether we hit the limits of the motors
uint8_t reached_limit( uint8_t which_limit = AP_MOTOR_ANY_LIMIT ) { uint8_t reached_limit( uint8_t which_limit = AP_MOTOR_ANY_LIMIT ) {
...@@ -109,8 +108,7 @@ public: ...@@ -109,8 +108,7 @@ public:
} }
// motor test // motor test
virtual void output_test() { virtual void output_test() = 0;
};
// throttle_pass_through - passes pilot's throttle input directly to all motors - dangerous but used for initialising ESCs // throttle_pass_through - passes pilot's throttle input directly to all motors - dangerous but used for initialising ESCs
virtual void throttle_pass_through(); virtual void throttle_pass_through();
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment