$search
00001 #! /usr/bin/env python -m 00002 # -*- coding: utf-8 -*- 00003 # _____ 00004 # / _ \ 00005 # / _/ \ \ 00006 # / / \_/ \ 00007 # / \_/ _ \ ___ _ ___ ___ ____ ____ ___ _____ _ _ 00008 # \ / \_/ \ / / _\| | | __| / _ \ | ┌┐ \ | ┌┐ \ / _ \ |_ _|| | | | 00009 # \ \_/ \_/ / | | | | | └─┐| |_| || └┘ / | └┘_/| |_| | | | | └─┘ | 00010 # \ \_/ / | |_ | |_ | ┌─┘| _ || |\ \ | | | _ | | | | ┌─┐ | 00011 # \_____/ \___/|___||___||_| |_||_| \_\|_| |_| |_| |_| |_| |_| 00012 # ROBOTICS™ 00013 # 00014 # File: horizon/__init__.py 00015 # Desc: Horizon Python Module 00016 # 00017 # Copyright © 2010 Clearpath Robotics, Inc. 00018 # All Rights Reserved 00019 # 00020 # Redistribution and use in source and binary forms, with or without 00021 # modification, are permitted provided that the following conditions are met: 00022 # * Redistributions of source code must retain the above copyright 00023 # notice, this list of conditions and the following disclaimer. 00024 # * Redistributions in binary form must reproduce the above copyright 00025 # notice, this list of conditions and the following disclaimer in the 00026 # documentation and/or other materials provided with the distribution. 00027 # * Neither the name of Clearpath Robotics, Inc. nor the 00028 # names of its contributors may be used to endorse or promote products 00029 # derived from this software without specific prior written permission. 00030 # 00031 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00032 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00033 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00034 # ARE DISCLAIMED. IN NO EVENT SHALL CLEARPATH ROBOTICS, INC. BE LIABLE FOR ANY 00035 # DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 00036 # (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00037 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 00038 # ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 00039 # (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 00040 # SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 00041 # 00042 # Please send comments, questions, or patches to code@clearpathrobotics.com 00043 # 00044 00045 if __name__ == "__main__": 00046 print ("ERROR: clearpath.horizon is a module and can NOT be run"\ 00047 " as a script!\nFor a command-line interface demo of Horizon, run:"\ 00048 "\n python -m clearpath.horizon.demo\n") 00049 00050 import sys 00051 sys.exit(1) 00052 00053 00054 ## @package clearpath.horizon 00055 # Horizon Python Module 00056 # 00057 # Horizon Interface. 00058 # Supported Horizon version(s): 0.1 - 1.0 00059 # 00060 # @author Ryan Gariepy 00061 # @author Malcolm Robert 00062 # @author Michael Purvis 00063 # @date 14/01/10 00064 # @req clearpath.utils 00065 # clearpath.horizon.protocol 00066 # clearpath.horizon.transports 00067 # @version 1.0 00068 # 00069 # 00070 # @section HISTORY 00071 # Version 0.1 - 0.3 {Ryan Gariepy} 00072 # - Initial Creation as protocol_demo.py 00073 # 00074 # Version 0.4 {Malcolm Robert} 00075 # - Move to horizon.py 00076 # - Added logging 00077 # - Added version support 00078 # - Added Doxygen documentation 00079 # - Changed version scheme to match Horizon doc 00080 # - Horizon support for v0.4 messages 00081 # 00082 # Version 0.5 00083 # - Added TCP and UDP support 00084 # - Horizon support for v0.5 00085 # 00086 # Version 0.6 00087 # - Move to horizon package __init__.py 00088 # - Horizon support for v0.6 00089 # 00090 # Version 0.7 00091 # - Added Encryption Support 00092 # - Horizon support for v0.7 00093 # 00094 # Version 0.8 00095 # - Horizon support for v0.8 00096 # 00097 # Version 1.0 00098 # - Horizon support for v 0.1 - 1.0 00099 # - Python 2.6+ & 3.x compatible 00100 # 00101 00102 00103 # Required Clearpath Modules 00104 from .. import utils 00105 from . import protocol 00106 00107 # Required Python Modules 00108 import datetime # Date & Time Manipulation 00109 import logging # Logging Utilities 00110 import time # System Date & Time 00111 import inspect # For parameter comprehension in command decorators 00112 00113 __version__ = "1.0" 00114 __revision__ = "$Revision: 916 $" 00115 00116 logger = logging.getLogger('clearpath.horizon') 00117 """Horizon Module Log""" 00118 logger.setLevel(logging.DEBUG) 00119 logger.addHandler(utils.NullLoggingHandler()) 00120 logger.propagate = True 00121 logger.debug("Loading clearpath.horizon ...") 00122 00123 00124 00125 ## Horizon Interface. 00126 # 00127 # Interface for interaction over a transport using the Horizon protocol. 00128 # Contains direct 1-1 function mappings for commands and requests. 00129 # 00130 class Horizon(object): 00131 version = (1, 1) 00132 00133 ## Create a Horizon Interface. 00134 # 00135 # Constructor for the Horizon Interface class. 00136 # Performs the initial creation and initialization of the underlying 00137 # protocol and transport through instantiation. 00138 # Supports version auto-detection (will take place in open) by sending 00139 # a request for the platform information message. 00140 # 00141 # @param retries The number of times to retry sending a message 00142 # that received a timeout or checksum error 00143 # @param rec_timeout The time to wait for a data message after 00144 # sending a request, 0 - wait indefinitely 00145 # @param send_timeout The time to wait for an acknowledgment 00146 # in milliseconds, 0 - wait indefinitely 00147 # @param store_timeout The time to store an un-handled message for the 00148 # method get_waiting in milliseconds, 00149 # 0 - store indefinitely 00150 # @param transport The Transport class to use. 00151 # @param transport_args Dictionary of arguments to pass to the transport's 00152 # __init__ method. Do NOT include version or 00153 # store_timeout as these will be populated. 00154 # @throws LookupError If auto-detect version fails 00155 # @throws TransportError Upon transport creation/initialization failure 00156 # @throws ValueError From bad arguments 00157 # 00158 # @pydoc 00159 def __init__(self, transport = protocol.transports.Serial.autodetect, 00160 transport_args = {}, retries = 5, send_timeout = 50, 00161 rec_timeout = 100, store_timeout = 2000): 00162 00163 self._protocol = None 00164 self._protocol = protocol.Client(transport, transport_args, retries, 00165 send_timeout, rec_timeout, store_timeout) 00166 00167 def __str__(self): 00168 return str(self._protocol) 00169 00170 def __del__(self): 00171 self.close() 00172 00173 def open(self): 00174 if not self._protocol.is_open(): 00175 self._protocol.open() 00176 00177 # Get version from device 00178 firm = self.request_firmware_info() 00179 self.version = firm.version 00180 00181 def close(self): 00182 if self._protocol != None and self._protocol.is_open(): 00183 self._protocol.close() 00184 00185 00186 def acks(self, enabled): 00187 if enabled: 00188 self._protocol.acks = True 00189 else: 00190 self._protocol.acks = False 00191 00192 #-------------------------------- Safeties --------------------------------- 00193 00194 def emergency_stop(self): 00195 self._protocol.emergency_stop() 00196 00197 def reset(self): 00198 self.set_reset() 00199 00200 00201 #-------------------------------- Commands --------------------------------- 00202 00203 def set_platform_info(self, passcode = 0, model = '', revision = 0, serial = 0): 00204 self._protocol.command('platform_info', locals()) 00205 00206 def set_platform_name(self, name = 'Clearpath1'): 00207 self._protocol.command('platform_name', locals()) 00208 00209 def set_platform_time(self, time = 0): 00210 self._protocol.command('platform_time', locals()) 00211 00212 def set_platform_kinematics(self, passcode = 0, track = 0.0, wheelbase = 0.0): 00213 self._protocol.command('platform_kinematics', locals()) 00214 00215 def set_control_flags(self, passcode = 0, flags = 0x00000000): 00216 self._protocol.command('control_flags', locals()) 00217 00218 def set_safety_status(self, flags = 0x0000): 00219 self._protocol.command('safety_status', locals()) 00220 00221 def set_config(self, index=0, value=0.0): 00222 self._protocol.command('config', locals()) 00223 00224 def set_differential_speed(self, left_speed = 0.0, right_speed = 0.0, 00225 left_accel = 0.0, right_accel = 0.0): 00226 self._protocol.command('differential_speed', locals()) 00227 00228 def set_differential_current(self, left = 0.0, right = 0.0): 00229 self._protocol.command('differential_current', locals()) 00230 00231 def set_differential_control(self, left_p = 0.0, left_i = 0.0, left_d = 0.0, 00232 left_ffwd = 0.0, left_stic = 0.0, left_sat = 0.0, 00233 right_p = 0.0, right_i = 0.0, right_d = 0.0, right_ffwd = 0.0, 00234 right_stic = 0.0, right_sat = 0.0): 00235 self._protocol.command('differential_control', locals()) 00236 00237 def set_differential_current_control(self, left_p = 0.0, left_i = 0.0, left_d = 0.0, 00238 left_ffwd = 0.0, left_stic = 0.0, left_sat = 0.0, 00239 right_p = 0.0, right_i = 0.0, right_d = 0.0, right_ffwd = 0.0, 00240 right_stic = 0.0, right_sat = 0.0): 00241 self._protocol.command('differential_current_control', locals()) 00242 00243 def set_differential_output(self, left = 0.0, right = 0.0): 00244 self._protocol.command('differential_output', locals()) 00245 00246 def set_ackermann_output(self, steering = 0.0, throttle = 0.0, brake = 0.0): 00247 self._protocol.command('ackermann_output', locals()) 00248 00249 def set_velocity(self, trans = 0.0, rot = 0.0, accel = 0.0): 00250 self._protocol.command('velocity', locals()) 00251 00252 def set_turn(self, trans = 0.0, rad = 0.0, accel = 0.0): 00253 self._protocol.command('turn', locals()) 00254 00255 def set_max_speed(self, forward = 0.0, reverse = 0.0): 00256 self._protocol.command('max_speed', locals()) 00257 00258 def set_max_accel(self, forward = 0.0, reverse = 0.0): 00259 self._protocol.command('max_accel', locals()) 00260 00261 def set_gear(self, gear = 0): 00262 self._protocol.command('gear', locals()) 00263 00264 def set_gpadc_output(self, values = {0:0}): 00265 self._protocol.command('gpadc_output', locals()) 00266 00267 def set_gpio_direction(self, mask = 0, direction = 0): 00268 self._protocol.command('gpio_direction', locals()) 00269 00270 def set_gpio_output(self, mask = 0, output = 0): 00271 self._protocol.command('gpio_output', locals()) 00272 00273 def set_pan_tilt_zoom(self, mount = 0, pan = 0.0, tilt = 0.0, zoom = 1.0): 00274 self._protocol.command('pan_tilt_zoom', locals()) 00275 00276 def set_absolute_joint_position(self, angles = {0:0.0}): 00277 self._protocol.command('absolute_joint_position', locals()) 00278 00279 def set_relative_joint_position(self, angles = {0:0.0}): 00280 self._protocol.command('relative_joint_position', locals()) 00281 00282 def set_joint_control(self, joint = 0, p = 0.0, i = 0.0, d = 0.0, 00283 feed = 0.0, stiction = 0.0, limit = 0.0): 00284 self._protocol.command('joint_control', locals()) 00285 00286 def set_joint_homing(self, joint = 0): 00287 self._protocol.command('joint_homing', locals()) 00288 00289 def set_end_effector_position(self, x = 0.0, y = 0.0, z = 0.0): 00290 self._protocol.command('end_effector_position', locals()) 00291 00292 def set_end_effector_pose(self, x = 0.0, y = 0.0, z = 0.0, roll = 0.0, pitch = 0.0, yaw = 0.0): 00293 self._protocol.command('end_effector_pose', locals()) 00294 00295 def set_reset(self): 00296 self._protocol.command('reset', locals()) 00297 00298 def restore_system_config(self, passcode = 0x3A18, flags = 0x1): 00299 self._protocol.command('restore_system_config', locals()) 00300 00301 def store_system_config(self, passcode = 0x3A18): 00302 self._protocol.command('store_system_config', locals()) 00303 00304 def set_current_sensor_config(self, passcode = 0, offsets = [ 0.0 ], scales = [ 0.0 ]): 00305 self._protocol.command('current_sensor_config', locals()) 00306 00307 def set_voltage_sensor_config(self, passcode = 0, offsets = [ 0.0 ], scales = [ 0.0 ]): 00308 self._protocol.command('voltage_sensor_config', locals()) 00309 00310 def set_temperature_sensor_config(self, passcode = 0, offsets = [ 0.0 ], scales = [ 0.0 ]): 00311 self._protocol.command('temperature_sensor_config', locals()) 00312 00313 def set_orientation_sensor_config(self, passcode = 0, 00314 roll_offset = 0.0, roll_scale = 0.0, 00315 pitch_offset = 0.0, pitch_scale = 0.0, 00316 yaw_offset = 0.0, yaw_scale = 0.0): 00317 self._protocol.command('orientation_sensor_config', locals()) 00318 00319 def set_magnetometer_config(self, passcode = 0, 00320 x_offset = 0.0, x_scale = 0.0, 00321 y_offset = 0.0, y_scale = 0.0, 00322 z_offset = 0.0, z_scale = 0.0): 00323 self._protocol.command('magnetometer_config', locals()) 00324 00325 def set_gyro_config(self, passcode = 0, 00326 roll_offset = 0.0, roll_scale = 0.0, 00327 pitch_offset = 0.0, pitch_scale = 0.0, 00328 yaw_offset = 0.0, yaw_scale = 0.0): 00329 self._protocol.command('gyro_config', locals()) 00330 00331 def set_accelerometer_config(self, passcode = 0, 00332 x_offset = 0.0, x_scale = 0.0, 00333 y_offset = 0.0, y_scale = 0.0, 00334 z_offset = 0.0, z_scale = 0.0): 00335 self._protocol.command('accelerometer_config', locals()) 00336 00337 def set_encoders_config(self, ppr = [ 0.0 ], scales = [ 0.0 ]): 00338 self._protocol.command('encoders_config', locals()) 00339 00340 def set_battery_estimation_config(self, passcode = 0.0, offsets = [ 0.0 ], scales = [ 0.0 ]): 00341 self._protocol.command('battery_estimation_config', locals()) 00342 00343 00344 #-------------------------------- Requests --------------------------------- 00345 00346 def request_echo(self, subscription = 0): 00347 return self._protocol.request('echo', locals()) 00348 00349 def request_platform_info(self, subscription = 0): 00350 return self._protocol.request('platform_info', locals()) 00351 00352 def request_platform_name(self, subscription = 0): 00353 return self._protocol.request('platform_name', locals()) 00354 00355 def request_platform_kinematics(self, subscription = 0): 00356 return self._protocol.request('platform_kinematics', locals()) 00357 00358 def request_platform_kinematics(self, subscription = 0): 00359 return self._protocol.request('platform_kinematics', locals()) 00360 00361 def request_firmware_info(self, subscription = 0): 00362 return self._protocol.request('firmware_info', locals()) 00363 00364 def request_control_flags(self, subscription = 0): 00365 return self._protocol.request('control_flags', locals()) 00366 00367 def request_system_status(self, subscription = 0): 00368 return self._protocol.request('system_status', locals()) 00369 00370 def request_processor_status(self, subscription = 0): 00371 return self._protocol.request('processor_status', locals()) 00372 00373 def request_power_status(self, subscription = 0): 00374 return self._protocol.request('power_status', locals()) 00375 00376 def request_safety_status(self, subscription = 0): 00377 return self._protocol.request('safety_status', locals()) 00378 00379 def request_config(self, index=0): 00380 return self._protocol.request('config', locals()) 00381 00382 def request_differential_speed(self, subscription = 0): 00383 return self._protocol.request('differential_speed', locals()) 00384 00385 def request_differential_control(self, subscription = 0): 00386 return self._protocol.request('differential_control', locals()) 00387 00388 def request_differential_current(self, subscription = 0): 00389 return self._protocol.request('differential_current', locals()) 00390 00391 def request_differential_current_control(self, subscription = 0): 00392 return self._protocol.request('differential_current_control', locals()) 00393 00394 def request_differential_output(self, subscription = 0): 00395 return self._protocol.request('differential_output', locals()) 00396 00397 def request_ackermann_output(self, subscription = 0): 00398 return self._protocol.request('ackermann_output', locals()) 00399 00400 def request_velocity(self, subscription = 0): 00401 return self._protocol.request('velocity', locals()) 00402 00403 def request_turn(self, subscription = 0): 00404 return self._protocol.request('turn', locals()) 00405 00406 def request_max_speed(self, subscription = 0): 00407 return self._protocol.request('max_speed', locals()) 00408 00409 def request_max_accel(self, subscription = 0): 00410 return self._protocol.request('max_accel', locals()) 00411 00412 def request_gear_status(self, subscription = 0): 00413 return self._protocol.request('gear_status', locals()) 00414 00415 def request_gpadc_output(self, subscription = 0, channel=0): 00416 return self._protocol.request('gpadc_output', locals()) 00417 00418 def request_gpio(self, subscription = 0): 00419 return self._protocol.request('gpio', locals()) 00420 00421 def request_gpadc_input(self, subscription = 0): 00422 return self._protocol.request('gpadc_input', locals()) 00423 00424 def request_pan_tilt_zoom(self, mount = 0, subscription = 0): 00425 return self._protocol.request('pan_tilt_zoom', locals()) 00426 00427 def request_distance(self, subscription = 0): 00428 return self._protocol.request('distance', locals()) 00429 00430 def request_distance_timing(self, subscription = 0): 00431 return self._protocol.request('distance_timing', locals()) 00432 00433 def request_platform_orientation(self, subscription = 0): 00434 return self._protocol.request('platform_orientation', locals()) 00435 00436 def request_platform_rotation(self, subscription = 0): 00437 return self._protocol.request('platform_rotation', locals()) 00438 00439 def request_platform_acceleration(self, subscription = 0): 00440 return self._protocol.request('platform_acceleration', locals()) 00441 00442 def request_platform_6axis(self, subscription = 0): 00443 return self._protocol.request('platform_6axis', locals()) 00444 00445 def request_platform_6axis_orientation(self, subscription = 0): 00446 return self._protocol.request('platform_6axis_orientation', locals()) 00447 00448 def request_platform_magnetometer(self, subscription = 0): 00449 return self._protocol.request('platform_magnetometer', locals()) 00450 00451 def request_encoders(self, subscription = 0): 00452 return self._protocol.request('encoders', locals()) 00453 00454 def request_raw_encoders(self, subscription = 0): 00455 return self._protocol.request('raw_encoders', locals()) 00456 00457 def request_encoders_config(self, subscription = 0): 00458 return self._protocol.request('encoders_config', locals()) 00459 00460 def request_absolute_joint_position(self, subscription = 0): 00461 return self._protocol.request('absolute_joint_position', locals()) 00462 00463 def request_relative_joint_position(self, subscription = 0): 00464 return self._protocol.request('relative_joint_position', locals()) 00465 00466 def request_joint_control(self, joint = 0, subscription = 0): 00467 return self._protocol.request('joint_control', locals()) 00468 00469 def request_joint_homing_status(self, subscription = 0): 00470 return self._protocol.request('joint_homing_status', locals()) 00471 00472 def request_joint_torques(self, subscription = 0): 00473 return self._protocol.request('joint_torques', locals()) 00474 00475 def request_end_effector_position(self, subscription = 0): 00476 return self._protocol.request('end_effector_position', locals()) 00477 00478 def request_end_effector_pose(self, subscription = 0): 00479 return self._protocol.request('end_effector_pose', locals()) 00480 00481 def request_end_effector_orientation(self, subscription = 0): 00482 return self._protocol.request('end_effector_orientation', locals()) 00483 00484 def request_current_sensor_config(self, subscription = 0): 00485 return self._protocol.request('current_sensor_config', locals()) 00486 00487 def request_voltage_sensor_config(self, subscription = 0): 00488 return self._protocol.request('voltage_sensor_config', locals()) 00489 00490 def request_temperature_sensor_config(self, subscription = 0): 00491 return self._protocol.request('temperature_sensor_config', locals()) 00492 00493 def request_orientation_sensor_config(self, subscription = 0): 00494 return self._protocol.request('orientation_sensor_config', locals()) 00495 00496 def request_magnetometer_config(self, subscription = 0): 00497 return self._protocol.request('magnetometer_config', locals()) 00498 00499 def request_gyro_config(self, subscription = 0): 00500 return self._protocol.request('gyro_config', locals()) 00501 00502 def request_battery_estimation_config(self, subscription = 0): 00503 return self._protocol.request('battery_estimation_config', locals()) 00504 00505 def request_accelerometer_config(self, subscription = 0): 00506 return self._protocol.request('accelerometer_config', locals()) 00507 00508 def request_raw_current_sensor(self, subscription = 0): 00509 return self._protocol.request('raw_current_sensor', locals()) 00510 00511 def request_raw_voltage_sensor(self, subscription = 0): 00512 return self._protocol.request('raw_voltage_sensor', locals()) 00513 00514 def request_raw_temperature_sensor(self, subscription = 0): 00515 return self._protocol.request('raw_temperature_sensor', locals()) 00516 00517 def request_raw_orientation_sensor(self, subscription = 0): 00518 return self._protocol.request('raw_orientation_sensor', locals()) 00519 00520 def request_raw_magnetometer(self, subscription = 0): 00521 return self._protocol.request('raw_magnetometer', locals()) 00522 00523 def request_raw_gyro(self, subscription = 0): 00524 return self._protocol.request('raw_gyro', locals()) 00525 00526 def request_raw_accelerometer(self, subscription = 0): 00527 return self._protocol.request('raw_accelerometer', locals()) 00528 00529 00530 #------------------------------ Subscriptions ------------------------------ 00531 00532 00533 ## Add Subscription Data Handler 00534 # 00535 # Adds a data subscription handler to be called when data is received. 00536 # Asynchronous method of getting subscription Data. 00537 # 00538 # @param backtrack Call the new handler with any waiting data? 00539 # @param request The name of the request data to handle, ie 'platform_info' 00540 # If None then it returns all subscription data. 00541 # @param handler The Message Handler. 00542 # Must have three parameters: 00543 # str name, 00544 # Payload payload, 00545 # long timestamp 00546 # 00547 def add_handler(self, handler, backtrack = False, request = None): 00548 self._protocol.add_handler(handler, backtrack, request) 00549 00550 00551 ## Remove Subscription Data Handler 00552 # 00553 # Removes a data subscription handler. 00554 # 00555 # @param handler The Handler to remove. 00556 # If None, remove all handlers. 00557 # @param request The name of the requested data. 00558 # 00559 def remove_handler(self, handler = None, request = None): 00560 self._protocol.remove_handler(handler, request) 00561 00562 00563 ## Get Waiting Data 00564 # 00565 # Returns payload(s) from any waiting messages. 00566 # Synchronous method of getting subscription Data. 00567 # 00568 # @param request The name of the requested data. 00569 # If None then it returns all subscription data. 00570 # @return list of tuple(name,payload,timestamp), empty if no waiting data. 00571 # Invalid messages are returned as payloads.Null. 00572 # 00573 def get_waiting_data(self, request = None): 00574 return self._protocol.get_waiting(request) 00575 00576 00577 #------------------------------- Properties -------------------------------- 00578 00579 00580 ## Horizon Device Open? 00581 # 00582 # @return is the horizon device open? 00583 # 00584 def is_open(self): 00585 if self._protocol.is_open() == False: 00586 self.close() 00587 return False 00588 return True 00589 00590 00591 ## Horizon Device Alive? 00592 # 00593 # @return is the horizon device alive? 00594 # 00595 def is_alive(self): 00596 # Echo 00597 try: 00598 self.request_echo() 00599 return True 00600 except Exception: 00601 return False 00602 00603 00604 ## Get Device Time 00605 # 00606 # Note that the time returned has a delay from transmission. 00607 # 00608 # @return device time in milliseconds 00609 # 00610 def get_device_time(self): 00611 # Get Time 00612 # TODO: Move this to protocol.py 00613 self.request_echo() 00614 return self._protocol._received[2] 00615 00616 00617 ## Get Program Start Time 00618 # 00619 # @return program start time in milliseconds as stored in Transport 00620 # 00621 def get_start_time(self): 00622 return self._protocol.start_time 00623 00624 00625 # Class Properties 00626 alive = property(fget=is_alive, doc="Horizon Device Alive") 00627 device_time = property(fget=get_device_time, doc="Horizon Device Time") 00628 opened = property(fget=is_open, doc="Horizon Device Open") 00629 start_time = property(fget=get_start_time, doc="Horizon Start Time")