mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 11:59:17 +08:00
advertise esc_status where is publishes
- esc_status is an optional logging topic resulting in it not being logged if it doesn't get advertise -> Add advertise where applicable
This commit is contained in:
@@ -75,6 +75,8 @@ ModalIo::ModalIo() :
|
|||||||
_esc_status.esc[i].esc_power = 0;
|
_esc_status.esc[i].esc_power = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
_esc_status_pub.advertise();
|
||||||
|
|
||||||
qc_esc_packet_init(&_fb_packet);
|
qc_esc_packet_init(&_fb_packet);
|
||||||
qc_esc_packet_init(&_uart_bridge_packet);
|
qc_esc_packet_init(&_uart_bridge_packet);
|
||||||
|
|
||||||
|
|||||||
@@ -65,6 +65,8 @@ int TAP_ESC::init()
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
_esc_feedback_pub.advertise();
|
||||||
|
|
||||||
/* Respect boot time required by the ESC FW */
|
/* Respect boot time required by the ESC FW */
|
||||||
hrt_abstime uptime_us = hrt_absolute_time();
|
hrt_abstime uptime_us = hrt_absolute_time();
|
||||||
|
|
||||||
|
|||||||
@@ -64,6 +64,8 @@ UavcanEscController::init()
|
|||||||
return res;
|
return res;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
_esc_status_pub.advertise();
|
||||||
|
|
||||||
return res;
|
return res;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -53,6 +53,8 @@ bool GZMixingInterfaceESC::init(const std::string &model_name)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
_esc_status_pub.advertise();
|
||||||
|
|
||||||
ScheduleNow();
|
ScheduleNow();
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
|
|||||||
@@ -96,6 +96,8 @@ SimulatorMavlink::SimulatorMavlink() :
|
|||||||
snprintf(param_name, sizeof(param_name), "%s_%s%d", "PWM_MAIN", "FUNC", i + 1);
|
snprintf(param_name, sizeof(param_name), "%s_%s%d", "PWM_MAIN", "FUNC", i + 1);
|
||||||
param_get(param_find(param_name), &_output_functions[i]);
|
param_get(param_find(param_name), &_output_functions[i]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
_esc_status_pub.advertise();
|
||||||
}
|
}
|
||||||
|
|
||||||
void SimulatorMavlink::parameters_update(bool force)
|
void SimulatorMavlink::parameters_update(bool force)
|
||||||
|
|||||||
Reference in New Issue
Block a user