forked from Archive/PX4-Autopilot
commit
2341d56927
|
@ -1183,8 +1183,7 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg)
|
|||
tstatus.heartbeat_time = tstatus.timestamp;
|
||||
|
||||
if (_telemetry_status_pub == nullptr) {
|
||||
int multi_instance;
|
||||
_telemetry_status_pub = orb_advertise_multi(ORB_ID(telemetry_status), &tstatus, &multi_instance, ORB_PRIO_HIGH);
|
||||
_telemetry_status_pub = orb_advertise_multi(ORB_ID(telemetry_status), &tstatus, NULL, ORB_PRIO_HIGH);
|
||||
|
||||
} else {
|
||||
orb_publish(ORB_ID(telemetry_status), _telemetry_status_pub, &tstatus);
|
||||
|
@ -1837,10 +1836,12 @@ MavlinkReceiver::receive_thread(void *arg)
|
|||
}
|
||||
}
|
||||
|
||||
/* count received bytes */
|
||||
/* count received bytes (nread will be -1 on read error) */
|
||||
if (nread > 0) {
|
||||
_mavlink->count_rxbytes(nread);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
|
|
@ -380,6 +380,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
|||
orb_advert_t vehicle_global_position_pub = NULL;
|
||||
|
||||
struct position_estimator_inav_params params;
|
||||
memset(¶ms, 0, sizeof(params));
|
||||
struct position_estimator_inav_param_handles pos_inav_param_handles;
|
||||
/* initialize parameter handles */
|
||||
inav_parameters_init(&pos_inav_param_handles);
|
||||
|
|
|
@ -542,6 +542,7 @@ Sensors::Sensors() :
|
|||
|
||||
memset(&_rc, 0, sizeof(_rc));
|
||||
memset(&_diff_pres, 0, sizeof(_diff_pres));
|
||||
memset(&_parameters, 0, sizeof(_parameters));
|
||||
memset(&_rc_parameter_map, 0, sizeof(_rc_parameter_map));
|
||||
|
||||
/* basic r/c parameters */
|
||||
|
|
Loading…
Reference in New Issue