Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/mavproxy_modules/sitl_calibration.py
Views: 1798
# Copyright (C) 2015-2016 Intel Corporation. All rights reserved.1#2# This file is free software: you can redistribute it and/or modify it3# under the terms of the GNU General Public License as published by the4# Free Software Foundation, either version 3 of the License, or5# (at your option) any later version.6#7# This file is distributed in the hope that it will be useful, but8# WITHOUT ANY WARRANTY; without even the implied warranty of9# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.10# See the GNU General Public License for more details.11#12# You should have received a copy of the GNU General Public License along13# with this program. If not, see <http://www.gnu.org/licenses/>.14'''calibration simulation command handling'''1516from __future__ import division, print_function17import math18from pymavlink import quaternion19import random20import time2122from MAVProxy.modules.lib import mp_module2324class CalController(object):25def __init__(self, mpstate):26self.mpstate = mpstate27self.active = False28self.reset()2930def reset(self):31self.desired_quaternion = None32self.general_state = 'idle'33self.attitude_callback = None34self.desired_quaternion_close_count = 03536def start(self):37self.active = True3839def stop(self):40self.reset()41self.mpstate.functions.process_stdin('servo set 5 1000')42self.active = False4344def normalize_attitude_angle(self, angle):45if angle < 0:46angle = 2 * math.pi + angle % (-2 * math.pi)47angle %= 2 * math.pi48if angle > math.pi:49return angle % -math.pi50return angle5152def set_attitute(self, roll, pitch, yaw, callback=None):53roll = self.normalize_attitude_angle(roll)54pitch = self.normalize_attitude_angle(pitch)55yaw = self.normalize_attitude_angle(yaw)5657self.desired_quaternion = quaternion.Quaternion((roll, pitch, yaw))58self.desired_quaternion.normalize()5960scale = 500.0 / math.pi6162roll_pwm = 1500 + int(roll * scale)63pitch_pwm = 1500 + int(pitch * scale)64yaw_pwm = 1500 + int(yaw * scale)6566self.mpstate.functions.process_stdin('servo set 5 1150')67self.mpstate.functions.process_stdin('servo set 6 %d' % roll_pwm)68self.mpstate.functions.process_stdin('servo set 7 %d' % pitch_pwm)69self.mpstate.functions.process_stdin('servo set 8 %d' % yaw_pwm)7071self.general_state = 'attitude'72self.desired_quaternion_close_count = 07374if callback:75self.attitude_callback = callback7677def angvel(self, x, y, z, theta):78m = max(abs(x), abs(y), abs(z))79if not m:80x_pwm = y_pwm = z_pwm = 150081else:82x_pwm = 1500 + round((x / m) * 500)83y_pwm = 1500 + round((y / m) * 500)84z_pwm = 1500 + round((z / m) * 500)8586max_theta = 2 * math.pi87if theta < 0:88theta = 089elif theta > max_theta:90theta = max_theta91theta_pwm = 1300 + round((theta / max_theta) * 700)9293self.mpstate.functions.process_stdin('servo set 5 %d' % theta_pwm)94self.mpstate.functions.process_stdin('servo set 6 %d' % x_pwm)95self.mpstate.functions.process_stdin('servo set 7 %d' % y_pwm)96self.mpstate.functions.process_stdin('servo set 8 %d' % z_pwm)9798self.general_state = 'angvel'99100def autonomous_magcal(self):101self.mpstate.functions.process_stdin('servo set 5 1250')102103def handle_simstate(self, m):104if self.general_state == 'attitude':105q = quaternion.Quaternion((m.roll, m.pitch, m.yaw))106q.normalize()107d1 = abs(self.desired_quaternion.q - q.q)108d2 = abs(self.desired_quaternion.q + q.q)109if (d1 <= 1e-2).all() or (d2 <= 1e-2).all():110self.desired_quaternion_close_count += 1111else:112self.desired_quaternion_close_count = 0113114if self.desired_quaternion_close_count == 5:115self.general_state = 'idle'116if callable(self.attitude_callback):117self.attitude_callback()118self.attitude_callback = None119120def mavlink_packet(self, m):121if not self.active:122return123if m.get_type() == 'SIMSTATE':124self.handle_simstate(m)125126127class AccelcalController(CalController):128state_data = {129'level': dict(130name='Level',131attitude=(0, 0, 0),132),133'LEFT': dict(134name='Left side',135attitude=(-math.pi / 2, 0, 0),136),137'RIGHT': dict(138name='Right side',139attitude=(math.pi / 2, 0, 0),140),141'DOWN': dict(142name='Nose down',143attitude=(0, -math.pi / 2, 0),144),145'UP': dict(146name='Nose up',147attitude=(0, math.pi / 2, 0),148),149'BACK': dict(150name='Back',151attitude=(math.pi, 0, 0),152),153}154155def __init__(self, mpstate):156super(AccelcalController, self).__init__(mpstate)157self.state = None158159def reset(self):160super(AccelcalController, self).reset()161162def start(self):163super(AccelcalController, self).start()164if self.state:165self.set_side_state(self.state)166167def side_from_msg(self, m):168text = str(m.text)169if text.startswith('Place '):170for side in self.state_data:171if side in text:172return side173return None174175def report_from_msg(self, m):176'''Return true if successful, false if failed, None if unknown'''177text = str(m.text)178if 'Calibration successful' in text:179return True180elif 'Calibration FAILED' in text:181return False182return None183184def set_side_state(self, side):185self.state = side186187if not self.active:188return189190data = self.state_data[side]191192def callback():193self.mpstate.console.set_status(194name='sitl_accelcal',195text='sitl_accelcal: %s ready - Waiting for user input' % data['name'],196row=4,197fg='blue',198)199self.mpstate.console.writeln('sitl_accelcal: attitude detected, please press any key..')200201self.mpstate.console.writeln('sitl_accelcal: sending attitude, please wait..')202203roll, pitch, yaw = data['attitude']204self.set_attitute(roll, pitch, yaw, callback=callback)205206self.mpstate.console.set_status(207name='sitl_accelcal',208text='sitl_accelcal: %s - Waiting for attitude' % data['name'],209row=4,210fg='orange',211)212213def mavlink_packet(self, m):214super(AccelcalController, self).mavlink_packet(m)215216if m.get_type() != 'STATUSTEXT':217return218219side = self.side_from_msg(m)220if side:221self.set_side_state(side)222else:223success = self.report_from_msg(m)224if success is None:225return226227self.state = None228if success:229self.mpstate.console.set_status(230name='sitl_accelcal',231text='sitl_accelcal: Calibration successful',232row=4,233fg='blue',234)235else:236self.mpstate.console.set_status(237name='sitl_accelcal',238text='sitl_accelcal: Calibration failed',239row=4,240fg='red',241)242243244class MagcalController(CalController):245yaw_increment = math.radians(45)246yaw_noise_range = math.radians(5)247248rotation_angspeed = math.pi / 4249'''rotation angular speed in rad/s'''250rotation_angspeed_noise = math.radians(2)251rotation_axes = (252(1, 0, 0),253(0, 1, 0),254(1, 1, 0),255)256257full_turn_time = 2 * math.pi / rotation_angspeed258259max_full_turns = 3260'''maximum number of full turns to be performed for each initial attitude'''261262def reset(self):263super(MagcalController, self).reset()264self.yaw = 0265self.rotation_start_time = 0266self.last_progress = {}267self.rotation_axis_idx = 0268269def start(self):270super(MagcalController, self).start()271self.set_attitute(0, 0, 0, callback=self.next_rot_att_callback)272273def next_rot_att_callback(self):274x, y, z = self.rotation_axes[self.rotation_axis_idx]275angspeed = self.rotation_angspeed276angspeed += random.uniform(-1, 1) * self.rotation_angspeed_noise277self.angvel(x, y, z, angspeed)278self.rotation_start_time = time.time()279280def next_rotation(self):281self.rotation_axis_idx += 1282self.rotation_axis_idx %= len(self.rotation_axes)283284if self.rotation_axis_idx == 0:285yaw_inc = self.yaw_increment286yaw_inc += random.uniform(-1, 1) * self.yaw_noise_range287self.yaw = (self.yaw + yaw_inc) % (2 * math.pi)288289self.rotation_start_time = 0290self.last_progress = {}291self.set_attitute(0, 0, self.yaw, callback=self.next_rot_att_callback)292293def mavlink_packet(self, m):294super(MagcalController, self).mavlink_packet(m)295296if not self.active:297return298299if m.get_type() == 'MAG_CAL_REPORT':300# NOTE: This may be not the ideal way to handle it301if m.compass_id in self.last_progress:302# this is set to None so we can ensure we don't get303# progress reports for completed compasses.304self.last_progress[m.compass_id] = None305if len(self.last_progress.values()) and all(progress is None for progress in self.last_progress.values()):306self.stop()307return308309if m.get_type() != 'MAG_CAL_PROGRESS':310return311312if not self.rotation_start_time:313return314315t = time.time()316m.time = t317318if m.compass_id not in self.last_progress:319self.last_progress[m.compass_id] = m320m.stuck = False321return322323last = self.last_progress[m.compass_id]324if last is None:325raise Exception("Received progress message for completed compass")326327dt = t - self.rotation_start_time328if dt > self.max_full_turns * self.full_turn_time:329self.next_rotation()330return331332if m.completion_pct == last.completion_pct:333if m.time - last.time > self.full_turn_time / 2:334last.stuck = True335else:336self.last_progress[m.compass_id] = m337m.stuck = False338339for p in self.last_progress.values():340if p is not None and not p.stuck:341break342else:343self.next_rotation()344345346class SitlCalibrationModule(mp_module.MPModule):347def __init__(self, mpstate):348super(SitlCalibrationModule, self).__init__(mpstate, "sitl_calibration")349self.add_command(350'sitl_attitude',351self.cmd_sitl_attitude,352'set the vehicle at the inclination given by ROLL, PITCH and YAW' +353' in degrees',354)355self.add_command(356'sitl_angvel',357self.cmd_angvel,358'apply angular velocity on the vehicle with a rotation axis and a '+359'magnitude in degrees/s',360)361self.add_command(362'sitl_accelcal',363self.cmd_sitl_accelcal,364'actuate on the simulator vehicle for accelerometer calibration',365)366self.add_command(367'sitl_magcal',368self.cmd_sitl_magcal,369'actuate on the simulator vehicle for magnetometer calibration',370)371self.add_command(372'sitl_autonomous_magcal',373self.cmd_sitl_autonomous_magcal,374'let the simulating program do the rotations for magnetometer ' +375'calibration - basically, continuous rotations over six ' +376'calibration poses',377)378self.add_command(379'sitl_stop',380self.cmd_sitl_stop,381'stop the current calibration control',382)383384self.controllers = dict(385generic_controller=CalController(mpstate),386accelcal_controller=AccelcalController(mpstate),387magcal_controller=MagcalController(mpstate),388)389390self.current_controller = None391392def set_controller(self, controller):393if self.current_controller:394self.current_controller.stop()395396controller = self.controllers.get(controller, None)397if controller:398controller.start()399self.current_controller = controller400401def cmd_sitl_attitude(self, args):402if len(args) != 3:403print('Usage: sitl_attitude <ROLL> <PITCH> <YAW>')404return405406try:407roll, pitch, yaw = args408roll = math.radians(float(roll))409pitch = math.radians(float(pitch))410yaw = math.radians(float(yaw))411except ValueError:412print('Invalid arguments')413414self.set_controller('generic_controller')415self.current_controller.set_attitute(roll, pitch, yaw)416417def cmd_angvel(self, args):418if len(args) != 4:419print('Usage: sitl_angvel <AXIS_X> <AXIS_Y> <AXIS_Z> <THETA>')420return421422try:423x, y, z, theta = args424x = float(x)425y = float(y)426z = float(z)427theta = math.radians(float(theta))428except ValueError:429print('Invalid arguments')430431self.set_controller('generic_controller')432self.current_controller.angvel(x, y, z, theta)433434def cmd_sitl_stop(self, args):435self.set_controller('generic_controller')436437def cmd_sitl_accelcal(self, args):438self.set_controller('accelcal_controller')439440def cmd_sitl_magcal(self, args):441self.set_controller('magcal_controller')442443def cmd_sitl_autonomous_magcal(self, args):444self.set_controller('generic_controller')445self.current_controller.autonomous_magcal()446447def mavlink_packet(self, m):448for c in self.controllers.values():449c.mavlink_packet(m)450451def init(mpstate):452'''initialise module'''453return SitlCalibrationModule(mpstate)454455456