mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-28 00:14:08 +08:00
Merge remote-tracking branch 'upstream/master' into new_state_machine
This commit is contained in:
commit
f0d8ce009e
12
Debug/NuttX
12
Debug/NuttX
@ -174,11 +174,15 @@ end
|
||||
define showtaskstack
|
||||
set $task = (struct _TCB *)$arg0
|
||||
|
||||
set $stack_free = 0
|
||||
while ($stack_free < $task->adj_stack_size) && *(uint8_t *)($task->stack_alloc_ptr + $stack_free)
|
||||
set $stack_free = $stack_free + 1
|
||||
if $task == &g_idletcb
|
||||
printf "can't measure idle stack\n"
|
||||
else
|
||||
set $stack_free = 0
|
||||
while ($stack_free < $task->adj_stack_size) && *(uint8_t *)($task->stack_alloc_ptr + $stack_free)
|
||||
set $stack_free = $stack_free + 1
|
||||
end
|
||||
printf" stack 0x%08x-0x%08x (%d) %d free\n", $task->stack_alloc_ptr, $task->adj_stack_ptr, $task->adj_stack_size, $stack_free
|
||||
end
|
||||
printf" stack 0x%08x-0x%08x (%d) %d free\n", $task->stack_alloc_ptr, $task->adj_stack_ptr, $task->adj_stack_size, $stack_free
|
||||
end
|
||||
|
||||
#
|
||||
|
||||
@ -22,7 +22,7 @@ end
|
||||
|
||||
define _perf_print
|
||||
set $hdr = (struct perf_ctr_header *)$arg0
|
||||
printf "%p\n", $hdr
|
||||
#printf "%p\n", $hdr
|
||||
printf "%s: ", $hdr->name
|
||||
# PC_COUNT
|
||||
if $hdr->type == 0
|
||||
|
||||
42
apps/examples/px4_mavlink_debug/Makefile
Normal file
42
apps/examples/px4_mavlink_debug/Makefile
Normal file
@ -0,0 +1,42 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Basic example application
|
||||
#
|
||||
|
||||
APPNAME = px4_mavlink_debug
|
||||
PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||
STACKSIZE = 2048
|
||||
|
||||
include $(APPDIR)/mk/app.mk
|
||||
74
apps/examples/px4_mavlink_debug/px4_mavlink_debug.c
Normal file
74
apps/examples/px4_mavlink_debug/px4_mavlink_debug.c
Normal file
@ -0,0 +1,74 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: @author Example User <mail@example.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file px4_mavlink_debug.c
|
||||
* Debug application example for PX4 autopilot
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <poll.h>
|
||||
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/debug_key_value.h>
|
||||
|
||||
__EXPORT int px4_mavlink_debug_main(int argc, char *argv[]);
|
||||
|
||||
int px4_mavlink_debug_main(int argc, char *argv[])
|
||||
{
|
||||
printf("Hello Debug!\n");
|
||||
|
||||
/* advertise debug value */
|
||||
struct debug_key_value_s dbg = { .key = "velx", .value = 0.0f };
|
||||
orb_advert_t pub_dbg = orb_advertise(ORB_ID(debug_key_value), &dbg);
|
||||
|
||||
int value_counter = 0;
|
||||
|
||||
while (value_counter < 100) {
|
||||
/* send one value */
|
||||
dbg.value = value_counter;
|
||||
orb_publish(ORB_ID(debug_key_value), pub_dbg, &dbg);
|
||||
|
||||
warnx("sent one more value..");
|
||||
|
||||
value_counter++;
|
||||
usleep(500000);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
@ -1,42 +0,0 @@
|
||||
/* List of application requirements, generated during make context. */
|
||||
{ "math_demo", SCHED_PRIORITY_DEFAULT, 8192, math_demo_main },
|
||||
{ "control_demo", SCHED_PRIORITY_DEFAULT, 2048, control_demo_main },
|
||||
{ "kalman_demo", SCHED_PRIORITY_MAX - 30, 2048, kalman_demo_main },
|
||||
{ "reboot", SCHED_PRIORITY_DEFAULT, 2048, reboot_main },
|
||||
{ "perf", SCHED_PRIORITY_DEFAULT, 2048, perf_main },
|
||||
{ "top", SCHED_PRIORITY_DEFAULT - 10, 3000, top_main },
|
||||
{ "boardinfo", SCHED_PRIORITY_DEFAULT, 2048, boardinfo_main },
|
||||
{ "mixer", SCHED_PRIORITY_DEFAULT, 4096, mixer_main },
|
||||
{ "eeprom", SCHED_PRIORITY_DEFAULT, 4096, eeprom_main },
|
||||
{ "param", SCHED_PRIORITY_DEFAULT, 4096, param_main },
|
||||
{ "bl_update", SCHED_PRIORITY_DEFAULT, 4096, bl_update_main },
|
||||
{ "preflight_check", SCHED_PRIORITY_DEFAULT, 2048, preflight_check_main },
|
||||
{ "delay_test", SCHED_PRIORITY_DEFAULT, 2048, delay_test_main },
|
||||
{ "uorb", SCHED_PRIORITY_DEFAULT, 4096, uorb_main },
|
||||
{ "mavlink", SCHED_PRIORITY_DEFAULT, 2048, mavlink_main },
|
||||
{ "mavlink_onboard", SCHED_PRIORITY_DEFAULT, 2048, mavlink_onboard_main },
|
||||
{ "gps", SCHED_PRIORITY_DEFAULT, 2048, gps_main },
|
||||
{ "commander", SCHED_PRIORITY_MAX - 30, 2048, commander_main },
|
||||
{ "sdlog", SCHED_PRIORITY_MAX - 30, 2048, sdlog_main },
|
||||
{ "sensors", SCHED_PRIORITY_MAX-5, 4096, sensors_main },
|
||||
{ "ardrone_interface", SCHED_PRIORITY_MAX - 15, 2048, ardrone_interface_main },
|
||||
{ "multirotor_att_control", SCHED_PRIORITY_MAX - 15, 2048, multirotor_att_control_main },
|
||||
{ "multirotor_pos_control", SCHED_PRIORITY_MAX - 25, 2048, multirotor_pos_control_main },
|
||||
{ "fixedwing_att_control", SCHED_PRIORITY_MAX - 30, 2048, fixedwing_att_control_main },
|
||||
{ "fixedwing_pos_control", SCHED_PRIORITY_MAX - 30, 2048, fixedwing_pos_control_main },
|
||||
{ "position_estimator", SCHED_PRIORITY_DEFAULT, 4096, position_estimator_main },
|
||||
{ "attitude_estimator_ekf", SCHED_PRIORITY_DEFAULT, 2048, attitude_estimator_ekf_main },
|
||||
{ "ms5611", SCHED_PRIORITY_DEFAULT, 2048, ms5611_main },
|
||||
{ "hmc5883", SCHED_PRIORITY_DEFAULT, 4096, hmc5883_main },
|
||||
{ "mpu6000", SCHED_PRIORITY_DEFAULT, 4096, mpu6000_main },
|
||||
{ "bma180", SCHED_PRIORITY_DEFAULT, 2048, bma180_main },
|
||||
{ "l3gd20", SCHED_PRIORITY_DEFAULT, 2048, l3gd20_main },
|
||||
{ "px4io", SCHED_PRIORITY_DEFAULT, 2048, px4io_main },
|
||||
{ "blinkm", SCHED_PRIORITY_DEFAULT, 2048, blinkm_main },
|
||||
{ "tone_alarm", SCHED_PRIORITY_DEFAULT, 2048, tone_alarm_main },
|
||||
{ "adc", SCHED_PRIORITY_DEFAULT, 2048, adc_main },
|
||||
{ "fmu", SCHED_PRIORITY_DEFAULT, 2048, fmu_main },
|
||||
{ "hil", SCHED_PRIORITY_DEFAULT, 2048, hil_main },
|
||||
{ "tests", SCHED_PRIORITY_DEFAULT, 12000, tests_main },
|
||||
{ "sercon", SCHED_PRIORITY_DEFAULT, 2048, sercon_main },
|
||||
{ "serdis", SCHED_PRIORITY_DEFAULT, 2048, serdis_main },
|
||||
@ -1,42 +0,0 @@
|
||||
/* List of application entry points, generated during make context. */
|
||||
EXTERN int math_demo_main(int argc, char *argv[]);
|
||||
EXTERN int control_demo_main(int argc, char *argv[]);
|
||||
EXTERN int kalman_demo_main(int argc, char *argv[]);
|
||||
EXTERN int reboot_main(int argc, char *argv[]);
|
||||
EXTERN int perf_main(int argc, char *argv[]);
|
||||
EXTERN int top_main(int argc, char *argv[]);
|
||||
EXTERN int boardinfo_main(int argc, char *argv[]);
|
||||
EXTERN int mixer_main(int argc, char *argv[]);
|
||||
EXTERN int eeprom_main(int argc, char *argv[]);
|
||||
EXTERN int param_main(int argc, char *argv[]);
|
||||
EXTERN int bl_update_main(int argc, char *argv[]);
|
||||
EXTERN int preflight_check_main(int argc, char *argv[]);
|
||||
EXTERN int delay_test_main(int argc, char *argv[]);
|
||||
EXTERN int uorb_main(int argc, char *argv[]);
|
||||
EXTERN int mavlink_main(int argc, char *argv[]);
|
||||
EXTERN int mavlink_onboard_main(int argc, char *argv[]);
|
||||
EXTERN int gps_main(int argc, char *argv[]);
|
||||
EXTERN int commander_main(int argc, char *argv[]);
|
||||
EXTERN int sdlog_main(int argc, char *argv[]);
|
||||
EXTERN int sensors_main(int argc, char *argv[]);
|
||||
EXTERN int ardrone_interface_main(int argc, char *argv[]);
|
||||
EXTERN int multirotor_att_control_main(int argc, char *argv[]);
|
||||
EXTERN int multirotor_pos_control_main(int argc, char *argv[]);
|
||||
EXTERN int fixedwing_att_control_main(int argc, char *argv[]);
|
||||
EXTERN int fixedwing_pos_control_main(int argc, char *argv[]);
|
||||
EXTERN int position_estimator_main(int argc, char *argv[]);
|
||||
EXTERN int attitude_estimator_ekf_main(int argc, char *argv[]);
|
||||
EXTERN int ms5611_main(int argc, char *argv[]);
|
||||
EXTERN int hmc5883_main(int argc, char *argv[]);
|
||||
EXTERN int mpu6000_main(int argc, char *argv[]);
|
||||
EXTERN int bma180_main(int argc, char *argv[]);
|
||||
EXTERN int l3gd20_main(int argc, char *argv[]);
|
||||
EXTERN int px4io_main(int argc, char *argv[]);
|
||||
EXTERN int blinkm_main(int argc, char *argv[]);
|
||||
EXTERN int tone_alarm_main(int argc, char *argv[]);
|
||||
EXTERN int adc_main(int argc, char *argv[]);
|
||||
EXTERN int fmu_main(int argc, char *argv[]);
|
||||
EXTERN int hil_main(int argc, char *argv[]);
|
||||
EXTERN int tests_main(int argc, char *argv[]);
|
||||
EXTERN int sercon_main(int argc, char *argv[]);
|
||||
EXTERN int serdis_main(int argc, char *argv[]);
|
||||
@ -231,6 +231,7 @@ dsm_guess_format(bool reset)
|
||||
0x3f, /* 6 channels (DX6) */
|
||||
0x7f, /* 7 channels (DX7) */
|
||||
0xff, /* 8 channels (DX8) */
|
||||
0x1ff, /* 9 channels (DX9, etc.) */
|
||||
0x3ff, /* 10 channels (DX10) */
|
||||
0x3fff /* 18 channels (DX10) */
|
||||
};
|
||||
|
||||
@ -1049,7 +1049,6 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
|
||||
}
|
||||
|
||||
_last_adc = hrt_absolute_time();
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -126,7 +126,7 @@ static inline int readline_rawgetc(int infd)
|
||||
* error occurs).
|
||||
*/
|
||||
|
||||
do
|
||||
for (;;)
|
||||
{
|
||||
/* Read one character from the incoming stream */
|
||||
|
||||
@ -154,13 +154,21 @@ static inline int readline_rawgetc(int infd)
|
||||
{
|
||||
return -errcode;
|
||||
}
|
||||
|
||||
continue;
|
||||
}
|
||||
|
||||
else if (buffer == '\0')
|
||||
{
|
||||
/* Ignore NUL characters, since they look like EOF to our caller */
|
||||
|
||||
continue;
|
||||
}
|
||||
|
||||
/* Success, return the character that was read */
|
||||
|
||||
return (int)buffer;
|
||||
}
|
||||
while (nread < 1);
|
||||
|
||||
/* On success, return the character that was read */
|
||||
|
||||
return (int)buffer;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
|
||||
@ -79,6 +79,10 @@ CONFIGURED_APPS += systemcmds/delay_test
|
||||
# https://pixhawk.ethz.ch/px4/dev/deamon
|
||||
# CONFIGURED_APPS += examples/px4_deamon_app
|
||||
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/debug_values
|
||||
CONFIGURED_APPS += examples/px4_mavlink_debug
|
||||
|
||||
# Shared object broker; required by many parts of the system.
|
||||
CONFIGURED_APPS += uORB
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user