mirror of https://github.com/ArduPilot/ardupilot
Rover: move contents of Rover.cpp to APMrover2.cpp
This commit is contained in:
parent
ef8baf28ad
commit
43719d5e5d
|
@ -31,9 +31,11 @@
|
|||
|
||||
#include "Rover.h"
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
#define FORCE_VERSION_H_INCLUDE
|
||||
#include "version.h"
|
||||
#undef FORCE_VERSION_H_INCLUDE
|
||||
|
||||
Rover rover;
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
#define SCHED_TASK(func, _interval_ticks, _max_time_micros) SCHED_TASK_CLASS(Rover, &rover, func, _interval_ticks, _max_time_micros)
|
||||
|
||||
|
@ -107,6 +109,18 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
|||
|
||||
constexpr int8_t Rover::_failsafe_priorities[7];
|
||||
|
||||
Rover::Rover(void) :
|
||||
param_loader(var_info),
|
||||
channel_steer(nullptr),
|
||||
channel_throttle(nullptr),
|
||||
channel_lateral(nullptr),
|
||||
logger{g.log_bitmask},
|
||||
modes(&g.mode1),
|
||||
control_mode(&mode_initializing),
|
||||
G_Dt(0.02f)
|
||||
{
|
||||
}
|
||||
|
||||
#if STATS_ENABLED == ENABLED
|
||||
/*
|
||||
update AP_Stats
|
||||
|
@ -319,4 +333,6 @@ void Rover::update_mission(void)
|
|||
}
|
||||
}
|
||||
|
||||
Rover rover;
|
||||
|
||||
AP_HAL_MAIN_CALLBACKS(&rover);
|
||||
|
|
|
@ -1,35 +0,0 @@
|
|||
/*
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/*
|
||||
main Rover class, containing all vehicle specific state
|
||||
*/
|
||||
|
||||
#include "Rover.h"
|
||||
|
||||
#define FORCE_VERSION_H_INCLUDE
|
||||
#include "version.h"
|
||||
#undef FORCE_VERSION_H_INCLUDE
|
||||
|
||||
Rover::Rover(void) :
|
||||
param_loader(var_info),
|
||||
channel_steer(nullptr),
|
||||
channel_throttle(nullptr),
|
||||
channel_lateral(nullptr),
|
||||
logger{g.log_bitmask},
|
||||
modes(&g.mode1),
|
||||
control_mode(&mode_initializing),
|
||||
G_Dt(0.02f)
|
||||
{
|
||||
}
|
Loading…
Reference in New Issue