mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
HAL_PX4: updates for upstream merge
This commit is contained in:
parent
57cef63b94
commit
333778bac1
@ -231,12 +231,12 @@ void HAL_PX4::init(int argc, char * const argv[]) const
|
||||
SKETCHNAME, deviceA, deviceC, deviceD, deviceE);
|
||||
|
||||
_px4_thread_should_exit = false;
|
||||
daemon_task = task_spawn_cmd(SKETCHNAME,
|
||||
SCHED_FIFO,
|
||||
APM_MAIN_PRIORITY,
|
||||
APM_MAIN_THREAD_STACK_SIZE,
|
||||
main_loop,
|
||||
NULL);
|
||||
daemon_task = px4_task_spawn_cmd(SKETCHNAME,
|
||||
SCHED_FIFO,
|
||||
APM_MAIN_PRIORITY,
|
||||
APM_MAIN_THREAD_STACK_SIZE,
|
||||
main_loop,
|
||||
NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
@ -59,10 +59,10 @@ void PX4RCOutput::init(void* unused)
|
||||
}
|
||||
|
||||
// publish actuator vaules on demand
|
||||
_actuator_direct_pub = -1;
|
||||
_actuator_direct_pub = NULL;
|
||||
|
||||
// and armed state
|
||||
_actuator_armed_pub = -1;
|
||||
_actuator_armed_pub = NULL;
|
||||
}
|
||||
|
||||
|
||||
@ -280,7 +280,7 @@ void PX4RCOutput::_arm_actuators(bool arm)
|
||||
_armed.lockdown = false;
|
||||
_armed.force_failsafe = false;
|
||||
|
||||
if (_actuator_armed_pub == -1) {
|
||||
if (_actuator_armed_pub == NULL) {
|
||||
_actuator_armed_pub = orb_advertise(ORB_ID(actuator_armed), &_armed);
|
||||
} else {
|
||||
orb_publish(ORB_ID(actuator_armed), _actuator_armed_pub, &_armed);
|
||||
@ -295,8 +295,8 @@ void PX4RCOutput::_publish_actuators(void)
|
||||
struct actuator_direct_s actuators;
|
||||
|
||||
actuators.nvalues = _max_channel;
|
||||
if (actuators.nvalues > NUM_ACTUATORS_DIRECT) {
|
||||
actuators.nvalues = NUM_ACTUATORS_DIRECT;
|
||||
if (actuators.nvalues > actuators.NUM_ACTUATORS_DIRECT) {
|
||||
actuators.nvalues = actuators.NUM_ACTUATORS_DIRECT;
|
||||
}
|
||||
// don't publish more than 8 actuators for now, as the uavcan ESC
|
||||
// driver refuses to update any motors if you try to publish more
|
||||
@ -311,7 +311,7 @@ void PX4RCOutput::_publish_actuators(void)
|
||||
actuators.values[i] = actuators.values[i]*2 - 1;
|
||||
}
|
||||
|
||||
if (_actuator_direct_pub == -1) {
|
||||
if (_actuator_direct_pub == NULL) {
|
||||
_actuator_direct_pub = orb_advertise(ORB_ID(actuator_direct), &actuators);
|
||||
} else {
|
||||
orb_publish(ORB_ID(actuator_direct), _actuator_direct_pub, &actuators);
|
||||
|
@ -49,8 +49,8 @@ private:
|
||||
actuator_outputs_s _outputs;
|
||||
actuator_armed_s _armed;
|
||||
|
||||
int _actuator_direct_pub = -1;
|
||||
int _actuator_armed_pub = -1;
|
||||
orb_advert_t _actuator_direct_pub = NULL;
|
||||
orb_advert_t _actuator_armed_pub = NULL;
|
||||
uint16_t _esc_pwm_min = 1000;
|
||||
uint16_t _esc_pwm_max = 2000;
|
||||
|
||||
|
@ -242,7 +242,7 @@ void PX4Scheduler::resume_timer_procs()
|
||||
|
||||
void PX4Scheduler::reboot(bool hold_in_bootloader)
|
||||
{
|
||||
systemreset(hold_in_bootloader);
|
||||
px4_systemreset(hold_in_bootloader);
|
||||
}
|
||||
|
||||
void PX4Scheduler::_run_timers(bool called_from_timer_thread)
|
||||
|
Loading…
Reference in New Issue
Block a user