# # http://www.apache.org/licenses/LICENSE-2.0 # # Unless required by applicable law or agreed to in writing, software # distributed under the License is distributed on an "AS IS" BASIS, # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. # See the License for the specific language governing permissions and # limitations under the License. from pymavlink import mavutil from pymavlink.mavutil import mavlink from utils import main_utils if __name__ == '__main__': try: connection = main_utils.connect() main_utils.start_sending_heartbeat(connection) connection.wait_heartbeat() result = main_utils.send_command( connection, mavlink.MAV_CMD_SET_MESSAGE_INTERVAL, blocking=True, param1=float(mavlink.MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE), param2=-1.0) success = (result == mavlink.MAV_RESULT_ACCEPTED) print('disable VISION_POSITION_ESTIMATE: %r (%d)' % (success, result)) except KeyboardInterrupt: exit(0)
stamp_offset_ms = None def send_attitude(): global stamp_offset_ms while True: stamp = int(time.time() * 1000) + stamp_offset_ms connection.mav.attitude_send(stamp, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0) time.sleep(0.05) if __name__ == '__main__': connection = main_utils.connect() main_utils.start_sending_heartbeat(connection, armed=True) connection.wait_heartbeat() params = param_utils.list_params(connection) for p in params: print('Param %s = %3.6f' % (p.param_id, p.param_value)) check_and_set_param(p, 'SAVE_MAP', 1) check_and_set_param(p, 'LOAD_MAP', 0) check_and_set_param(p, 'SEND_ORIGIN', 0) check_and_set_param(p, 'INIT_ALT', 1.0) if need_reboot: print('Parameters was changed. Rebooting, please wait...') main_utils.reboot(connection) main_utils.stop_sending_heartbeat(connection) del connection