mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_HAL_SITL: use method for downcast
Instead of just doing a static cast to the desired class, use a method named "from". Pros: - When we have data shared on the parent class, the code is cleaner in child class when it needs to access this data. Almost all the data we use in AP_HAL benefits from this - There's a minimal type checking because now we are using a method that can only receive the type of the parent class
This commit is contained in:
parent
6c19f741df
commit
0ed7f94bfc
@ -524,7 +524,7 @@ void SITL_State::init(int argc, char * const argv[])
|
||||
pwm_input[4] = pwm_input[7] = 1800;
|
||||
pwm_input[2] = pwm_input[5] = pwm_input[6] = 1000;
|
||||
|
||||
_scheduler = (SITLScheduler *)hal.scheduler;
|
||||
_scheduler = SITLScheduler::from(hal.scheduler);
|
||||
_parse_command_line(argc, argv);
|
||||
}
|
||||
|
||||
|
@ -13,6 +13,10 @@
|
||||
class HALSITL::SITLScheduler : public AP_HAL::Scheduler {
|
||||
public:
|
||||
SITLScheduler(SITL_State *sitlState);
|
||||
static SITLScheduler *from(AP_HAL::Scheduler *scheduler) {
|
||||
return static_cast<SITLScheduler*>(scheduler);
|
||||
}
|
||||
|
||||
/* AP_HAL::Scheduler methods */
|
||||
|
||||
void init(void *unused);
|
||||
|
Loading…
Reference in New Issue
Block a user