forked from Archive/PX4-Autopilot
Merge branch 'master' into navigator_rewrite_estimator
This commit is contained in:
commit
f02de30c32
|
@ -37,3 +37,7 @@ then
|
|||
fi
|
||||
|
||||
set MIXER FMU_Q
|
||||
|
||||
# Provide ESC a constant 1000 us pulse
|
||||
set PWM_OUTPUTS 4
|
||||
set PWM_DISARMED 1000
|
||||
|
|
|
@ -197,8 +197,10 @@ public:
|
|||
* Print IO status.
|
||||
*
|
||||
* Print all relevant IO status information
|
||||
*
|
||||
* @param extended_status Shows more verbose information (in particular RC config)
|
||||
*/
|
||||
void print_status();
|
||||
void print_status(bool extended_status);
|
||||
|
||||
/**
|
||||
* Fetch and print debug console output.
|
||||
|
@ -1850,7 +1852,7 @@ PX4IO::mixer_send(const char *buf, unsigned buflen, unsigned retries)
|
|||
}
|
||||
|
||||
void
|
||||
PX4IO::print_status()
|
||||
PX4IO::print_status(bool extended_status)
|
||||
{
|
||||
/* basic configuration */
|
||||
printf("protocol %u hardware %u bootloader %u buffer %uB crc 0x%04x%04x\n",
|
||||
|
@ -2013,19 +2015,21 @@ PX4IO::print_status()
|
|||
printf("\n");
|
||||
}
|
||||
|
||||
for (unsigned i = 0; i < _max_rc_input; i++) {
|
||||
unsigned base = PX4IO_P_RC_CONFIG_STRIDE * i;
|
||||
uint16_t options = io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_OPTIONS);
|
||||
printf("input %u min %u center %u max %u deadzone %u assigned %u options 0x%04x%s%s\n",
|
||||
i,
|
||||
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MIN),
|
||||
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_CENTER),
|
||||
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MAX),
|
||||
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_DEADZONE),
|
||||
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_ASSIGNMENT),
|
||||
options,
|
||||
((options & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) ? " ENABLED" : ""),
|
||||
((options & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE) ? " REVERSED" : ""));
|
||||
if (extended_status) {
|
||||
for (unsigned i = 0; i < _max_rc_input; i++) {
|
||||
unsigned base = PX4IO_P_RC_CONFIG_STRIDE * i;
|
||||
uint16_t options = io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_OPTIONS);
|
||||
printf("input %u min %u center %u max %u deadzone %u assigned %u options 0x%04x%s%s\n",
|
||||
i,
|
||||
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MIN),
|
||||
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_CENTER),
|
||||
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_MAX),
|
||||
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_DEADZONE),
|
||||
io_reg_get(PX4IO_PAGE_RC_CONFIG, base + PX4IO_P_RC_CONFIG_ASSIGNMENT),
|
||||
options,
|
||||
((options & PX4IO_P_RC_CONFIG_OPTIONS_ENABLED) ? " ENABLED" : ""),
|
||||
((options & PX4IO_P_RC_CONFIG_OPTIONS_REVERSE) ? " REVERSED" : ""));
|
||||
}
|
||||
}
|
||||
|
||||
printf("failsafe");
|
||||
|
@ -2853,7 +2857,7 @@ monitor(void)
|
|||
if (g_dev != nullptr) {
|
||||
|
||||
printf("\033[2J\033[H"); /* move cursor home and clear screen */
|
||||
(void)g_dev->print_status();
|
||||
(void)g_dev->print_status(false);
|
||||
(void)g_dev->print_debug();
|
||||
printf("\n\n\n[ Use 'px4io debug <N>' for more output. Hit <enter> three times to exit monitor mode ]\n");
|
||||
|
||||
|
@ -3119,7 +3123,7 @@ px4io_main(int argc, char *argv[])
|
|||
if (!strcmp(argv[1], "status")) {
|
||||
|
||||
printf("[px4io] loaded\n");
|
||||
g_dev->print_status();
|
||||
g_dev->print_status(true);
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
|
|
@ -240,9 +240,9 @@ PX4IO_Uploader::upload(const char *filenames[])
|
|||
close(_io_fd);
|
||||
_io_fd = -1;
|
||||
|
||||
// sleep for enough time for the IO chip to boot. This makes
|
||||
// forceupdate more reliably startup IO again after update
|
||||
up_udelay(100*1000);
|
||||
// sleep for enough time for the IO chip to boot. This makes
|
||||
// forceupdate more reliably startup IO again after update
|
||||
up_udelay(100*1000);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
|
|
@ -1576,32 +1576,36 @@ Mavlink::configure_stream(const char *stream_name, const float rate)
|
|||
/* delete stream */
|
||||
LL_DELETE(_streams, stream);
|
||||
delete stream;
|
||||
warnx("deleted stream %s", stream->get_name());
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
}
|
||||
|
||||
if (interval > 0) {
|
||||
/* search for stream with specified name in supported streams list */
|
||||
for (unsigned int i = 0; streams_list[i] != nullptr; i++) {
|
||||
|
||||
if (strcmp(stream_name, streams_list[i]->get_name()) == 0) {
|
||||
/* create new instance */
|
||||
stream = streams_list[i]->new_instance();
|
||||
stream->set_channel(get_channel());
|
||||
stream->set_interval(interval);
|
||||
stream->subscribe(this);
|
||||
LL_APPEND(_streams, stream);
|
||||
return OK;
|
||||
}
|
||||
}
|
||||
|
||||
} else {
|
||||
/* stream not found, nothing to disable */
|
||||
if (interval == 0) {
|
||||
/* stream was not active and is requested to be disabled, do nothing */
|
||||
return OK;
|
||||
}
|
||||
|
||||
/* search for stream with specified name in supported streams list */
|
||||
for (unsigned int i = 0; streams_list[i] != nullptr; i++) {
|
||||
|
||||
if (strcmp(stream_name, streams_list[i]->get_name()) == 0) {
|
||||
/* create new instance */
|
||||
stream = streams_list[i]->new_instance();
|
||||
stream->set_channel(get_channel());
|
||||
stream->set_interval(interval);
|
||||
stream->subscribe(this);
|
||||
LL_APPEND(_streams, stream);
|
||||
|
||||
return OK;
|
||||
}
|
||||
}
|
||||
|
||||
/* if we reach here, the stream list does not contain the stream */
|
||||
warnx("stream %s not found", stream_name);
|
||||
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
|
|
|
@ -1652,7 +1652,7 @@ StreamListItem *streams_list[] = {
|
|||
new StreamListItem(&MavlinkStreamLocalPositionSetpoint::new_instance, &MavlinkStreamLocalPositionSetpoint::get_name_static),
|
||||
new StreamListItem(&MavlinkStreamRollPitchYawThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawThrustSetpoint::get_name_static),
|
||||
new StreamListItem(&MavlinkStreamRollPitchYawRatesThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static),
|
||||
new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamGlobalPositionInt::get_name_static),
|
||||
new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamRCChannelsRaw::get_name_static),
|
||||
new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static),
|
||||
new StreamListItem(&MavlinkStreamOpticalFlow::new_instance, &MavlinkStreamOpticalFlow::get_name_static),
|
||||
new StreamListItem(&MavlinkStreamAttitudeControls::new_instance, &MavlinkStreamAttitudeControls::get_name_static),
|
||||
|
|
|
@ -44,6 +44,8 @@
|
|||
#include <uORB/uORB.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#include "mavlink_orb_subscription.h"
|
||||
|
||||
MavlinkOrbSubscription::MavlinkOrbSubscription(const orb_id_t topic) :
|
||||
|
@ -77,21 +79,23 @@ MavlinkOrbSubscription::update(uint64_t *time, void* data)
|
|||
time_topic = 0;
|
||||
}
|
||||
|
||||
if (orb_copy(_topic, _fd, data)) {
|
||||
/* error copying topic data */
|
||||
memset(data, 0, _topic->o_size);
|
||||
return false;
|
||||
if (time_topic != *time) {
|
||||
|
||||
} else {
|
||||
/* data copied successfully */
|
||||
_published = true;
|
||||
if (time_topic != *time) {
|
||||
*time = time_topic;
|
||||
return true;
|
||||
if (orb_copy(_topic, _fd, data)) {
|
||||
/* error copying topic data */
|
||||
memset(data, 0, _topic->o_size);
|
||||
//warnx("err copy, fd: %d, obj: %s, size: %d", _fd, _topic->o_name, _topic->o_size);
|
||||
return false;
|
||||
|
||||
} else {
|
||||
return false;
|
||||
/* data copied successfully */
|
||||
_published = true;
|
||||
*time = time_topic;
|
||||
return true;
|
||||
}
|
||||
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -301,7 +301,7 @@ perf_print_counter_fd(int fd, perf_counter_t handle)
|
|||
case PC_ELAPSED: {
|
||||
struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
|
||||
|
||||
dprintf(fd, "%s: %llu events, %lluus elapsed, %llu avg, min %lluus max %lluus\n",
|
||||
dprintf(fd, "%s: %llu events, %lluus elapsed, %lluus avg, min %lluus max %lluus\n",
|
||||
handle->name,
|
||||
pce->event_count,
|
||||
pce->time_total,
|
||||
|
@ -314,7 +314,7 @@ perf_print_counter_fd(int fd, perf_counter_t handle)
|
|||
case PC_INTERVAL: {
|
||||
struct perf_ctr_interval *pci = (struct perf_ctr_interval *)handle;
|
||||
|
||||
dprintf(fd, "%s: %llu events, %llu avg, min %lluus max %lluus\n",
|
||||
dprintf(fd, "%s: %llu events, %lluus avg, min %lluus max %lluus\n",
|
||||
handle->name,
|
||||
pci->event_count,
|
||||
(pci->time_last - pci->time_first) / pci->event_count,
|
||||
|
|
Loading…
Reference in New Issue