mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-22 06:14:14 +08:00
Merge branch 'master' into px4dev_new_param
This commit is contained in:
@@ -474,7 +474,7 @@ static int set_mavlink_interval_limit(int mavlink_msg_id, int min_interval)
|
||||
break;
|
||||
case MAVLINK_MSG_ID_ATTITUDE:
|
||||
/* attitude sub triggers attitude */
|
||||
orb_set_interval(att_sub, 100);
|
||||
orb_set_interval(att_sub, min_interval);
|
||||
break;
|
||||
default:
|
||||
/* not found */
|
||||
@@ -527,6 +527,7 @@ static void *uorb_receiveloop(void *arg)
|
||||
/* --- ATTITUDE VALUE --- */
|
||||
/* subscribe to ORB for attitude */
|
||||
att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
|
||||
orb_set_interval(att_sub, 100);
|
||||
fds[fdsc_count].fd = att_sub;
|
||||
fds[fdsc_count].events = POLLIN;
|
||||
fdsc_count++;
|
||||
@@ -1324,17 +1325,17 @@ int mavlink_thread_main(int argc, char *argv[])
|
||||
|
||||
/* all subscriptions are now active, set up initial guess about rate limits */
|
||||
if (baudrate >= 921600) {
|
||||
/* set no limit */
|
||||
/* 500 Hz / 2 ms */
|
||||
//set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 2);
|
||||
set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 2);
|
||||
set_mavlink_interval_limit(MAVLINK_MSG_ID_ATTITUDE, 2);
|
||||
} else if (baudrate >= 460800) {
|
||||
/* 250 Hz / 4 ms */
|
||||
set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 4);
|
||||
set_mavlink_interval_limit(MAVLINK_MSG_ID_ATTITUDE, 4);
|
||||
set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 5);
|
||||
set_mavlink_interval_limit(MAVLINK_MSG_ID_ATTITUDE, 5);
|
||||
} else if (baudrate >= 115200) {
|
||||
/* 50 Hz / 20 ms */
|
||||
set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 20);
|
||||
set_mavlink_interval_limit(MAVLINK_MSG_ID_ATTITUDE, 20);
|
||||
set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 50);
|
||||
set_mavlink_interval_limit(MAVLINK_MSG_ID_ATTITUDE, 50);
|
||||
} else if (baudrate >= 57600) {
|
||||
/* 10 Hz / 100 ms */
|
||||
set_mavlink_interval_limit(MAVLINK_MSG_ID_SCALED_IMU, 100);
|
||||
|
||||
@@ -87,14 +87,14 @@ int attitude_estimator_bm_update(struct sensor_combined_s *raw, float_vect3 *eul
|
||||
gyro_values.z = raw->gyro_rad_s[2];
|
||||
|
||||
float_vect3 accel_values;
|
||||
accel_values.x = raw->accelerometer_m_s2[0] * 9.81f;
|
||||
accel_values.y = raw->accelerometer_m_s2[1] * 9.81f;
|
||||
accel_values.z = raw->accelerometer_m_s2[2] * 9.81f;
|
||||
accel_values.x = raw->accelerometer_m_s2[0] * 9.81f * 9.0f;
|
||||
accel_values.y = raw->accelerometer_m_s2[1] * 9.81f * 9.0f;
|
||||
accel_values.z = raw->accelerometer_m_s2[2] * 9.81f * 9.0f;
|
||||
|
||||
float_vect3 mag_values;
|
||||
mag_values.x = raw->magnetometer_ga[0]*100.0f;
|
||||
mag_values.y = raw->magnetometer_ga[1]*100.0f;
|
||||
mag_values.z = raw->magnetometer_ga[2]*100.0f;
|
||||
mag_values.x = raw->magnetometer_ga[0]*510.0f;
|
||||
mag_values.y = raw->magnetometer_ga[1]*510.0f;
|
||||
mag_values.z = raw->magnetometer_ga[2]*510.0f;
|
||||
|
||||
attitude_blackmagic(&accel_values, &mag_values, &gyro_values);
|
||||
|
||||
|
||||
@@ -37,6 +37,7 @@
|
||||
|
||||
APPNAME = sensors
|
||||
PRIORITY = SCHED_PRIORITY_MAX-5
|
||||
STACKSIZE = 4096
|
||||
# Reduce to 4096 on next occasion
|
||||
STACKSIZE = 8000
|
||||
|
||||
include $(APPDIR)/mk/app.mk
|
||||
|
||||
Reference in New Issue
Block a user