forked from Archive/PX4-Autopilot
mavlink: camera mode rate is now correct
This commit is contained in:
parent
a989dd6eec
commit
bf69a7b647
|
@ -1773,8 +1773,8 @@ Mavlink::task_main(int argc, char *argv[])
|
|||
|
||||
case MAVLINK_MODE_CAMERA:
|
||||
configure_stream("SYS_STATUS", 1.0f);
|
||||
configure_stream("ATTITUDE", 20.0f * rate_mult);
|
||||
configure_stream("GLOBAL_POSITION_INT", 20.0f * rate_mult);
|
||||
configure_stream("ATTITUDE", 15.0f * rate_mult);
|
||||
configure_stream("GLOBAL_POSITION_INT", 15.0f * rate_mult);
|
||||
configure_stream("CAMERA_CAPTURE", 1.0f);
|
||||
break;
|
||||
|
||||
|
|
Loading…
Reference in New Issue