mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Fixed some sitl init bugs.
This commit is contained in:
parent
2ffd0cd61f
commit
ca5a2d1fca
@ -1250,7 +1250,7 @@ Sensors::vehicle_control_mode_poll()
|
||||
void
|
||||
Sensors::parameter_update_poll(bool forced)
|
||||
{
|
||||
bool param_updated;
|
||||
bool param_updated=false;
|
||||
|
||||
/* Check if any parameter has changed */
|
||||
orb_check(_params_sub, ¶m_updated);
|
||||
|
||||
@ -463,10 +463,12 @@ void Simulator::pollForMAVLinkMessages(bool publish)
|
||||
char serial_buf[1024];
|
||||
|
||||
struct pollfd fds[2];
|
||||
memset(fds, 0, sizeof(fds));
|
||||
unsigned fd_count = 1;
|
||||
fds[0].fd = _fd;
|
||||
fds[0].events = POLLIN;
|
||||
|
||||
|
||||
if (serial_fd >= 0) {
|
||||
fds[1].fd = serial_fd;
|
||||
fds[1].events = POLLIN;
|
||||
|
||||
@ -111,6 +111,7 @@ private:
|
||||
|
||||
ADCSIM::ADCSIM(uint32_t channels) :
|
||||
VDev("adcsim", ADCSIM0_DEVICE_PATH),
|
||||
_call(),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "adc_samples")),
|
||||
_channel_count(0),
|
||||
_samples(nullptr)
|
||||
|
||||
@ -81,9 +81,7 @@ typedef struct {
|
||||
|
||||
static void *entry_adapter(void *ptr)
|
||||
{
|
||||
pthdata_t *data;
|
||||
data = (pthdata_t *) ptr;
|
||||
|
||||
pthdata_t *data = (pthdata_t *) ptr;
|
||||
data->entry(data->argc, data->argv);
|
||||
free(ptr);
|
||||
PX4_DEBUG("Before px4_task_exit");
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user