Browse Source

POSIX configs: Send to port 14540 for onboard links

sbg
Lorenz Meier 9 years ago
parent
commit
86c8308e98
  1. 2
      posix-configs/SITL/init/rcS_gazebo_iris
  2. 2
      posix-configs/SITL/init/rcS_gazebo_standard_vtol
  3. 2
      posix-configs/SITL/init/rcS_gazebo_tailsitter
  4. 2
      posix-configs/SITL/init/rcS_jmavsim_iris
  5. 1
      posix-configs/SITL/init/rcS_lpe_gazebo_iris
  6. 2
      posix-configs/SITL/init/rcS_lpe_jmavsim_iris

2
posix-configs/SITL/init/rcS_gazebo_iris

@ -50,7 +50,7 @@ mc_pos_control start @@ -50,7 +50,7 @@ mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_w.main.mix
mavlink start -u 14556 -r 2000000
mavlink start -u 14557 -r 2000000 -m onboard
mavlink start -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556

2
posix-configs/SITL/init/rcS_gazebo_standard_vtol

@ -53,7 +53,7 @@ fw_pos_control_l1 start @@ -53,7 +53,7 @@ fw_pos_control_l1 start
fw_att_control start
mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/standard_vtol_sitl.main.mix
mavlink start -u 14556 -r 2000000
mavlink start -u 14557 -r 2000000 -m onboard
mavlink start -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556

2
posix-configs/SITL/init/rcS_gazebo_tailsitter

@ -53,7 +53,7 @@ fw_pos_control_l1 start @@ -53,7 +53,7 @@ fw_pos_control_l1 start
fw_att_control start
mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_x_vtol.main.mix
mavlink start -u 14556 -r 2000000
mavlink start -u 14557 -r 2000000 -m onboard
mavlink start -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556

2
posix-configs/SITL/init/rcS_jmavsim_iris

@ -56,7 +56,7 @@ mc_pos_control start @@ -56,7 +56,7 @@ mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_x.main.mix
mavlink start -u 14556 -r 2000000
mavlink start -u 14557 -r 2000000 -m onboard
mavlink start -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556

1
posix-configs/SITL/init/rcS_lpe_gazebo_iris

@ -50,6 +50,7 @@ mc_pos_control start @@ -50,6 +50,7 @@ mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_w.main.mix
mavlink start -u 14556 -r 2000000
mavlink start -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED_COV -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556

2
posix-configs/SITL/init/rcS_lpe_jmavsim_iris

@ -61,7 +61,7 @@ mc_pos_control start @@ -61,7 +61,7 @@ mc_pos_control start
mc_att_control start
mixer load /dev/pwm_output0 ../../../../ROMFS/px4fmu_common/mixers/quad_x.main.mix
mavlink start -u 14556 -r 2000000
mavlink start -u 14557 -r 2000000 -m onboard
mavlink start -u 14557 -r 2000000 -m onboard -o 14540
mavlink stream -r 80 -s POSITION_TARGET_LOCAL_NED -u 14556
mavlink stream -r 80 -s LOCAL_POSITION_NED_COV -u 14556
mavlink stream -r 80 -s GLOBAL_POSITION_INT -u 14556

Loading…
Cancel
Save