mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Merge branch 'release_v1.0.0' into beta
This commit is contained in:
commit
3d860086fa
@ -457,13 +457,13 @@ then
|
||||
if [ $TTYS1_BUSY == yes ]
|
||||
then
|
||||
# Start MAVLink on ttyS0, because FMU ttyS1 pins configured as something else
|
||||
set MAVLINK_F "-r 1000 -d /dev/ttyS0"
|
||||
set MAVLINK_F "-r 5000 -d /dev/ttyS0"
|
||||
|
||||
# Exit from nsh to free port for mavlink
|
||||
set EXIT_ON_END yes
|
||||
else
|
||||
# Start MAVLink on default port: ttyS1
|
||||
set MAVLINK_F "-r 1000"
|
||||
set MAVLINK_F "-r 5000"
|
||||
fi
|
||||
fi
|
||||
|
||||
@ -479,11 +479,11 @@ then
|
||||
# but this works for now
|
||||
if param compare SYS_COMPANION 921600
|
||||
then
|
||||
mavlink start -d /dev/ttyS2 -b 921600 -m onboard -r 20000 -x
|
||||
mavlink start -d /dev/ttyS2 -b 921600 -m onboard -r 80000 -x
|
||||
fi
|
||||
if param compare SYS_COMPANION 57600
|
||||
then
|
||||
mavlink start -d /dev/ttyS2 -b 57600 -m onboard -r 1000 -x
|
||||
mavlink start -d /dev/ttyS2 -b 57600 -m onboard -r 60000 -x
|
||||
fi
|
||||
if param compare SYS_COMPANION 157600
|
||||
then
|
||||
|
||||
24
ROMFS/px4fmu_test/mixers/IO_pass.mix
Normal file
24
ROMFS/px4fmu_test/mixers/IO_pass.mix
Normal file
@ -0,0 +1,24 @@
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 10000 10000 0 -10000 10000
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 1 10000 10000 0 -10000 10000
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 2 10000 10000 0 -10000 10000
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 3 10000 10000 0 -10000 10000
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 4 10000 10000 0 -10000 10000
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 5 10000 10000 0 -10000 10000
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 6 10000 10000 0 -10000 10000
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 7 10000 10000 0 -10000 10000
|
||||
@ -52,8 +52,8 @@ void _assert_parameter_int_value(param_t param, int32_t expected)
|
||||
{
|
||||
int32_t value;
|
||||
int result = param_get(param, &value);
|
||||
ASSERT_EQ(0, result) << printf("param_get (%i) did not return parameter\n", param);
|
||||
ASSERT_EQ(expected, value) << printf("value for param (%i) doesn't match default value\n", param);
|
||||
ASSERT_EQ(0, result) << printf("param_get (%lu) did not return parameter\n", param);
|
||||
ASSERT_EQ(expected, value) << printf("value for param (%lu) doesn't match default value\n", param);
|
||||
}
|
||||
|
||||
void _set_all_int_parameters_to(int32_t value)
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user