mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-07 09:01:29 +08:00
Compare commits
7 Commits
pr-param_n
...
v1.12.1
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
1682fd5671 | ||
|
|
a8572f0fdd | ||
|
|
a299a3bbd0 | ||
|
|
349dd63072 | ||
|
|
6b51c6390a | ||
|
|
4f7909ee8e | ||
|
|
cbb48f9af3 |
@ -235,6 +235,25 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
syslog(LOG_ERR, "DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
/* set up the serial DMA polling */
|
||||
#ifdef SERIAL_HAVE_DMA
|
||||
static struct hrt_call serial_dma_call;
|
||||
struct timespec ts;
|
||||
|
||||
/*
|
||||
* Poll at 1ms intervals for received bytes that have not triggered
|
||||
* a DMA event.
|
||||
*/
|
||||
ts.tv_sec = 0;
|
||||
ts.tv_nsec = 1000000;
|
||||
|
||||
hrt_call_every(&serial_dma_call,
|
||||
ts_to_abstime(&ts),
|
||||
ts_to_abstime(&ts),
|
||||
(hrt_callout)kinetis_serial_dma_poll,
|
||||
NULL);
|
||||
#endif
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_RED);
|
||||
|
||||
@ -235,6 +235,25 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
syslog(LOG_ERR, "DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
/* set up the serial DMA polling */
|
||||
#ifdef SERIAL_HAVE_DMA
|
||||
static struct hrt_call serial_dma_call;
|
||||
struct timespec ts;
|
||||
|
||||
/*
|
||||
* Poll at 1ms intervals for received bytes that have not triggered
|
||||
* a DMA event.
|
||||
*/
|
||||
ts.tv_sec = 0;
|
||||
ts.tv_nsec = 1000000;
|
||||
|
||||
hrt_call_every(&serial_dma_call,
|
||||
ts_to_abstime(&ts),
|
||||
ts_to_abstime(&ts),
|
||||
(hrt_callout)kinetis_serial_dma_poll,
|
||||
NULL);
|
||||
#endif
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_RED);
|
||||
|
||||
@ -76,7 +76,7 @@ px4_add_board(
|
||||
#gyro_fft
|
||||
land_detector
|
||||
#landing_target_estimator
|
||||
load_mon
|
||||
#load_mon
|
||||
#local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
|
||||
@ -48,7 +48,7 @@ px4_add_board(
|
||||
#events
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
load_mon
|
||||
#load_mon
|
||||
#local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
|
||||
@ -1 +1 @@
|
||||
Subproject commit 76bb42f3ebd902102e844084b564274bf215ec9f
|
||||
Subproject commit bf660cba2af81f055002b3817c87b1f63a78fd09
|
||||
@ -1 +1 @@
|
||||
Subproject commit 71fc1b81612fa9b5184d5abb93b69d109e9d0e4b
|
||||
Subproject commit b3fed06fe822d08d19ab1d2c2f8daf7b7d21951c
|
||||
@ -911,10 +911,12 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
|
||||
(type_mask & POSITION_TARGET_TYPEMASK_VZ_IGNORE) ? 0.f : target_local_ned.vz
|
||||
};
|
||||
|
||||
const matrix::Vector3f velocity_setpoint{R * velocity_body_sp};
|
||||
setpoint.vx = velocity_setpoint(0);
|
||||
setpoint.vy = velocity_setpoint(1);
|
||||
setpoint.vz = velocity_setpoint(2);
|
||||
|
||||
const float yaw = matrix::Eulerf{R}(2);
|
||||
|
||||
setpoint.vx = cosf(yaw) * velocity_body_sp(0) - sinf(yaw) * velocity_body_sp(1);
|
||||
setpoint.vy = sinf(yaw) * velocity_body_sp(0) + cosf(yaw) * velocity_body_sp(1);
|
||||
setpoint.vz = velocity_body_sp(2);
|
||||
|
||||
} else {
|
||||
setpoint.vx = NAN;
|
||||
|
||||
@ -187,6 +187,8 @@ void VotedSensorsUpdate::imuPoll(struct sensor_combined_s &raw)
|
||||
// find the best sensor
|
||||
int accel_best_index = -1;
|
||||
int gyro_best_index = -1;
|
||||
_accel.voter.get_best(hrt_absolute_time(), &accel_best_index);
|
||||
_gyro.voter.get_best(hrt_absolute_time(), &gyro_best_index);
|
||||
|
||||
if (!_param_sens_imu_mode.get() && ((_selection.timestamp != 0) || (_sensor_selection_sub.updated()))) {
|
||||
// use sensor_selection to find best
|
||||
@ -213,9 +215,6 @@ void VotedSensorsUpdate::imuPoll(struct sensor_combined_s &raw)
|
||||
|
||||
} else {
|
||||
// use sensor voter to find best if SENS_IMU_MODE is enabled or ORB_ID(sensor_selection) has never published
|
||||
_accel.voter.get_best(hrt_absolute_time(), &accel_best_index);
|
||||
_gyro.voter.get_best(hrt_absolute_time(), &gyro_best_index);
|
||||
|
||||
checkFailover(_accel, "Accel");
|
||||
checkFailover(_gyro, "Gyro");
|
||||
}
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user