mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-28 05:44:07 +08:00
Merge remote-tracking branch 'upstream/master' into obcfailsafe
This commit is contained in:
commit
ca44efab7c
@ -1969,7 +1969,7 @@ PX4IO::print_status(bool extended_status)
|
||||
printf("actuators");
|
||||
|
||||
for (unsigned i = 0; i < _max_actuators; i++)
|
||||
printf(" %u", io_reg_get(PX4IO_PAGE_ACTUATORS, i));
|
||||
printf(" %hi", int16_t(io_reg_get(PX4IO_PAGE_ACTUATORS, i)));
|
||||
|
||||
printf("\n");
|
||||
printf("servos");
|
||||
|
||||
@ -134,44 +134,44 @@ Mavlink::Mavlink() :
|
||||
_mode(MAVLINK_MODE_NORMAL),
|
||||
_channel(MAVLINK_COMM_0),
|
||||
_logbuffer {},
|
||||
_total_counter(0),
|
||||
_receive_thread {},
|
||||
_verbose(false),
|
||||
_forwarding_on(false),
|
||||
_passing_on(false),
|
||||
_ftp_on(false),
|
||||
_uart_fd(-1),
|
||||
_baudrate(57600),
|
||||
_datarate(1000),
|
||||
_datarate_events(500),
|
||||
_rate_mult(1.0f),
|
||||
_mavlink_param_queue_index(0),
|
||||
mavlink_link_termination_allowed(false),
|
||||
_subscribe_to_stream(nullptr),
|
||||
_subscribe_to_stream_rate(0.0f),
|
||||
_flow_control_enabled(true),
|
||||
_last_write_success_time(0),
|
||||
_last_write_try_time(0),
|
||||
_bytes_tx(0),
|
||||
_bytes_txerr(0),
|
||||
_bytes_rx(0),
|
||||
_bytes_timestamp(0),
|
||||
_rate_tx(0.0f),
|
||||
_rate_txerr(0.0f),
|
||||
_rate_rx(0.0f),
|
||||
_rstatus {},
|
||||
_message_buffer {},
|
||||
_message_buffer_mutex {},
|
||||
_send_mutex {},
|
||||
_param_initialized(false),
|
||||
_param_system_id(0),
|
||||
_param_component_id(0),
|
||||
_param_system_type(0),
|
||||
_param_use_hil_gps(0),
|
||||
_total_counter(0),
|
||||
_receive_thread {},
|
||||
_verbose(false),
|
||||
_forwarding_on(false),
|
||||
_passing_on(false),
|
||||
_ftp_on(false),
|
||||
_uart_fd(-1),
|
||||
_baudrate(57600),
|
||||
_datarate(1000),
|
||||
_datarate_events(500),
|
||||
_rate_mult(1.0f),
|
||||
_mavlink_param_queue_index(0),
|
||||
mavlink_link_termination_allowed(false),
|
||||
_subscribe_to_stream(nullptr),
|
||||
_subscribe_to_stream_rate(0.0f),
|
||||
_flow_control_enabled(true),
|
||||
_last_write_success_time(0),
|
||||
_last_write_try_time(0),
|
||||
_bytes_tx(0),
|
||||
_bytes_txerr(0),
|
||||
_bytes_rx(0),
|
||||
_bytes_timestamp(0),
|
||||
_rate_tx(0.0f),
|
||||
_rate_txerr(0.0f),
|
||||
_rate_rx(0.0f),
|
||||
_rstatus {},
|
||||
_message_buffer {},
|
||||
_message_buffer_mutex {},
|
||||
_send_mutex {},
|
||||
_param_initialized(false),
|
||||
_param_system_id(0),
|
||||
_param_component_id(0),
|
||||
_param_system_type(0),
|
||||
_param_use_hil_gps(0),
|
||||
|
||||
/* performance counters */
|
||||
_loop_perf(perf_alloc(PC_ELAPSED, "mavlink_el")),
|
||||
_txerr_perf(perf_alloc(PC_COUNT, "mavlink_txe"))
|
||||
/* performance counters */
|
||||
_loop_perf(perf_alloc(PC_ELAPSED, "mavlink_el")),
|
||||
_txerr_perf(perf_alloc(PC_COUNT, "mavlink_txe"))
|
||||
{
|
||||
fops.ioctl = (int (*)(file *, int, long unsigned int))&mavlink_dev_ioctl;
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user