don't fly
git-svn-id: https://arducopter.googlecode.com/svn/trunk@427 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
5dc67ce6c6
commit
a496ef2b17
@ -6,7 +6,7 @@
|
||||
(Works with last PPM_encoder firmware)
|
||||
*/
|
||||
|
||||
#include <AP_RC.h> // ArduPilot Mega RC Library
|
||||
#include <AP_RC.h> // ArduPilot RC Library
|
||||
AP_RC rc;
|
||||
|
||||
#define CH_ROLL 0
|
||||
|
@ -11,15 +11,12 @@
|
||||
|
||||
#include "Waypoints.h"
|
||||
|
||||
Waypoints::Waypoints(uint16_t start_byte, uint8_t wp_size, uint8_t total)
|
||||
Waypoints::Waypoints()
|
||||
{
|
||||
_start_byte = start_byte;
|
||||
_wp_size = wp_size;
|
||||
_total = total;
|
||||
}
|
||||
|
||||
void
|
||||
Waypoints::set_waypoint_with_index(Waypoints::WP wp, uint16_t i)
|
||||
Waypoints::set_waypoint_with_index(Waypoints::WP wp, uint8_t i)
|
||||
{
|
||||
i = constrain(i, 0, _total);
|
||||
uint32_t mem = _start_byte + (i * _wp_size);
|
||||
@ -45,7 +42,7 @@ Waypoints::set_waypoint_with_index(Waypoints::WP wp, uint16_t i)
|
||||
}
|
||||
|
||||
Waypoints::WP
|
||||
Waypoints::get_waypoint_with_index(uint16_t i)
|
||||
Waypoints::get_waypoint_with_index(uint8_t i)
|
||||
{
|
||||
Waypoints::WP wp;
|
||||
|
||||
@ -79,6 +76,13 @@ Waypoints::get_next_waypoint(void)
|
||||
_index++;
|
||||
if (_index >= _total)
|
||||
_index == 0;
|
||||
return get_waypoint_with_index(_index);
|
||||
}
|
||||
|
||||
Waypoints::WP
|
||||
Waypoints::get_current_waypoint(void)
|
||||
{
|
||||
return get_waypoint_with_index(_index);
|
||||
}
|
||||
|
||||
uint8_t
|
||||
@ -98,3 +102,20 @@ Waypoints::get_total(void)
|
||||
{
|
||||
return _total;
|
||||
}
|
||||
void
|
||||
Waypoints::set_total(uint8_t total)
|
||||
{
|
||||
_total = total;
|
||||
}
|
||||
|
||||
void
|
||||
Waypoints::set_start_byte(uint16_t start_byte)
|
||||
{
|
||||
_start_byte = start_byte;
|
||||
}
|
||||
|
||||
void
|
||||
Waypoints::set_wp_size(uint8_t wp_size)
|
||||
{
|
||||
_wp_size = wp_size;
|
||||
}
|
||||
|
@ -8,7 +8,7 @@
|
||||
class Waypoints
|
||||
{
|
||||
public:
|
||||
Waypoints(uint16_t start_byte, uint8_t wp_size, uint8_t total);
|
||||
Waypoints();
|
||||
|
||||
struct WP {
|
||||
uint8_t id; // for commands
|
||||
@ -17,16 +17,21 @@ class Waypoints
|
||||
int32_t lat; // Lattitude * 10**7
|
||||
int32_t lng; // Longitude * 10**7
|
||||
};
|
||||
|
||||
|
||||
Waypoints::WP get_waypoint_with_index(uint16_t i);
|
||||
Waypoints::WP get_next_waypoint(void);
|
||||
|
||||
void set_waypoint_with_index(Waypoints::WP wp, uint16_t i);
|
||||
WP get_waypoint_with_index(uint16_t i);
|
||||
WP get_current_waypoint(void);
|
||||
WP get_next_waypoint(void);
|
||||
|
||||
void set_waypoint_with_index(Waypoints::WP wp, uint8_t i);
|
||||
|
||||
void set_start_byte(uint16_t start_byte);
|
||||
void set_wp_size(uint8_t wp_size);
|
||||
|
||||
uint8_t get_index(void);
|
||||
void set_index(uint8_t i);
|
||||
|
||||
uint8_t get_total(void);
|
||||
void set_total(uint8_t total);
|
||||
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user