Path: blob/master/Tools/mavproxy_modules/sitl_calibration.py
9644 views
# 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/>.1415# flake8: noqa1617'''calibration simulation command handling'''1819import math20from pymavlink import quaternion21import random22import time2324from MAVProxy.modules.lib import mp_module2526class CalController(object):27def __init__(self, mpstate):28self.mpstate = mpstate29self.active = False30self.reset()3132def reset(self):33self.desired_quaternion = None34self.general_state = 'idle'35self.attitude_callback = None36self.desired_quaternion_close_count = 03738def start(self):39self.active = True4041def stop(self):42self.reset()43self.mpstate.functions.process_stdin('servo set 5 1000')44self.active = False4546def normalize_attitude_angle(self, angle):47if angle < 0:48angle = 2 * math.pi + angle % (-2 * math.pi)49angle %= 2 * math.pi50if angle > math.pi:51return angle % -math.pi52return angle5354def set_attitute(self, roll, pitch, yaw, callback=None):55roll = self.normalize_attitude_angle(roll)56pitch = self.normalize_attitude_angle(pitch)57yaw = self.normalize_attitude_angle(yaw)5859self.desired_quaternion = quaternion.Quaternion((roll, pitch, yaw))60self.desired_quaternion.normalize()6162scale = 500.0 / math.pi6364roll_pwm = 1500 + int(roll * scale)65pitch_pwm = 1500 + int(pitch * scale)66yaw_pwm = 1500 + int(yaw * scale)6768self.mpstate.functions.process_stdin('servo set 5 1150')69self.mpstate.functions.process_stdin('servo set 6 %d' % roll_pwm)70self.mpstate.functions.process_stdin('servo set 7 %d' % pitch_pwm)71self.mpstate.functions.process_stdin('servo set 8 %d' % yaw_pwm)7273self.general_state = 'attitude'74self.desired_quaternion_close_count = 07576if callback:77self.attitude_callback = callback7879def angvel(self, x, y, z, theta):80m = max(abs(x), abs(y), abs(z))81if not m:82x_pwm = y_pwm = z_pwm = 150083else:84x_pwm = 1500 + round((x / m) * 500)85y_pwm = 1500 + round((y / m) * 500)86z_pwm = 1500 + round((z / m) * 500)8788max_theta = 2 * math.pi89if theta < 0:90theta = 091elif theta > max_theta:92theta = max_theta93theta_pwm = 1300 + round((theta / max_theta) * 700)9495self.mpstate.functions.process_stdin('servo set 5 %d' % theta_pwm)96self.mpstate.functions.process_stdin('servo set 6 %d' % x_pwm)97self.mpstate.functions.process_stdin('servo set 7 %d' % y_pwm)98self.mpstate.functions.process_stdin('servo set 8 %d' % z_pwm)99100self.general_state = 'angvel'101102def autonomous_magcal(self):103self.mpstate.functions.process_stdin('servo set 5 1250')104105def handle_simstate(self, m):106if self.general_state == 'attitude':107q = quaternion.Quaternion((m.roll, m.pitch, m.yaw))108q.normalize()109d1 = abs(self.desired_quaternion.q - q.q)110d2 = abs(self.desired_quaternion.q + q.q)111if (d1 <= 1e-2).all() or (d2 <= 1e-2).all():112self.desired_quaternion_close_count += 1113else:114self.desired_quaternion_close_count = 0115116if self.desired_quaternion_close_count == 5:117self.general_state = 'idle'118if callable(self.attitude_callback):119self.attitude_callback()120self.attitude_callback = None121122def mavlink_packet(self, m):123if not self.active:124return125if m.get_type() == 'SIMSTATE':126self.handle_simstate(m)127128129class AccelcalController(CalController):130state_data = {131'level': dict(132name='Level',133attitude=(0, 0, 0),134),135'LEFT': dict(136name='Left side',137attitude=(-math.pi / 2, 0, 0),138),139'RIGHT': dict(140name='Right side',141attitude=(math.pi / 2, 0, 0),142),143'DOWN': dict(144name='Nose down',145attitude=(0, -math.pi / 2, 0),146),147'UP': dict(148name='Nose up',149attitude=(0, math.pi / 2, 0),150),151'BACK': dict(152name='Back',153attitude=(math.pi, 0, 0),154),155}156157def __init__(self, mpstate):158super(AccelcalController, self).__init__(mpstate)159self.state = None160161def reset(self):162super(AccelcalController, self).reset()163164def start(self):165super(AccelcalController, self).start()166if self.state:167self.set_side_state(self.state)168169def side_from_msg(self, m):170text = str(m.text)171if text.startswith('Place '):172for side in self.state_data:173if side in text:174return side175return None176177def report_from_msg(self, m):178'''Return true if successful, false if failed, None if unknown'''179text = str(m.text)180if 'Calibration successful' in text:181return True182elif 'Calibration FAILED' in text:183return False184return None185186def set_side_state(self, side):187self.state = side188189if not self.active:190return191192data = self.state_data[side]193194def callback():195self.mpstate.console.set_status(196name='sitl_accelcal',197text='sitl_accelcal: %s ready - Waiting for user input' % data['name'],198row=4,199fg='blue',200)201self.mpstate.console.writeln('sitl_accelcal: attitude detected, please press any key..')202203self.mpstate.console.writeln('sitl_accelcal: sending attitude, please wait..')204205roll, pitch, yaw = data['attitude']206self.set_attitute(roll, pitch, yaw, callback=callback)207208self.mpstate.console.set_status(209name='sitl_accelcal',210text='sitl_accelcal: %s - Waiting for attitude' % data['name'],211row=4,212fg='orange',213)214215def mavlink_packet(self, m):216super(AccelcalController, self).mavlink_packet(m)217218if m.get_type() != 'STATUSTEXT':219return220221side = self.side_from_msg(m)222if side:223self.set_side_state(side)224else:225success = self.report_from_msg(m)226if success is None:227return228229self.state = None230if success:231self.mpstate.console.set_status(232name='sitl_accelcal',233text='sitl_accelcal: Calibration successful',234row=4,235fg='blue',236)237else:238self.mpstate.console.set_status(239name='sitl_accelcal',240text='sitl_accelcal: Calibration failed',241row=4,242fg='red',243)244245246class MagcalController(CalController):247yaw_increment = math.radians(45)248yaw_noise_range = math.radians(5)249250rotation_angspeed = math.pi / 4251'''rotation angular speed in rad/s'''252rotation_angspeed_noise = math.radians(2)253rotation_axes = (254(1, 0, 0),255(0, 1, 0),256(1, 1, 0),257)258259full_turn_time = 2 * math.pi / rotation_angspeed260261max_full_turns = 3262'''maximum number of full turns to be performed for each initial attitude'''263264def reset(self):265super(MagcalController, self).reset()266self.yaw = 0267self.rotation_start_time = 0268self.last_progress = {}269self.rotation_axis_idx = 0270271def start(self):272super(MagcalController, self).start()273self.set_attitute(0, 0, 0, callback=self.next_rot_att_callback)274275def next_rot_att_callback(self):276x, y, z = self.rotation_axes[self.rotation_axis_idx]277angspeed = self.rotation_angspeed278angspeed += random.uniform(-1, 1) * self.rotation_angspeed_noise279self.angvel(x, y, z, angspeed)280self.rotation_start_time = time.time()281282def next_rotation(self):283self.rotation_axis_idx += 1284self.rotation_axis_idx %= len(self.rotation_axes)285286if self.rotation_axis_idx == 0:287yaw_inc = self.yaw_increment288yaw_inc += random.uniform(-1, 1) * self.yaw_noise_range289self.yaw = (self.yaw + yaw_inc) % (2 * math.pi)290291self.rotation_start_time = 0292self.last_progress = {}293self.set_attitute(0, 0, self.yaw, callback=self.next_rot_att_callback)294295def mavlink_packet(self, m):296super(MagcalController, self).mavlink_packet(m)297298if not self.active:299return300301if m.get_type() == 'MAG_CAL_REPORT':302# NOTE: This may be not the ideal way to handle it303if m.compass_id in self.last_progress:304# this is set to None so we can ensure we don't get305# progress reports for completed compasses.306self.last_progress[m.compass_id] = None307if len(self.last_progress.values()) and all(progress is None for progress in self.last_progress.values()):308self.stop()309return310311if m.get_type() != 'MAG_CAL_PROGRESS':312return313314if not self.rotation_start_time:315return316317t = time.time()318m.time = t319320if m.compass_id not in self.last_progress:321self.last_progress[m.compass_id] = m322m.stuck = False323return324325last = self.last_progress[m.compass_id]326if last is None:327raise Exception("Received progress message for completed compass")328329dt = t - self.rotation_start_time330if dt > self.max_full_turns * self.full_turn_time:331self.next_rotation()332return333334if m.completion_pct == last.completion_pct:335if m.time - last.time > self.full_turn_time / 2:336last.stuck = True337else:338self.last_progress[m.compass_id] = m339m.stuck = False340341for p in self.last_progress.values():342if p is not None and not p.stuck:343break344else:345self.next_rotation()346347348class SitlCalibrationModule(mp_module.MPModule):349def __init__(self, mpstate):350super(SitlCalibrationModule, self).__init__(mpstate, "sitl_calibration")351self.add_command(352'sitl_attitude',353self.cmd_sitl_attitude,354'set the vehicle at the inclination given by ROLL, PITCH and YAW' +355' in degrees',356)357self.add_command(358'sitl_angvel',359self.cmd_angvel,360'apply angular velocity on the vehicle with a rotation axis and a '+361'magnitude in degrees/s',362)363self.add_command(364'sitl_accelcal',365self.cmd_sitl_accelcal,366'actuate on the simulator vehicle for accelerometer calibration',367)368self.add_command(369'sitl_magcal',370self.cmd_sitl_magcal,371'actuate on the simulator vehicle for magnetometer calibration',372)373self.add_command(374'sitl_autonomous_magcal',375self.cmd_sitl_autonomous_magcal,376'let the simulating program do the rotations for magnetometer ' +377'calibration - basically, continuous rotations over six ' +378'calibration poses',379)380self.add_command(381'sitl_stop',382self.cmd_sitl_stop,383'stop the current calibration control',384)385386self.controllers = dict(387generic_controller=CalController(mpstate),388accelcal_controller=AccelcalController(mpstate),389magcal_controller=MagcalController(mpstate),390)391392self.current_controller = None393394def set_controller(self, controller):395if self.current_controller:396self.current_controller.stop()397398controller = self.controllers.get(controller, None)399if controller:400controller.start()401self.current_controller = controller402403def cmd_sitl_attitude(self, args):404if len(args) != 3:405print('Usage: sitl_attitude <ROLL> <PITCH> <YAW>')406return407408try:409roll, pitch, yaw = args410roll = math.radians(float(roll))411pitch = math.radians(float(pitch))412yaw = math.radians(float(yaw))413except ValueError:414print('Invalid arguments')415416self.set_controller('generic_controller')417self.current_controller.set_attitute(roll, pitch, yaw)418419def cmd_angvel(self, args):420if len(args) != 4:421print('Usage: sitl_angvel <AXIS_X> <AXIS_Y> <AXIS_Z> <THETA>')422return423424try:425x, y, z, theta = args426x = float(x)427y = float(y)428z = float(z)429theta = math.radians(float(theta))430except ValueError:431print('Invalid arguments')432433self.set_controller('generic_controller')434self.current_controller.angvel(x, y, z, theta)435436def cmd_sitl_stop(self, args):437self.set_controller('generic_controller')438439def cmd_sitl_accelcal(self, args):440self.set_controller('accelcal_controller')441442def cmd_sitl_magcal(self, args):443self.set_controller('magcal_controller')444445def cmd_sitl_autonomous_magcal(self, args):446self.set_controller('generic_controller')447self.current_controller.autonomous_magcal()448449def mavlink_packet(self, m):450for c in self.controllers.values():451c.mavlink_packet(m)452453def init(mpstate):454'''initialise module'''455return SitlCalibrationModule(mpstate)456457458