Rover: automatic substitution for class members

This commit is contained in:
Andrew Tridgell 2015-05-12 15:03:23 +10:00
parent f99186afbc
commit adbf9c362e
18 changed files with 161 additions and 555 deletions

View File

@ -125,401 +125,17 @@
#include <AP_Declination.h> // ArduPilot Mega Declination Helper Library #include <AP_Declination.h> // ArduPilot Mega Declination Helper Library
AP_HAL::BetterStream* cliSerial; #include "Rover.h"
const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER;
// this sets up the parameter table, and sets the default values. This static Rover rover;
// must be the first AP_Param variable declared to ensure its
// constructor runs before the constructors of the other AP_Param
// variables
AP_Param param_loader(var_info);
////////////////////////////////////////////////////////////////////////////////
// the rate we run the main loop at
////////////////////////////////////////////////////////////////////////////////
static const AP_InertialSensor::Sample_rate ins_sample_rate = AP_InertialSensor::RATE_50HZ;
////////////////////////////////////////////////////////////////////////////////
// Parameters
////////////////////////////////////////////////////////////////////////////////
//
// Global parameters are all contained within the 'g' class.
//
static Parameters g;
// main loop scheduler
static AP_Scheduler scheduler;
// mapping between input channels
static RCMapper rcmap;
// board specific config
static AP_BoardConfig BoardConfig;
// primary control channels
static RC_Channel *channel_steer;
static RC_Channel *channel_throttle;
static RC_Channel *channel_learn;
////////////////////////////////////////////////////////////////////////////////
// prototypes
static void update_events(void);
void gcs_send_text_fmt(const prog_char_t *fmt, ...);
static void print_mode(AP_HAL::BetterStream *port, uint8_t mode);
////////////////////////////////////////////////////////////////////////////////
// DataFlash
////////////////////////////////////////////////////////////////////////////////
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
static DataFlash_APM1 DataFlash;
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
static DataFlash_APM2 DataFlash;
#elif defined(HAL_BOARD_LOG_DIRECTORY)
static DataFlash_File DataFlash(HAL_BOARD_LOG_DIRECTORY);
#else
DataFlash_Empty DataFlash;
#endif
static bool in_log_download;
////////////////////////////////////////////////////////////////////////////////
// Sensors
////////////////////////////////////////////////////////////////////////////////
//
// There are three basic options related to flight sensor selection.
//
// - Normal driving mode. Real sensors are used.
// - HIL Attitude mode. Most sensors are disabled, as the HIL
// protocol supplies attitude information directly.
// - HIL Sensors mode. Synthetic sensors are configured that
// supply data from the simulation.
//
// GPS driver
static AP_GPS gps;
// flight modes convenience array
static AP_Int8 *modes = &g.mode1;
static AP_Baro barometer;
Compass compass;
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
AP_ADC_ADS7844 apm1_adc;
#endif
AP_InertialSensor ins;
////////////////////////////////////////////////////////////////////////////////
// SONAR
static RangeFinder sonar;
// Inertial Navigation EKF
#if AP_AHRS_NAVEKF_AVAILABLE
AP_AHRS_NavEKF ahrs(ins, barometer, gps, sonar);
#else
AP_AHRS_DCM ahrs(ins, barometer, gps);
#endif
static AP_L1_Control L1_controller(ahrs);
// selected navigation controller
static AP_Navigation *nav_controller = &L1_controller;
// steering controller
static AP_SteerController steerController(ahrs);
////////////////////////////////////////////////////////////////////////////////
// Mission library
// forward declaration to avoid compiler errors
////////////////////////////////////////////////////////////////////////////////
static bool start_command(const AP_Mission::Mission_Command& cmd);
static bool verify_command(const AP_Mission::Mission_Command& cmd);
static void exit_mission();
AP_Mission mission(ahrs, &start_command, &verify_command, &exit_mission);
static OpticalFlow optflow;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
SITL sitl;
#endif
////////////////////////////////////////////////////////////////////////////////
// GCS selection
////////////////////////////////////////////////////////////////////////////////
static AP_SerialManager serial_manager;
static const uint8_t num_gcs = MAVLINK_COMM_NUM_BUFFERS;
static GCS_MAVLINK gcs[MAVLINK_COMM_NUM_BUFFERS];
// a pin for reading the receiver RSSI voltage. The scaling by 0.25
// is to take the 0 to 1024 range down to an 8 bit range for MAVLink
AP_HAL::AnalogSource *rssi_analog_source;
// relay support
AP_Relay relay;
AP_ServoRelayEvents ServoRelayEvents(relay);
// Camera
#if CAMERA == ENABLED
static AP_Camera camera(&relay);
#endif
// The rover's current location
static struct Location current_loc;
// Camera/Antenna mount tracking and stabilisation stuff
// --------------------------------------
#if MOUNT == ENABLED
// current_loc uses the baro/gps soloution for altitude rather than gps only.
AP_Mount camera_mount(ahrs, current_loc);
#endif
////////////////////////////////////////////////////////////////////////////////
// Global variables
////////////////////////////////////////////////////////////////////////////////
// if USB is connected
static bool usb_connected;
/* Radio values
Channel assignments
1 Steering
2 ---
3 Throttle
4 ---
5 Aux5
6 Aux6
7 Aux7/learn
8 Aux8/Mode
Each Aux channel can be configured to have any of the available auxiliary functions assigned to it.
See libraries/RC_Channel/RC_Channel_aux.h for more information
*/
////////////////////////////////////////////////////////////////////////////////
// Radio
////////////////////////////////////////////////////////////////////////////////
// This is the state of the flight control system
// There are multiple states defined such as MANUAL, FBW-A, AUTO
enum mode control_mode = INITIALISING;
// Used to maintain the state of the previous control switch position
// This is set to -1 when we need to re-read the switch
uint8_t oldSwitchPosition;
// These are values received from the GCS if the user is using GCS joystick
// control and are substituted for the values coming from the RC radio
static int16_t rc_override[8] = {0,0,0,0,0,0,0,0};
// A flag if GCS joystick control is in use
static bool rc_override_active = false;
////////////////////////////////////////////////////////////////////////////////
// Failsafe
////////////////////////////////////////////////////////////////////////////////
// A tracking variable for type of failsafe active
// Used for failsafe based on loss of RC signal or GCS signal. See
// FAILSAFE_EVENT_*
static struct {
uint8_t bits;
uint32_t rc_override_timer;
uint32_t start_time;
uint8_t triggered;
uint32_t last_valid_rc_ms;
} failsafe;
// notification object for LEDs, buzzers etc (parameter set to false disables external leds)
static AP_Notify notify;
// A counter used to count down valid gps fixes to allow the gps estimate to settle
// before recording our home position (and executing a ground start if we booted with an air start)
static uint8_t ground_start_count = 20;
////////////////////////////////////////////////////////////////////////////////
// Location & Navigation
////////////////////////////////////////////////////////////////////////////////
// Constants
const float radius_of_earth = 6378100; // meters
// true if we have a position estimate from AHRS
static bool have_position;
static bool rtl_complete = false;
// angle of our next navigation waypoint
static int32_t next_navigation_leg_cd;
// ground speed error in m/s
static float groundspeed_error;
// 0-(throttle_max - throttle_cruise) : throttle nudge in Auto mode using top 1/2 of throttle stick travel
static int16_t throttle_nudge = 0;
// receiver RSSI
static uint8_t receiver_rssi;
// the time when the last HEARTBEAT message arrived from a GCS
static uint32_t last_heartbeat_ms;
// obstacle detection information
static struct {
// have we detected an obstacle?
uint8_t detected_count;
float turn_angle;
uint16_t sonar1_distance_cm;
uint16_t sonar2_distance_cm;
// time when we last detected an obstacle, in milliseconds
uint32_t detected_time_ms;
} obstacle;
// this is set to true when auto has been triggered to start
static bool auto_triggered;
////////////////////////////////////////////////////////////////////////////////
// Ground speed
////////////////////////////////////////////////////////////////////////////////
// The amount current ground speed is below min ground speed. meters per second
static float ground_speed = 0;
static int16_t throttle_last = 0, throttle = 500;
////////////////////////////////////////////////////////////////////////////////
// CH7 control
////////////////////////////////////////////////////////////////////////////////
// Used to track the CH7 toggle state.
// When CH7 goes LOW PWM from HIGH PWM, this value will have been set true
// This allows advanced functionality to know when to execute
static bool ch7_flag;
////////////////////////////////////////////////////////////////////////////////
// Battery Sensors
////////////////////////////////////////////////////////////////////////////////
static AP_BattMonitor battery;
////////////////////////////////////////////////////////////////////////////////
// Battery Sensors
////////////////////////////////////////////////////////////////////////////////
#if FRSKY_TELEM_ENABLED == ENABLED
static AP_Frsky_Telem frsky_telemetry(ahrs, battery);
#endif
////////////////////////////////////////////////////////////////////////////////
// Navigation control variables
////////////////////////////////////////////////////////////////////////////////
// The instantaneous desired lateral acceleration in m/s/s
static float lateral_acceleration;
////////////////////////////////////////////////////////////////////////////////
// Waypoint distances
////////////////////////////////////////////////////////////////////////////////
// Distance between rover and next waypoint. Meters
static float wp_distance;
// Distance between previous and next waypoint. Meters
static int32_t wp_totalDistance;
////////////////////////////////////////////////////////////////////////////////
// Conditional command
////////////////////////////////////////////////////////////////////////////////
// A value used in condition commands (eg delay, change alt, etc.)
// For example in a change altitude command, it is the altitude to change to.
static int32_t condition_value;
// A starting value used to check the status of a conditional command.
// For example in a delay command the condition_start records that start time for the delay
static int32_t condition_start;
////////////////////////////////////////////////////////////////////////////////
// 3D Location vectors
// Location structure defined in AP_Common
////////////////////////////////////////////////////////////////////////////////
// The home location used for RTL. The location is set when we first get stable GPS lock
static const struct Location &home = ahrs.get_home();
// Flag for if we have gps lock and have set the home location
static bool home_is_set;
// The location of the previous waypoint. Used for track following and altitude ramp calculations
static struct Location prev_WP;
// The location of the current/active waypoint. Used for track following
static struct Location next_WP;
// The location of the active waypoint in Guided mode.
static struct Location guided_WP;
////////////////////////////////////////////////////////////////////////////////
// IMU variables
////////////////////////////////////////////////////////////////////////////////
// The main loop execution time. Seconds
//This is the time between calls to the DCM algorithm and is the Integration time for the gyros.
static float G_Dt = 0.02;
////////////////////////////////////////////////////////////////////////////////
// Performance monitoring
////////////////////////////////////////////////////////////////////////////////
// Timer used to accrue data and trigger recording of the performanc monitoring log message
static int32_t perf_mon_timer;
// The maximum main loop execution time recorded in the current performance monitoring interval
static uint32_t G_Dt_max;
////////////////////////////////////////////////////////////////////////////////
// System Timers
////////////////////////////////////////////////////////////////////////////////
// Time in microseconds of start of main control loop.
static uint32_t fast_loopTimer_us;
// Number of milliseconds used in last main loop cycle
static uint32_t delta_us_fast_loop;
// Counter of main loop executions. Used for performance monitoring and failsafe processing
static uint16_t mainLoop_count;
// set if we are driving backwards
static bool in_reverse;
////////////////////////////////////////////////////////////////////////////////
// Top-level logic
////////////////////////////////////////////////////////////////////////////////
/*
scheduler table - all regular tasks should be listed here, along
with how often they should be called (in 20ms units) and the maximum
time they are expected to take (in microseconds)
*/
static const AP_Scheduler::Task scheduler_tasks[] PROGMEM = {
{ read_radio, 1, 1000 },
{ ahrs_update, 1, 6400 },
{ read_sonars, 1, 2000 },
{ update_current_mode, 1, 1500 },
{ set_servos, 1, 1500 },
{ update_GPS_50Hz, 1, 2500 },
{ update_GPS_10Hz, 5, 2500 },
{ update_alt, 5, 3400 },
{ navigate, 5, 1600 },
{ update_compass, 5, 2000 },
{ update_commands, 5, 1000 },
{ update_logging1, 5, 1000 },
{ update_logging2, 5, 1000 },
{ gcs_retry_deferred, 1, 1000 },
{ gcs_update, 1, 1700 },
{ gcs_data_stream_send, 1, 3000 },
{ read_control_switch, 15, 1000 },
{ read_trim_switch, 5, 1000 },
{ read_battery, 5, 1000 },
{ read_receiver_rssi, 5, 1000 },
{ update_events, 1, 1000 },
{ check_usb_mux, 15, 1000 },
{ mount_update, 1, 600 },
{ gcs_failsafe_check, 5, 600 },
{ compass_accumulate, 1, 900 },
{ update_notify, 1, 300 },
{ one_second_loop, 50, 3000 },
#if FRSKY_TELEM_ENABLED == ENABLED
{ frsky_telemetry_send, 10, 100 }
#endif
};
/* /*
setup is called when the sketch starts setup is called when the sketch starts
*/ */
void setup() { void Rover::setup()
{
cliSerial = hal.console; cliSerial = hal.console;
// load the default values of variables listed in var_info[] // load the default values of variables listed in var_info[]
@ -544,7 +160,7 @@ void setup() {
/* /*
loop() is called rapidly while the sketch is running loop() is called rapidly while the sketch is running
*/ */
void loop() void Rover::loop()
{ {
// wait for an INS sample // wait for an INS sample
ins.wait_for_sample(); ins.wait_for_sample();
@ -567,7 +183,7 @@ void loop()
} }
// update AHRS system // update AHRS system
static void ahrs_update() void Rover::ahrs_update()
{ {
hal.util->set_soft_armed(hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED); hal.util->set_soft_armed(hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED);
@ -600,7 +216,7 @@ static void ahrs_update()
/* /*
update camera mount - 50Hz update camera mount - 50Hz
*/ */
static void mount_update(void) void Rover::mount_update(void)
{ {
#if MOUNT == ENABLED #if MOUNT == ENABLED
camera_mount.update(); camera_mount.update();
@ -610,7 +226,7 @@ static void mount_update(void)
#endif #endif
} }
static void update_alt() void Rover::update_alt()
{ {
barometer.update(); barometer.update();
if (should_log(MASK_LOG_IMU)) { if (should_log(MASK_LOG_IMU)) {
@ -621,7 +237,7 @@ static void update_alt()
/* /*
check for GCS failsafe - 10Hz check for GCS failsafe - 10Hz
*/ */
static void gcs_failsafe_check(void) void Rover::gcs_failsafe_check(void)
{ {
if (g.fs_gcs_enabled) { if (g.fs_gcs_enabled) {
failsafe_trigger(FAILSAFE_EVENT_GCS, last_heartbeat_ms != 0 && (millis() - last_heartbeat_ms) > 2000); failsafe_trigger(FAILSAFE_EVENT_GCS, last_heartbeat_ms != 0 && (millis() - last_heartbeat_ms) > 2000);
@ -631,7 +247,7 @@ static void gcs_failsafe_check(void)
/* /*
if the compass is enabled then try to accumulate a reading if the compass is enabled then try to accumulate a reading
*/ */
static void compass_accumulate(void) void Rover::compass_accumulate(void)
{ {
if (g.compass_enabled) { if (g.compass_enabled) {
compass.accumulate(); compass.accumulate();
@ -641,7 +257,7 @@ static void compass_accumulate(void)
/* /*
check for new compass data - 10Hz check for new compass data - 10Hz
*/ */
static void update_compass(void) void Rover::update_compass(void)
{ {
if (g.compass_enabled && compass.read()) { if (g.compass_enabled && compass.read()) {
ahrs.set_compass(&compass); ahrs.set_compass(&compass);
@ -658,7 +274,7 @@ static void update_compass(void)
/* /*
log some key data - 10Hz log some key data - 10Hz
*/ */
static void update_logging1(void) void Rover::update_logging1(void)
{ {
if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST))
Log_Write_Attitude(); Log_Write_Attitude();
@ -673,7 +289,7 @@ static void update_logging1(void)
/* /*
log some key data - 10Hz log some key data - 10Hz
*/ */
static void update_logging2(void) void Rover::update_logging2(void)
{ {
if (should_log(MASK_LOG_STEERING)) { if (should_log(MASK_LOG_STEERING)) {
if (control_mode == STEERING || control_mode == AUTO || control_mode == RTL || control_mode == GUIDED) { if (control_mode == STEERING || control_mode == AUTO || control_mode == RTL || control_mode == GUIDED) {
@ -689,7 +305,7 @@ static void update_logging2(void)
/* /*
update aux servo mappings update aux servo mappings
*/ */
static void update_aux(void) void Rover::update_aux(void)
{ {
RC_Channel_aux::enable_aux_servos(); RC_Channel_aux::enable_aux_servos();
} }
@ -697,7 +313,7 @@ static void update_aux(void)
/* /*
once a second events once a second events
*/ */
static void one_second_loop(void) void Rover::one_second_loop(void)
{ {
if (should_log(MASK_LOG_CURRENT)) if (should_log(MASK_LOG_CURRENT))
Log_Write_Current(); Log_Write_Current();
@ -715,7 +331,7 @@ static void one_second_loop(void)
// cope with changes to mavlink system ID // cope with changes to mavlink system ID
mavlink_system.sysid = g.sysid_this_mav; mavlink_system.sysid = g.sysid_this_mav;
static uint8_t counter; uint8_t Rover::counter;
counter++; counter++;
@ -741,9 +357,9 @@ static void one_second_loop(void)
ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW)); ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW));
} }
static void update_GPS_50Hz(void) void Rover::update_GPS_50Hz(void)
{ {
static uint32_t last_gps_reading[GPS_MAX_INSTANCES]; uint32_t Rover::last_gps_reading[GPS_MAX_INSTANCES];
gps.update(); gps.update();
for (uint8_t i=0; i<gps.num_sensors(); i++) { for (uint8_t i=0; i<gps.num_sensors(); i++) {
@ -757,7 +373,7 @@ static void update_GPS_50Hz(void)
} }
static void update_GPS_10Hz(void) void Rover::update_GPS_10Hz(void)
{ {
have_position = ahrs.get_position(current_loc); have_position = ahrs.get_position(current_loc);
@ -800,7 +416,7 @@ static void update_GPS_10Hz(void)
} }
} }
static void update_current_mode(void) void Rover::update_current_mode(void)
{ {
switch (control_mode){ switch (control_mode){
case AUTO: case AUTO:
@ -884,7 +500,7 @@ static void update_current_mode(void)
} }
} }
static void update_navigation() void Rover::update_navigation()
{ {
switch (control_mode) { switch (control_mode) {
case MANUAL: case MANUAL:

View File

@ -4,7 +4,7 @@
#define MAVLINK_SENSOR_PRESENT_DEFAULT (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL | MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION | MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL | MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS | MAV_SYS_STATUS_AHRS) #define MAVLINK_SENSOR_PRESENT_DEFAULT (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL | MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION | MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL | MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS | MAV_SYS_STATUS_AHRS)
// use this to prevent recursion during sensor init // use this to prevent recursion during sensor init
static bool in_mavlink_delay; bool Rover::in_mavlink_delay;
// true if we are out of time in our event timeslice // true if we are out of time in our event timeslice
static bool gcs_out_of_time; static bool gcs_out_of_time;
@ -12,17 +12,7 @@ static bool gcs_out_of_time;
// check if a message will fit in the payload space available // check if a message will fit in the payload space available
#define CHECK_PAYLOAD_SIZE(id) if (txspace < MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_MSG_ID_## id ##_LEN) return false #define CHECK_PAYLOAD_SIZE(id) if (txspace < MAVLINK_NUM_NON_PAYLOAD_BYTES+MAVLINK_MSG_ID_## id ##_LEN) return false
/* void Rover::send_heartbeat(mavlink_channel_t chan)
* !!NOTE!!
*
* the use of NOINLINE separate functions for each message type avoids
* a compiler bug in gcc that would cause it to use far more stack
* space than is needed. Without the NOINLINE we use the sum of the
* stack needed for each message type. Please be careful to follow the
* pattern below when adding any new messages
*/
static NOINLINE void send_heartbeat(mavlink_channel_t chan)
{ {
uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED; uint8_t base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
uint8_t system_status = MAV_STATE_ACTIVE; uint8_t system_status = MAV_STATE_ACTIVE;
@ -91,7 +81,7 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
system_status); system_status);
} }
static NOINLINE void send_attitude(mavlink_channel_t chan) void Rover::send_attitude(mavlink_channel_t chan)
{ {
Vector3f omega = ahrs.get_gyro(); Vector3f omega = ahrs.get_gyro();
mavlink_msg_attitude_send( mavlink_msg_attitude_send(
@ -105,7 +95,7 @@ static NOINLINE void send_attitude(mavlink_channel_t chan)
omega.z); omega.z);
} }
static NOINLINE void send_extended_status1(mavlink_channel_t chan) void Rover::send_extended_status1(mavlink_channel_t chan)
{ {
uint32_t control_sensors_present; uint32_t control_sensors_present;
uint32_t control_sensors_enabled; uint32_t control_sensors_enabled;
@ -203,7 +193,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
} }
static void NOINLINE send_location(mavlink_channel_t chan) void Rover:: send_location(mavlink_channel_t chan)
{ {
uint32_t fix_time; uint32_t fix_time;
// if we have a GPS fix, take the time as the last fix time. That // if we have a GPS fix, take the time as the last fix time. That
@ -230,7 +220,7 @@ static void NOINLINE send_location(mavlink_channel_t chan)
ahrs.yaw_sensor); ahrs.yaw_sensor);
} }
static void NOINLINE send_nav_controller_output(mavlink_channel_t chan) void Rover:: send_nav_controller_output(mavlink_channel_t chan)
{ {
mavlink_msg_nav_controller_output_send( mavlink_msg_nav_controller_output_send(
chan, chan,
@ -244,7 +234,7 @@ static void NOINLINE send_nav_controller_output(mavlink_channel_t chan)
nav_controller->crosstrack_error()); nav_controller->crosstrack_error());
} }
static void NOINLINE send_servo_out(mavlink_channel_t chan) void Rover:: send_servo_out(mavlink_channel_t chan)
{ {
#if HIL_MODE != HIL_MODE_DISABLED #if HIL_MODE != HIL_MODE_DISABLED
// normalized values scaled to -10000 to 10000 // normalized values scaled to -10000 to 10000
@ -266,7 +256,7 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
#endif #endif
} }
static void NOINLINE send_radio_out(mavlink_channel_t chan) void Rover:: send_radio_out(mavlink_channel_t chan)
{ {
#if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS #if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS
mavlink_msg_servo_output_raw_send( mavlink_msg_servo_output_raw_send(
@ -297,7 +287,7 @@ static void NOINLINE send_radio_out(mavlink_channel_t chan)
#endif #endif
} }
static void NOINLINE send_vfr_hud(mavlink_channel_t chan) void Rover:: send_vfr_hud(mavlink_channel_t chan)
{ {
mavlink_msg_vfr_hud_send( mavlink_msg_vfr_hud_send(
chan, chan,
@ -310,14 +300,14 @@ static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
} }
// report simulator state // report simulator state
static void NOINLINE send_simstate(mavlink_channel_t chan) void Rover:: send_simstate(mavlink_channel_t chan)
{ {
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
sitl.simstate_send(chan); sitl.simstate_send(chan);
#endif #endif
} }
static void NOINLINE send_hwstatus(mavlink_channel_t chan) void Rover:: send_hwstatus(mavlink_channel_t chan)
{ {
mavlink_msg_hwstatus_send( mavlink_msg_hwstatus_send(
chan, chan,
@ -325,7 +315,7 @@ static void NOINLINE send_hwstatus(mavlink_channel_t chan)
hal.i2c->lockup_count()); hal.i2c->lockup_count());
} }
static void NOINLINE send_rangefinder(mavlink_channel_t chan) void Rover:: send_rangefinder(mavlink_channel_t chan)
{ {
if (!sonar.has_data(0) && !sonar.has_data(1)) { if (!sonar.has_data(0) && !sonar.has_data(1)) {
// no sonar to report // no sonar to report
@ -364,12 +354,12 @@ static void NOINLINE send_rangefinder(mavlink_channel_t chan)
voltage); voltage);
} }
static void NOINLINE send_current_waypoint(mavlink_channel_t chan) void Rover:: send_current_waypoint(mavlink_channel_t chan)
{ {
mavlink_msg_mission_current_send(chan, mission.get_current_nav_index()); mavlink_msg_mission_current_send(chan, mission.get_current_nav_index());
} }
static void NOINLINE send_statustext(mavlink_channel_t chan) void Rover:: send_statustext(mavlink_channel_t chan)
{ {
mavlink_statustext_t *s = &gcs[chan-MAVLINK_COMM_0].pending_status; mavlink_statustext_t *s = &gcs[chan-MAVLINK_COMM_0].pending_status;
mavlink_msg_statustext_send( mavlink_msg_statustext_send(
@ -379,7 +369,7 @@ static void NOINLINE send_statustext(mavlink_channel_t chan)
} }
// are we still delaying telemetry to try to avoid Xbee bricking? // are we still delaying telemetry to try to avoid Xbee bricking?
static bool telemetry_delayed(mavlink_channel_t chan) bool Rover::telemetry_delayed(mavlink_channel_t chan)
{ {
uint32_t tnow = millis() >> 10; uint32_t tnow = millis() >> 10;
if (tnow > (uint32_t)g.telem_delay) { if (tnow > (uint32_t)g.telem_delay) {
@ -1241,9 +1231,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
* MAVLink to process packets while waiting for the initialisation to * MAVLink to process packets while waiting for the initialisation to
* complete * complete
*/ */
static void mavlink_delay_cb() void Rover::mavlink_delay_cb()
{ {
static uint32_t last_1hz, last_50hz, last_5s; uint32_t Rover::last_1hz, last_50hz, last_5s;
if (!gcs[0].initialised || in_mavlink_delay) return; if (!gcs[0].initialised || in_mavlink_delay) return;
in_mavlink_delay = true; in_mavlink_delay = true;
@ -1272,7 +1262,7 @@ static void mavlink_delay_cb()
/* /*
* send a message on both GCS links * send a message on both GCS links
*/ */
static void gcs_send_message(enum ap_message id) void Rover::gcs_send_message(enum ap_message id)
{ {
for (uint8_t i=0; i<num_gcs; i++) { for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) { if (gcs[i].initialised) {
@ -1284,7 +1274,7 @@ static void gcs_send_message(enum ap_message id)
/* /*
* send data streams in the given rate range on both links * send data streams in the given rate range on both links
*/ */
static void gcs_data_stream_send(void) void Rover::gcs_data_stream_send(void)
{ {
for (uint8_t i=0; i<num_gcs; i++) { for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) { if (gcs[i].initialised) {
@ -1296,7 +1286,7 @@ static void gcs_data_stream_send(void)
/* /*
* look for incoming commands on the GCS links * look for incoming commands on the GCS links
*/ */
static void gcs_update(void) void Rover::gcs_update(void)
{ {
for (uint8_t i=0; i<num_gcs; i++) { for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) { if (gcs[i].initialised) {
@ -1309,7 +1299,7 @@ static void gcs_update(void)
} }
} }
static void gcs_send_text_P(gcs_severity severity, const prog_char_t *str) void Rover::gcs_send_text_P(gcs_severity severity, const prog_char_t *str)
{ {
for (uint8_t i=0; i<num_gcs; i++) { for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) { if (gcs[i].initialised) {
@ -1350,7 +1340,7 @@ void gcs_send_text_fmt(const prog_char_t *fmt, ...)
/** /**
retry any deferred messages retry any deferred messages
*/ */
static void gcs_retry_deferred(void) void Rover::gcs_retry_deferred(void)
{ {
gcs_send_message(MSG_RETRY_DEFERRED); gcs_send_message(MSG_RETRY_DEFERRED);
} }

View File

@ -160,7 +160,7 @@ process_logs(uint8_t argc, const Menu::arg *argv)
#endif // CLI_ENABLED == ENABLED #endif // CLI_ENABLED == ENABLED
static void do_erase_logs(void) void Rover::do_erase_logs(void)
{ {
cliSerial->printf_P(PSTR("\nErasing log...\n")); cliSerial->printf_P(PSTR("\nErasing log...\n"));
DataFlash.EraseAll(); DataFlash.EraseAll();
@ -182,7 +182,7 @@ struct PACKED log_Performance {
}; };
// Write a performance monitoring packet. Total length : 19 bytes // Write a performance monitoring packet. Total length : 19 bytes
static void Log_Write_Performance() void Rover::Log_Write_Performance()
{ {
struct log_Performance pkt = { struct log_Performance pkt = {
LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG), LOG_PACKET_HEADER_INIT(LOG_PERFORMANCE_MSG),
@ -200,7 +200,7 @@ static void Log_Write_Performance()
} }
// Write a mission command. Total length : 36 bytes // Write a mission command. Total length : 36 bytes
static void Log_Write_Cmd(const AP_Mission::Mission_Command &cmd) void Rover::Log_Write_Cmd(const AP_Mission::Mission_Command &cmd)
{ {
mavlink_mission_item_t mav_cmd = {}; mavlink_mission_item_t mav_cmd = {};
AP_Mission::mission_cmd_to_mavlink(cmd,mav_cmd); AP_Mission::mission_cmd_to_mavlink(cmd,mav_cmd);
@ -215,7 +215,7 @@ struct PACKED log_Steering {
}; };
// Write a steering packet // Write a steering packet
static void Log_Write_Steering() void Rover::Log_Write_Steering()
{ {
struct log_Steering pkt = { struct log_Steering pkt = {
LOG_PACKET_HEADER_INIT(LOG_STEERING_MSG), LOG_PACKET_HEADER_INIT(LOG_STEERING_MSG),
@ -233,7 +233,7 @@ struct PACKED log_Startup {
uint16_t command_total; uint16_t command_total;
}; };
static void Log_Write_Startup(uint8_t type) void Rover::Log_Write_Startup(uint8_t type)
{ {
struct log_Startup pkt = { struct log_Startup pkt = {
LOG_PACKET_HEADER_INIT(LOG_STARTUP_MSG), LOG_PACKET_HEADER_INIT(LOG_STARTUP_MSG),
@ -247,7 +247,7 @@ static void Log_Write_Startup(uint8_t type)
Log_Write_EntireMission(); Log_Write_EntireMission();
} }
static void Log_Write_EntireMission() void Rover::Log_Write_EntireMission()
{ {
DataFlash.Log_Write_Message_P(PSTR("New mission")); DataFlash.Log_Write_Message_P(PSTR("New mission"));
@ -270,7 +270,7 @@ struct PACKED log_Control_Tuning {
}; };
// Write a control tuning packet. Total length : 22 bytes // Write a control tuning packet. Total length : 22 bytes
static void Log_Write_Control_Tuning() void Rover::Log_Write_Control_Tuning()
{ {
Vector3f accel = ins.get_accel(); Vector3f accel = ins.get_accel();
struct log_Control_Tuning pkt = { struct log_Control_Tuning pkt = {
@ -296,7 +296,7 @@ struct PACKED log_Nav_Tuning {
}; };
// Write a navigation tuning packet. Total length : 18 bytes // Write a navigation tuning packet. Total length : 18 bytes
static void Log_Write_Nav_Tuning() void Rover::Log_Write_Nav_Tuning()
{ {
struct log_Nav_Tuning pkt = { struct log_Nav_Tuning pkt = {
LOG_PACKET_HEADER_INIT(LOG_NTUN_MSG), LOG_PACKET_HEADER_INIT(LOG_NTUN_MSG),
@ -311,7 +311,7 @@ static void Log_Write_Nav_Tuning()
} }
// Write an attitude packet // Write an attitude packet
static void Log_Write_Attitude() void Rover::Log_Write_Attitude()
{ {
Vector3f targets(0,0,0); // Rover does not have attitude targets, use place-holder for commonality with Dataflash Log_Write_Attitude message Vector3f targets(0,0,0); // Rover does not have attitude targets, use place-holder for commonality with Dataflash Log_Write_Attitude message
@ -342,7 +342,7 @@ struct PACKED log_Sonar {
}; };
// Write a sonar packet // Write a sonar packet
static void Log_Write_Sonar() void Rover::Log_Write_Sonar()
{ {
uint16_t turn_time = 0; uint16_t turn_time = 0;
if (!is_zero(obstacle.turn_angle)) { if (!is_zero(obstacle.turn_angle)) {
@ -363,7 +363,7 @@ static void Log_Write_Sonar()
DataFlash.WriteBlock(&pkt, sizeof(pkt)); DataFlash.WriteBlock(&pkt, sizeof(pkt));
} }
static void Log_Write_Current() void Rover::Log_Write_Current()
{ {
DataFlash.Log_Write_Current(battery, channel_throttle->control_in); DataFlash.Log_Write_Current(battery, channel_throttle->control_in);
@ -371,13 +371,13 @@ static void Log_Write_Current()
DataFlash.Log_Write_Power(); DataFlash.Log_Write_Power();
} }
static void Log_Write_RC(void) void Rover::Log_Write_RC(void)
{ {
DataFlash.Log_Write_RCIN(); DataFlash.Log_Write_RCIN();
DataFlash.Log_Write_RCOUT(); DataFlash.Log_Write_RCOUT();
} }
static void Log_Write_Baro(void) void Rover::Log_Write_Baro(void)
{ {
DataFlash.Log_Write_Baro(barometer); DataFlash.Log_Write_Baro(barometer);
} }
@ -401,7 +401,7 @@ static const struct LogStructure log_structure[] PROGMEM = {
#if CLI_ENABLED == ENABLED #if CLI_ENABLED == ENABLED
// Read the DataFlash log memory : Packet Parser // Read the DataFlash log memory : Packet Parser
static void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page) void Rover::Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page)
{ {
cliSerial->printf_P(PSTR("\n" FIRMWARE_STRING cliSerial->printf_P(PSTR("\n" FIRMWARE_STRING
"\nFree RAM: %u\n"), "\nFree RAM: %u\n"),
@ -416,7 +416,7 @@ static void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page)
#endif // CLI_ENABLED #endif // CLI_ENABLED
// start a new log // start a new log
static void start_logging() void Rover::start_logging()
{ {
in_mavlink_delay = true; in_mavlink_delay = true;
DataFlash.StartNewLog(); DataFlash.StartNewLog();
@ -437,18 +437,18 @@ static void start_logging()
#else // LOGGING_ENABLED #else // LOGGING_ENABLED
// dummy functions // dummy functions
static void Log_Write_Startup(uint8_t type) {} void Rover::Log_Write_Startup(uint8_t type) {}
static void Log_Write_EntireMission() {} void Rover::Log_Write_EntireMission() {}
static void Log_Write_Current() {} void Rover::Log_Write_Current() {}
static void Log_Write_Nav_Tuning() {} void Rover::Log_Write_Nav_Tuning() {}
static void Log_Write_Performance() {} void Rover::Log_Write_Performance() {}
static void Log_Write_Cmd(const AP_Mission::Mission_Command &cmd) {} void Rover::Log_Write_Cmd(const AP_Mission::Mission_Command &cmd) {}
static int8_t process_logs(uint8_t argc, const Menu::arg *argv) { return 0; } int8_t Rover::process_logs(uint8_t argc, const Menu::arg *argv) { return 0; }
static void Log_Write_Control_Tuning() {} void Rover::Log_Write_Control_Tuning() {}
static void Log_Write_Sonar() {} void Rover::Log_Write_Sonar() {}
static void Log_Write_Attitude() {} void Rover::Log_Write_Attitude() {}
static void start_logging() {} void Rover::start_logging() {}
static void Log_Write_RC(void) {} void Rover::Log_Write_RC(void) {}
#endif // LOGGING_ENABLED #endif // LOGGING_ENABLED

View File

@ -550,7 +550,7 @@ const AP_Param::ConversionInfo conversion_table[] PROGMEM = {
{ Parameters::k_param_serial2_baud, 0, AP_PARAM_INT16, "SERIAL2_BAUD" }, { Parameters::k_param_serial2_baud, 0, AP_PARAM_INT16, "SERIAL2_BAUD" },
}; };
static void load_parameters(void) void Rover::load_parameters(void)
{ {
if (!AP_Param::check_var_info()) { if (!AP_Param::check_var_info()) {
cliSerial->printf_P(PSTR("Bad var table\n")); cliSerial->printf_P(PSTR("Bad var table\n"));

View File

@ -3,7 +3,7 @@
/***************************************** /*****************************************
* Throttle slew limit * Throttle slew limit
*****************************************/ *****************************************/
static void throttle_slew_limit(int16_t last_throttle) void Rover::throttle_slew_limit(int16_t last_throttle)
{ {
// if slew limit rate is set to zero then do not slew limit // if slew limit rate is set to zero then do not slew limit
if (g.throttle_slewrate && last_throttle != 0) { if (g.throttle_slewrate && last_throttle != 0) {
@ -20,7 +20,7 @@ static void throttle_slew_limit(int16_t last_throttle)
/* /*
check for triggering of start of auto mode check for triggering of start of auto mode
*/ */
static bool auto_check_trigger(void) bool Rover::auto_check_trigger(void)
{ {
// only applies to AUTO mode // only applies to AUTO mode
if (control_mode != AUTO) { if (control_mode != AUTO) {
@ -67,7 +67,7 @@ static bool auto_check_trigger(void)
/* /*
work out if we are going to use pivot steering work out if we are going to use pivot steering
*/ */
static bool use_pivot_steering(void) bool Rover::use_pivot_steering(void)
{ {
if (control_mode >= AUTO && g.skid_steer_out && g.pivot_turn_angle != 0) { if (control_mode >= AUTO && g.skid_steer_out && g.pivot_turn_angle != 0) {
int16_t bearing_error = wrap_180_cd(nav_controller->target_bearing_cd() - ahrs.yaw_sensor) / 100; int16_t bearing_error = wrap_180_cd(nav_controller->target_bearing_cd() - ahrs.yaw_sensor) / 100;
@ -82,7 +82,7 @@ static bool use_pivot_steering(void)
/* /*
calculate the throtte for auto-throttle modes calculate the throtte for auto-throttle modes
*/ */
static void calc_throttle(float target_speed) void Rover::calc_throttle(float target_speed)
{ {
if (!auto_check_trigger()) { if (!auto_check_trigger()) {
channel_throttle->servo_out = g.throttle_min.get(); channel_throttle->servo_out = g.throttle_min.get();
@ -158,7 +158,7 @@ static void calc_throttle(float target_speed)
* Calculate desired turn angles (in medium freq loop) * Calculate desired turn angles (in medium freq loop)
*****************************************/ *****************************************/
static void calc_lateral_acceleration() void Rover::calc_lateral_acceleration()
{ {
switch (control_mode) { switch (control_mode) {
case AUTO: case AUTO:
@ -192,7 +192,7 @@ static void calc_lateral_acceleration()
/* /*
calculate steering angle given lateral_acceleration calculate steering angle given lateral_acceleration
*/ */
static void calc_nav_steer() void Rover::calc_nav_steer()
{ {
// add in obstacle avoidance // add in obstacle avoidance
lateral_acceleration += (obstacle.turn_angle/45.0f) * g.turn_max_g; lateral_acceleration += (obstacle.turn_angle/45.0f) * g.turn_max_g;
@ -206,7 +206,7 @@ static void calc_nav_steer()
/***************************************** /*****************************************
* Set the flight control servos based on the current calculated values * Set the flight control servos based on the current calculated values
*****************************************/ *****************************************/
static void set_servos(void) void Rover::set_servos(void)
{ {
static int16_t last_throttle; static int16_t last_throttle;

View File

@ -12,7 +12,7 @@
/* /*
* set_next_WP - sets the target location the vehicle should fly to * set_next_WP - sets the target location the vehicle should fly to
*/ */
static void set_next_WP(const struct Location& loc) void Rover::set_next_WP(const struct Location& loc)
{ {
// copy the current WP into the OldWP slot // copy the current WP into the OldWP slot
// --------------------------------------- // ---------------------------------------
@ -37,7 +37,7 @@ static void set_next_WP(const struct Location& loc)
wp_distance = wp_totalDistance; wp_distance = wp_totalDistance;
} }
static void set_guided_WP(void) void Rover::set_guided_WP(void)
{ {
// copy the current location into the OldWP slot // copy the current location into the OldWP slot
// --------------------------------------- // ---------------------------------------
@ -78,7 +78,7 @@ void init_home()
guided_WP = home; guided_WP = home;
} }
static void restart_nav() void Rover::restart_nav()
{ {
g.pidSpeedThrottle.reset_I(); g.pidSpeedThrottle.reset_I();
prev_WP = current_loc; prev_WP = current_loc;

View File

@ -1,15 +1,15 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// forward declarations to make compiler happy // forward declarations to make compiler happy
static void do_nav_wp(const AP_Mission::Mission_Command& cmd); void Rover::do_nav_wp(const AP_Mission::Mission_Command& cmd);
static void do_wait_delay(const AP_Mission::Mission_Command& cmd); void Rover::do_wait_delay(const AP_Mission::Mission_Command& cmd);
static void do_within_distance(const AP_Mission::Mission_Command& cmd); void Rover::do_within_distance(const AP_Mission::Mission_Command& cmd);
static void do_change_speed(const AP_Mission::Mission_Command& cmd); void Rover::do_change_speed(const AP_Mission::Mission_Command& cmd);
static void do_set_home(const AP_Mission::Mission_Command& cmd); void Rover::do_set_home(const AP_Mission::Mission_Command& cmd);
static bool verify_nav_wp(const AP_Mission::Mission_Command& cmd); bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd);
#if CAMERA == ENABLED #if CAMERA == ENABLED
static void do_digicam_configure(const AP_Mission::Mission_Command& cmd); void Rover::do_digicam_configure(const AP_Mission::Mission_Command& cmd);
static void do_digicam_control(const AP_Mission::Mission_Command& cmd); void Rover::do_digicam_control(const AP_Mission::Mission_Command& cmd);
#endif #endif
/********************************************************************************/ /********************************************************************************/
@ -125,7 +125,7 @@ start_command(const AP_Mission::Mission_Command& cmd)
// exit_mission - callback function called from ap-mission when the mission has completed // exit_mission - callback function called from ap-mission when the mission has completed
// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode // we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode
static void exit_mission() void Rover::exit_mission()
{ {
if (control_mode == AUTO) { if (control_mode == AUTO) {
gcs_send_text_fmt(PSTR("No commands. Can't set AUTO - setting HOLD")); gcs_send_text_fmt(PSTR("No commands. Can't set AUTO - setting HOLD"));
@ -138,7 +138,7 @@ static void exit_mission()
// Returns true if command complete // Returns true if command complete
/********************************************************************************/ /********************************************************************************/
static bool verify_command(const AP_Mission::Mission_Command& cmd) bool Rover::verify_command(const AP_Mission::Mission_Command& cmd)
{ {
// exit immediately if not in AUTO mode // exit immediately if not in AUTO mode
// we return true or we will continue to be called by ap-mission // we return true or we will continue to be called by ap-mission
@ -178,14 +178,14 @@ static bool verify_command(const AP_Mission::Mission_Command& cmd)
// Nav (Must) commands // Nav (Must) commands
/********************************************************************************/ /********************************************************************************/
static void do_RTL(void) void Rover::do_RTL(void)
{ {
prev_WP = current_loc; prev_WP = current_loc;
control_mode = RTL; control_mode = RTL;
next_WP = home; next_WP = home;
} }
static void do_nav_wp(const AP_Mission::Mission_Command& cmd) void Rover::do_nav_wp(const AP_Mission::Mission_Command& cmd)
{ {
set_next_WP(cmd.content.location); set_next_WP(cmd.content.location);
} }
@ -193,7 +193,7 @@ static void do_nav_wp(const AP_Mission::Mission_Command& cmd)
/********************************************************************************/ /********************************************************************************/
// Verify Nav (Must) commands // Verify Nav (Must) commands
/********************************************************************************/ /********************************************************************************/
static bool verify_nav_wp(const AP_Mission::Mission_Command& cmd) bool Rover::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
{ {
if ((wp_distance > 0) && (wp_distance <= g.waypoint_radius)) { if ((wp_distance > 0) && (wp_distance <= g.waypoint_radius)) {
gcs_send_text_fmt(PSTR("Reached Waypoint #%i dist %um"), gcs_send_text_fmt(PSTR("Reached Waypoint #%i dist %um"),
@ -213,7 +213,7 @@ static bool verify_nav_wp(const AP_Mission::Mission_Command& cmd)
return false; return false;
} }
static bool verify_RTL() bool Rover::verify_RTL()
{ {
if (wp_distance <= g.waypoint_radius) { if (wp_distance <= g.waypoint_radius) {
gcs_send_text_P(SEVERITY_LOW,PSTR("Reached Destination")); gcs_send_text_P(SEVERITY_LOW,PSTR("Reached Destination"));
@ -236,13 +236,13 @@ static bool verify_RTL()
// Condition (May) commands // Condition (May) commands
/********************************************************************************/ /********************************************************************************/
static void do_wait_delay(const AP_Mission::Mission_Command& cmd) void Rover::do_wait_delay(const AP_Mission::Mission_Command& cmd)
{ {
condition_start = millis(); condition_start = millis();
condition_value = cmd.content.delay.seconds * 1000; // convert seconds to milliseconds condition_value = cmd.content.delay.seconds * 1000; // convert seconds to milliseconds
} }
static void do_within_distance(const AP_Mission::Mission_Command& cmd) void Rover::do_within_distance(const AP_Mission::Mission_Command& cmd)
{ {
condition_value = cmd.content.distance.meters; condition_value = cmd.content.distance.meters;
} }
@ -251,7 +251,7 @@ static void do_within_distance(const AP_Mission::Mission_Command& cmd)
// Verify Condition (May) commands // Verify Condition (May) commands
/********************************************************************************/ /********************************************************************************/
static bool verify_wait_delay() bool Rover::verify_wait_delay()
{ {
if ((uint32_t)(millis() - condition_start) > (uint32_t)condition_value){ if ((uint32_t)(millis() - condition_start) > (uint32_t)condition_value){
condition_value = 0; condition_value = 0;
@ -260,7 +260,7 @@ static bool verify_wait_delay()
return false; return false;
} }
static bool verify_within_distance() bool Rover::verify_within_distance()
{ {
if (wp_distance < condition_value){ if (wp_distance < condition_value){
condition_value = 0; condition_value = 0;
@ -273,7 +273,7 @@ static bool verify_within_distance()
// Do (Now) commands // Do (Now) commands
/********************************************************************************/ /********************************************************************************/
static void do_change_speed(const AP_Mission::Mission_Command& cmd) void Rover::do_change_speed(const AP_Mission::Mission_Command& cmd)
{ {
switch (cmd.p1) switch (cmd.p1)
{ {
@ -291,7 +291,7 @@ static void do_change_speed(const AP_Mission::Mission_Command& cmd)
} }
} }
static void do_set_home(const AP_Mission::Mission_Command& cmd) void Rover::do_set_home(const AP_Mission::Mission_Command& cmd)
{ {
if(cmd.p1 == 1 && have_position) { if(cmd.p1 == 1 && have_position) {
init_home(); init_home();
@ -302,7 +302,7 @@ static void do_set_home(const AP_Mission::Mission_Command& cmd)
} }
// do_digicam_configure Send Digicam Configure message with the camera library // do_digicam_configure Send Digicam Configure message with the camera library
static void do_digicam_configure(const AP_Mission::Mission_Command& cmd) void Rover::do_digicam_configure(const AP_Mission::Mission_Command& cmd)
{ {
#if CAMERA == ENABLED #if CAMERA == ENABLED
camera.configure_cmd(cmd); camera.configure_cmd(cmd);
@ -310,7 +310,7 @@ static void do_digicam_configure(const AP_Mission::Mission_Command& cmd)
} }
// do_digicam_control Send Digicam Control message with the camera library // do_digicam_control Send Digicam Control message with the camera library
static void do_digicam_control(const AP_Mission::Mission_Command& cmd) void Rover::do_digicam_control(const AP_Mission::Mission_Command& cmd)
{ {
#if CAMERA == ENABLED #if CAMERA == ENABLED
camera.control_cmd(cmd); camera.control_cmd(cmd);
@ -319,7 +319,7 @@ static void do_digicam_control(const AP_Mission::Mission_Command& cmd)
} }
// do_take_picture - take a picture with the camera library // do_take_picture - take a picture with the camera library
static void do_take_picture() void Rover::do_take_picture()
{ {
#if CAMERA == ENABLED #if CAMERA == ENABLED
camera.trigger_pic(true); camera.trigger_pic(true);
@ -328,7 +328,7 @@ static void do_take_picture()
} }
// log_picture - log picture taken and send feedback to GCS // log_picture - log picture taken and send feedback to GCS
static void log_picture() void Rover::log_picture()
{ {
gcs_send_message(MSG_CAMERA_FEEDBACK); gcs_send_message(MSG_CAMERA_FEEDBACK);
if (should_log(MASK_LOG_CAMERA)) { if (should_log(MASK_LOG_CAMERA)) {

View File

@ -2,7 +2,7 @@
// called by update navigation at 10Hz // called by update navigation at 10Hz
// -------------------- // --------------------
static void update_commands(void) void Rover::update_commands(void)
{ {
if(control_mode == AUTO) { if(control_mode == AUTO) {
if(home_is_set == true && mission.num_commands() > 1) { if(home_is_set == true && mission.num_commands() > 1) {

View File

@ -1,21 +1,21 @@
static void delay(uint32_t ms) void Rover::delay(uint32_t ms)
{ {
hal.scheduler->delay(ms); hal.scheduler->delay(ms);
} }
static void mavlink_delay(uint32_t ms) void Rover::mavlink_delay(uint32_t ms)
{ {
hal.scheduler->delay(ms); hal.scheduler->delay(ms);
} }
static uint32_t millis() uint32_t Rover::millis()
{ {
return hal.scheduler->millis(); return hal.scheduler->millis();
} }
static uint32_t micros() uint32_t Rover::micros()
{ {
return hal.scheduler->micros(); return hal.scheduler->micros();
} }

View File

@ -1,6 +1,6 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static void read_control_switch() void Rover::read_control_switch()
{ {
uint8_t switchPosition = readSwitch(); uint8_t switchPosition = readSwitch();
@ -35,7 +35,7 @@ static void read_control_switch()
} }
static uint8_t readSwitch(void){ uint8_t Rover::readSwitch(void){
uint16_t pulsewidth = hal.rcin->read(g.mode_channel - 1); uint16_t pulsewidth = hal.rcin->read(g.mode_channel - 1);
if (pulsewidth <= 900 || pulsewidth >= 2200) return 255; // This is an error condition if (pulsewidth <= 900 || pulsewidth >= 2200) return 255; // This is an error condition
if (pulsewidth > 1230 && pulsewidth <= 1360) return 1; if (pulsewidth > 1230 && pulsewidth <= 1360) return 1;
@ -46,7 +46,7 @@ static uint8_t readSwitch(void){
return 0; return 0;
} }
static void reset_control_switch() void Rover::reset_control_switch()
{ {
oldSwitchPosition = 0; oldSwitchPosition = 0;
read_control_switch(); read_control_switch();
@ -56,7 +56,7 @@ static void reset_control_switch()
// read at 10 hz // read at 10 hz
// set this to your trainer switch // set this to your trainer switch
static void read_trim_switch() void Rover::read_trim_switch()
{ {
switch ((enum ch7_option)g.ch7_option.get()) { switch ((enum ch7_option)g.ch7_option.get()) {
case CH7_DO_NOTHING: case CH7_DO_NOTHING:

View File

@ -1,7 +1,7 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static void update_events(void) void Rover::update_events(void)
{ {
ServoRelayEvents.update_events(); ServoRelayEvents.update_events();
} }

View File

@ -13,11 +13,11 @@
this failsafe_check function is called from the core timer interrupt this failsafe_check function is called from the core timer interrupt
at 1kHz. at 1kHz.
*/ */
static void failsafe_check() void Rover::failsafe_check()
{ {
static uint16_t last_mainLoop_count; static uint16_t last_mainLoop_count;
static uint32_t last_timestamp; uint32_t Rover::last_timestamp;
static bool in_failsafe; bool Rover::in_failsafe;
uint32_t tnow = hal.scheduler->micros(); uint32_t tnow = hal.scheduler->micros();
if (mainLoop_count != last_mainLoop_count) { if (mainLoop_count != last_mainLoop_count) {

View File

@ -3,7 +3,7 @@
//**************************************************************** //****************************************************************
// Function that will calculate the desired direction to fly and distance // Function that will calculate the desired direction to fly and distance
//**************************************************************** //****************************************************************
static void navigate() void Rover::navigate()
{ {
// do not navigate with corrupt data // do not navigate with corrupt data
// --------------------------------- // ---------------------------------

View File

@ -3,7 +3,7 @@
/* /*
allow for runtime change of control channel ordering allow for runtime change of control channel ordering
*/ */
static void set_control_channels(void) void Rover::set_control_channels(void)
{ {
channel_steer = RC_Channel::rc_channel(rcmap.roll()-1); channel_steer = RC_Channel::rc_channel(rcmap.roll()-1);
channel_throttle = RC_Channel::rc_channel(rcmap.throttle()-1); channel_throttle = RC_Channel::rc_channel(rcmap.throttle()-1);
@ -18,7 +18,7 @@ static void set_control_channels(void)
hal.rcout->set_esc_scaling(channel_throttle->radio_min, channel_throttle->radio_max); hal.rcout->set_esc_scaling(channel_throttle->radio_min, channel_throttle->radio_max);
} }
static void init_rc_in() void Rover::init_rc_in()
{ {
// set rc dead zones // set rc dead zones
channel_steer->set_default_dead_zone(30); channel_steer->set_default_dead_zone(30);
@ -28,7 +28,7 @@ static void init_rc_in()
update_aux(); update_aux();
} }
static void init_rc_out() void Rover::init_rc_out()
{ {
RC_Channel::rc_channel(CH_1)->enable_out(); RC_Channel::rc_channel(CH_1)->enable_out();
RC_Channel::rc_channel(CH_3)->enable_out(); RC_Channel::rc_channel(CH_3)->enable_out();
@ -38,7 +38,7 @@ static void init_rc_out()
RC_Channel::setup_failsafe_trim_all(); RC_Channel::setup_failsafe_trim_all();
} }
static void read_radio() void Rover::read_radio()
{ {
if (!hal.rcin->new_input()) { if (!hal.rcin->new_input()) {
control_failsafe(channel_throttle->radio_in); control_failsafe(channel_throttle->radio_in);
@ -90,7 +90,7 @@ static void read_radio()
} }
} }
static void control_failsafe(uint16_t pwm) void Rover::control_failsafe(uint16_t pwm)
{ {
if (!g.fs_throttle_enabled) { if (!g.fs_throttle_enabled) {
// no throttle failsafe // no throttle failsafe
@ -109,7 +109,7 @@ static void control_failsafe(uint16_t pwm)
} }
} }
static void trim_control_surfaces() void Rover::trim_control_surfaces()
{ {
read_radio(); read_radio();
// Store control surface trim values // Store control surface trim values
@ -121,7 +121,7 @@ static void trim_control_surfaces()
} }
} }
static void trim_radio() void Rover::trim_radio()
{ {
for (int y = 0; y < 30; y++) { for (int y = 0; y < 30; y++) {
read_radio(); read_radio();

View File

@ -1,20 +1,20 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static void init_barometer(void) void Rover::init_barometer(void)
{ {
gcs_send_text_P(SEVERITY_LOW, PSTR("Calibrating barometer")); gcs_send_text_P(SEVERITY_LOW, PSTR("Calibrating barometer"));
barometer.calibrate(); barometer.calibrate();
gcs_send_text_P(SEVERITY_LOW, PSTR("barometer calibration complete")); gcs_send_text_P(SEVERITY_LOW, PSTR("barometer calibration complete"));
} }
static void init_sonar(void) void Rover::init_sonar(void)
{ {
sonar.init(); sonar.init();
} }
// read_battery - reads battery voltage and current and invokes failsafe // read_battery - reads battery voltage and current and invokes failsafe
// should be called at 10hz // should be called at 10hz
static void read_battery(void) void Rover::read_battery(void)
{ {
battery.read(); battery.read();
} }
@ -29,7 +29,7 @@ void read_receiver_rssi(void)
} }
// read the sonars // read the sonars
static void read_sonars(void) void Rover::read_sonars(void)
{ {
sonar.update(); sonar.update();

View File

@ -8,8 +8,8 @@ static int8_t setup_show (uint8_t argc, const Menu::arg *argv);
static int8_t setup_factory (uint8_t argc, const Menu::arg *argv); static int8_t setup_factory (uint8_t argc, const Menu::arg *argv);
static int8_t setup_flightmodes (uint8_t argc, const Menu::arg *argv); static int8_t setup_flightmodes (uint8_t argc, const Menu::arg *argv);
#if !defined( __AVR_ATmega1280__ ) #if !defined( __AVR_ATmega1280__ )
static int8_t setup_accel_scale (uint8_t argc, const Menu::arg *argv); int8_t Rover:: setup_accel_scale (uint8_t argc, const Menu::arg *argv);
static int8_t setup_set (uint8_t argc, const Menu::arg *argv); int8_t Rover:: setup_set (uint8_t argc, const Menu::arg *argv);
#endif #endif
static int8_t setup_erase (uint8_t argc, const Menu::arg *argv); static int8_t setup_erase (uint8_t argc, const Menu::arg *argv);
static int8_t setup_compass (uint8_t argc, const Menu::arg *argv); static int8_t setup_compass (uint8_t argc, const Menu::arg *argv);
@ -122,7 +122,7 @@ setup_show(uint8_t argc, const Menu::arg *argv)
//Set a parameter to a specified value. It will cast the value to the current type of the //Set a parameter to a specified value. It will cast the value to the current type of the
//parameter and make sure it fits in case of INT8 and INT16 //parameter and make sure it fits in case of INT8 and INT16
static int8_t setup_set(uint8_t argc, const Menu::arg *argv) int8_t Rover::setup_set(uint8_t argc, const Menu::arg *argv)
{ {
int8_t value_int8; int8_t value_int8;
int16_t value_int16; int16_t value_int16;
@ -446,7 +446,7 @@ setup_compass(uint8_t argc, const Menu::arg *argv)
// CLI reports // CLI reports
/***************************************************************************/ /***************************************************************************/
static void report_batt_monitor() void Rover::report_batt_monitor()
{ {
//print_blanks(2); //print_blanks(2);
cliSerial->printf_P(PSTR("Batt Mointor\n")); cliSerial->printf_P(PSTR("Batt Mointor\n"));
@ -460,7 +460,7 @@ static void report_batt_monitor()
} }
print_blanks(2); print_blanks(2);
} }
static void report_radio() void Rover::report_radio()
{ {
//print_blanks(2); //print_blanks(2);
cliSerial->printf_P(PSTR("Radio\n")); cliSerial->printf_P(PSTR("Radio\n"));
@ -470,7 +470,7 @@ static void report_radio()
print_blanks(2); print_blanks(2);
} }
static void report_gains() void Rover::report_gains()
{ {
//print_blanks(2); //print_blanks(2);
cliSerial->printf_P(PSTR("Gains\n")); cliSerial->printf_P(PSTR("Gains\n"));
@ -482,7 +482,7 @@ static void report_gains()
print_blanks(2); print_blanks(2);
} }
static void report_throttle() void Rover::report_throttle()
{ {
//print_blanks(2); //print_blanks(2);
cliSerial->printf_P(PSTR("Throttle\n")); cliSerial->printf_P(PSTR("Throttle\n"));
@ -501,7 +501,7 @@ static void report_throttle()
print_blanks(2); print_blanks(2);
} }
static void report_compass() void Rover::report_compass()
{ {
//print_blanks(2); //print_blanks(2);
cliSerial->printf_P(PSTR("Compass: ")); cliSerial->printf_P(PSTR("Compass: "));
@ -522,7 +522,7 @@ static void report_compass()
print_blanks(2); print_blanks(2);
} }
static void report_modes() void Rover::report_modes()
{ {
//print_blanks(2); //print_blanks(2);
cliSerial->printf_P(PSTR("Flight modes\n")); cliSerial->printf_P(PSTR("Flight modes\n"));
@ -597,7 +597,7 @@ print_divider(void)
static int8_t static int8_t
radio_input_switch(void) radio_input_switch(void)
{ {
static int8_t bouncer = 0; int8_t Rover::bouncer = 0;
if (int16_t(channel_steer->radio_in - channel_steer->radio_trim) > 100) { if (int16_t(channel_steer->radio_in - channel_steer->radio_trim) > 100) {
@ -621,14 +621,14 @@ radio_input_switch(void)
} }
static void zero_eeprom(void) void Rover::zero_eeprom(void)
{ {
cliSerial->printf_P(PSTR("\nErasing EEPROM\n")); cliSerial->printf_P(PSTR("\nErasing EEPROM\n"));
StorageManager::erase(); StorageManager::erase();
cliSerial->printf_P(PSTR("done\n")); cliSerial->printf_P(PSTR("done\n"));
} }
static void print_enabled(bool b) void Rover::print_enabled(bool b)
{ {
if(b) if(b)
cliSerial->printf_P(PSTR("en")); cliSerial->printf_P(PSTR("en"));

View File

@ -12,7 +12,7 @@ The init_ardupilot function processes everything we need for an in - air restart
static int8_t process_logs(uint8_t argc, const Menu::arg *argv); // in Log.pde static int8_t process_logs(uint8_t argc, const Menu::arg *argv); // in Log.pde
static int8_t setup_mode(uint8_t argc, const Menu::arg *argv); // in setup.pde static int8_t setup_mode(uint8_t argc, const Menu::arg *argv); // in setup.pde
static int8_t test_mode(uint8_t argc, const Menu::arg *argv); // in test.cpp static int8_t test_mode(uint8_t argc, const Menu::arg *argv); // in test.cpp
static int8_t reboot_board(uint8_t argc, const Menu::arg *argv); int8_t Rover:: reboot_board(uint8_t argc, const Menu::arg *argv);
// This is the help function // This is the help function
// PSTR is an AVR macro to read strings from flash memory // PSTR is an AVR macro to read strings from flash memory
@ -43,14 +43,14 @@ static const struct Menu::command main_menu_commands[] PROGMEM = {
// Create the top-level menu object. // Create the top-level menu object.
MENU(main_menu, THISFIRMWARE, main_menu_commands); MENU(main_menu, THISFIRMWARE, main_menu_commands);
static int8_t reboot_board(uint8_t argc, const Menu::arg *argv) int8_t Rover::reboot_board(uint8_t argc, const Menu::arg *argv)
{ {
hal.scheduler->reboot(false); hal.scheduler->reboot(false);
return 0; return 0;
} }
// the user wants the CLI. It never exits // the user wants the CLI. It never exits
static void run_cli(AP_HAL::UARTDriver *port) void Rover::run_cli(AP_HAL::UARTDriver *port)
{ {
// disable the failsafe code in the CLI // disable the failsafe code in the CLI
hal.scheduler->register_timer_failsafe(NULL,1); hal.scheduler->register_timer_failsafe(NULL,1);
@ -69,7 +69,7 @@ static void run_cli(AP_HAL::UARTDriver *port)
#endif // CLI_ENABLED #endif // CLI_ENABLED
static void init_ardupilot() void Rover::init_ardupilot()
{ {
// initialise console serial port // initialise console serial port
serial_manager.init_console(); serial_manager.init_console();
@ -225,7 +225,7 @@ static void init_ardupilot()
//******************************************************************************** //********************************************************************************
//This function does all the calibrations, etc. that we need during a ground start //This function does all the calibrations, etc. that we need during a ground start
//******************************************************************************** //********************************************************************************
static void startup_ground(void) void Rover::startup_ground(void)
{ {
set_mode(INITIALISING); set_mode(INITIALISING);
@ -263,7 +263,7 @@ static void startup_ground(void)
set the in_reverse flag set the in_reverse flag
reset the throttle integrator if this changes in_reverse reset the throttle integrator if this changes in_reverse
*/ */
static void set_reverse(bool reverse) void Rover::set_reverse(bool reverse)
{ {
if (in_reverse == reverse) { if (in_reverse == reverse) {
return; return;
@ -272,7 +272,7 @@ static void set_reverse(bool reverse)
in_reverse = reverse; in_reverse = reverse;
} }
static void set_mode(enum mode mode) void Rover::set_mode(enum mode mode)
{ {
if(control_mode == mode){ if(control_mode == mode){
@ -324,7 +324,7 @@ static void set_mode(enum mode mode)
/* /*
set_mode() wrapper for MAVLink SET_MODE set_mode() wrapper for MAVLink SET_MODE
*/ */
static bool mavlink_set_mode(uint8_t mode) bool Rover::mavlink_set_mode(uint8_t mode)
{ {
switch (mode) { switch (mode) {
case MANUAL: case MANUAL:
@ -342,7 +342,7 @@ static bool mavlink_set_mode(uint8_t mode)
/* /*
called to set/unset a failsafe event. called to set/unset a failsafe event.
*/ */
static void failsafe_trigger(uint8_t failsafe_type, bool on) void Rover::failsafe_trigger(uint8_t failsafe_type, bool on)
{ {
uint8_t old_bits = failsafe.bits; uint8_t old_bits = failsafe.bits;
if (on) { if (on) {
@ -381,7 +381,7 @@ static void failsafe_trigger(uint8_t failsafe_type, bool on)
} }
} }
static void startup_INS_ground(void) void Rover::startup_INS_ground(void)
{ {
gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Warming up ADC...")); gcs_send_text_P(SEVERITY_MEDIUM, PSTR("Warming up ADC..."));
mavlink_delay(500); mavlink_delay(500);
@ -409,19 +409,19 @@ static void startup_INS_ground(void)
// updates the notify state // updates the notify state
// should be called at 50hz // should be called at 50hz
static void update_notify() void Rover::update_notify()
{ {
notify.update(); notify.update();
} }
static void resetPerfData(void) { void Rover::resetPerfData(void) {
mainLoop_count = 0; mainLoop_count = 0;
G_Dt_max = 0; G_Dt_max = 0;
perf_mon_timer = millis(); perf_mon_timer = millis();
} }
static void check_usb_mux(void) void Rover::check_usb_mux(void)
{ {
bool usb_check = hal.gpio->usb_connected(); bool usb_check = hal.gpio->usb_connected();
if (usb_check == usb_connected) { if (usb_check == usb_connected) {
@ -476,7 +476,7 @@ print_mode(AP_HAL::BetterStream *port, uint8_t mode)
/* /*
check a digitial pin for high,low (1/0) check a digitial pin for high,low (1/0)
*/ */
static uint8_t check_digital_pin(uint8_t pin) uint8_t Rover::check_digital_pin(uint8_t pin)
{ {
int8_t dpin = hal.gpio->analogPinToDigitalPin(pin); int8_t dpin = hal.gpio->analogPinToDigitalPin(pin);
if (dpin == -1) { if (dpin == -1) {
@ -494,7 +494,7 @@ static uint8_t check_digital_pin(uint8_t pin)
/* /*
should we log a message type now? should we log a message type now?
*/ */
static bool should_log(uint32_t mask) bool Rover::should_log(uint32_t mask)
{ {
if (!(mask & g.log_bitmask) || in_mavlink_delay) { if (!(mask & g.log_bitmask) || in_mavlink_delay) {
return false; return false;
@ -514,7 +514,7 @@ static bool should_log(uint32_t mask)
send FrSky telemetry. Should be called at 5Hz by scheduler send FrSky telemetry. Should be called at 5Hz by scheduler
*/ */
#if FRSKY_TELEM_ENABLED == ENABLED #if FRSKY_TELEM_ENABLED == ENABLED
static void frsky_telemetry_send(void) void Rover::frsky_telemetry_send(void)
{ {
frsky_telemetry.send_frames((uint8_t)control_mode); frsky_telemetry.send_frames((uint8_t)control_mode);
} }

View File

@ -17,11 +17,11 @@ static int8_t test_mag(uint8_t argc, const Menu::arg *argv);
static int8_t test_modeswitch(uint8_t argc, const Menu::arg *argv); static int8_t test_modeswitch(uint8_t argc, const Menu::arg *argv);
static int8_t test_logging(uint8_t argc, const Menu::arg *argv); static int8_t test_logging(uint8_t argc, const Menu::arg *argv);
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
static int8_t test_shell(uint8_t argc, const Menu::arg *argv); int8_t Rover:: test_shell(uint8_t argc, const Menu::arg *argv);
#endif #endif
// forward declaration to keep the compiler happy // forward declaration to keep the compiler happy
static void test_wp_print(const AP_Mission::Mission_Command& cmd); void Rover::test_wp_print(const AP_Mission::Mission_Command& cmd);
// Creates a constant array of structs representing menu options // Creates a constant array of structs representing menu options
// and stores them in Flash memory, not RAM. // and stores them in Flash memory, not RAM.
@ -59,7 +59,7 @@ test_mode(uint8_t argc, const Menu::arg *argv)
return 0; return 0;
} }
static void print_hit_enter() void Rover::print_hit_enter()
{ {
cliSerial->printf_P(PSTR("Hit Enter to exit.\n\n")); cliSerial->printf_P(PSTR("Hit Enter to exit.\n\n"));
} }