diff --git a/docs/examples/vehicle_state.rst b/docs/examples/vehicle_state.rst index 64a367f39..78a9b0bb4 100644 --- a/docs/examples/vehicle_state.rst +++ b/docs/examples/vehicle_state.rst @@ -95,23 +95,46 @@ In summary, after cloning the repository: Home location: LocationGlobal:lat=-35.3632621765,lon=149.165237427,alt=583.989990234 - Set new home location - New Home Location (from attribute - altitude should be 222): LocationGlobal:lat=-35.363261,lon=149.1652299,alt=222 - New Home Location (from vehicle - altitude should be 222): LocationGlobal:lat=-35.3632621765,lon=149.165237427,alt=222.0 - - Set Vehicle.mode=GUIDED (currently: STABILIZE) - Waiting for mode change ... - - Set Vehicle.armed=True (currently: False) - Waiting for arming... - Waiting for arming... - Waiting for arming... - >>> ARMING MOTORS - >>> GROUND START - Waiting for arming... - Waiting for arming... - >>> Initialising APM... - Vehicle is armed: True + Set new home location using synchronous function (returns when value confirmed changed) + New Home Location (altitude should be 222): LocationGlobal:lat=-35.3632621765,lon=149.165237427,alt=222.0 + + Set new home location using asynchronous function (returns immediately) + New Home Location (from vehicle - should be 333.0): LocationGlobal:lat=-35.3632621765,lon=149.165237427,alt=333.0 + + Set Vehicle mode to GUIDED using synchronous setter (currently: STABILIZE) + New mode: GUIDED + + Set Vehicle mode to STABILIZE using synchronous setter and 'mode string' (currently: GUIDED) + New mode: STABILIZE + + Set Vehicle.mode = GUIDED using asynchronous setter (currently: STABILIZE) + Waiting for mode change... + Waiting for mode change... + Waiting for mode change... + Waiting for mode change... + New mode: GUIDED + + Send arm message and return when value changed (currently: False) + >>> ARMING MOTORS + >>> GROUND START + >>> Initialising APM... + Vehicle is armed: True + + Send disarm message and return when value changed (currently: True) + >>> DISARMING MOTORS + Vehicle is armed: False + + Send arm message and poll in loop for value to change (currently: False) + Waiting for arming... + >>> ARMING MOTORS + Waiting for arming... + Waiting for arming... + Waiting for arming... + Vehicle is armed: True + + Send 'set target groundspeed' message (currently: 0.0) + + Set 'set target airspeed' message (currently: 0.0) Add `attitude` attribute callback/observer on `vehicle` Wait 2s so callback invoked before observer removed diff --git a/docs/guide/vehicle_state_and_parameters.rst b/docs/guide/vehicle_state_and_parameters.rst index 1bb23ddde..2cbf21dd9 100644 --- a/docs/guide/vehicle_state_and_parameters.rst +++ b/docs/guide/vehicle_state_and_parameters.rst @@ -79,8 +79,6 @@ regularly updated from MAVLink messages sent by the vehicle). print "Attitude: %s" % vehicle.attitude print "Velocity: %s" % vehicle.velocity print "GPS: %s" % vehicle.gps_0 - print "Groundspeed: %s" % vehicle.groundspeed - print "Airspeed: %s" % vehicle.airspeed print "Gimbal status: %s" % vehicle.gimbal print "Battery: %s" % vehicle.battery print "EKF OK?: %s" % vehicle.ekf_ok @@ -91,6 +89,8 @@ regularly updated from MAVLink messages sent by the vehicle). print "Heading: %s" % vehicle.heading print "Is Armable?: %s" % vehicle.is_armable print "System status: %s" % vehicle.system_status.state + print "Groundspeed: %s" % vehicle.groundspeed # settable + print "Airspeed: %s" % vehicle.airspeed # settable print "Mode: %s" % vehicle.mode.name # settable print "Armed: %s" % vehicle.armed # settable @@ -119,39 +119,76 @@ regularly updated from MAVLink messages sent by the vehicle). Setting attributes ------------------ -The :py:attr:`Vehicle.mode `, :py:attr:`Vehicle.armed ` -, :py:attr:`Vehicle.airspeed ` and :py:attr:`Vehicle.groundspeed `, -attributes can all be "directly" written (:py:attr:`Vehicle.home_location ` can also be directly written, +The :py:attr:`Vehicle.mode `, :py:attr:`Vehicle.armed `, +:py:attr:`Vehicle.airspeed ` and :py:attr:`Vehicle.groundspeed `, +attributes can all be written using setter functions (:py:attr:`Vehicle.home_location ` can also be written, but has special considerations that are :ref:`discussed below `). -These attributes are set by assigning a value: +The setter functions generally take two forms: -.. code:: python +* Setters with the name prefix ``set_`` simply send the associated MAVLink message to set the attribute and then return. + These include: :py:func:`set_mode() `, :py:func:`set_armed() `, + :py:func:`set_home_location() `, :py:func:`set_target_groundspeed() `, + :py:func:`set_target_airspeed() `. +* Setters with the name prefix ``sync_set_`` are "synchronous" - they send the message (with retries) and + either return when the value has changed or raise an exception. These include: :py:func:`sync_set_armed() `, + :py:func:`sync_set_mode() `, :py:func:`sync_set_home_location() `. + + .. note:: - #disarm the vehicle - vehicle.armed = False - - #set the default groundspeed to be used in movement commands - vehicle.groundspeed = 3.2 + Not every setter has a ``sync_set_`` variant. For example, we could not create ``set_sync_target_airspeed()`` because + there is no reliable way to check whether the message has been received. +.. warning:: -Commands to change a value are **not guaranteed to succeed** (or even to be received) and code should be written with this in mind. -For example, the code snippet below polls the attribute values to confirm they have changed before proceeding. + It is also possible to set the value of most of the *settable attributes* by directly assigning a value to the attribute itself. + This form is deprecated because it creates the incorrect impression for developers that the write operation must succeed, and confusion + when a re-read value does not match a just-set value. This feature will be removed in a future version. + +Using the synchronous version is often preferred because the methods are guaranteed to succeed or fail in an obvious way. +Commands to change a value are **not guaranteed to succeed** (or even to be received) so if you use the asynchronous version +you may have to write your own code to check for success. On the other hand, the ``set_`` methods are more flexible, and are useful +for developers who prefer to set values and use observers to drive the program flow. + + +The code snippet below shows the use of the synchronous functions: .. code:: python + + # Set mode using synchronous function + vehicle.sync_set_mode(VehicleMode("GUIDED")) + print " New mode: %s" % vehicle.mode.name - vehicle.mode = VehicleMode("GUIDED") - vehicle.armed = True - while not vehicle.mode.name=='GUIDED' and not vehicle.armed and not api.exit: - print " Getting ready to take off ..." + # Check that vehicle is armable (required) + while not vehicle.is_armable: + print " Waiting for vehicle to initialise..." time.sleep(1) + # If required, you can provide additional information about initialisation + # using `vehicle.gps_0.fix_type` and `vehicle.mode.name`. + + # Arm the vehicle (return when armed) + vehicle.sync_set_armed() #returns when armed. + +The code snippet below shows a similar use of the ``set_`` functions: -.. note:: +.. code:: python + + # Check that vehicle is armable (required) + while not vehicle.is_armable: + print " Waiting for vehicle to initialise..." + time.sleep(1) - While the autopilot does send information about the success (or failure) of the request, - this is `not currently handled by DroneKit `_. + #set mode and armed at same time + vehicle.set_mode(VehicleMode("GUIDED")) + vehicle.set_armed() -:py:attr:`Vehicle.gimbal ` can't be written directly, but the gimbal can be controlled using the + while not vehicle.armed: + print " Waiting for arming..." + time.sleep(0.3) + #vehicle not armed. + + +The gimbal (:py:attr:`Vehicle.gimbal `) can be controlled using the :py:func:`Vehicle.gimbal.rotate() ` and :py:func:`Vehicle.gimbal.target_location() ` methods. The first method lets you set the precise orientation of the gimbal while the second makes the gimbal track a specific "region of interest". @@ -312,21 +349,21 @@ waypoints is set relative to this position. # We have a home location. print "\n Home location: %s" % vehicle.home_location -* The attribute can be *set* to a :py:class:`LocationGlobal ` object - (the code fragment below sets it to the current location): +* The home location can be *set* to a :py:class:`LocationGlobal ` object using + :py:attr:`Vehicle.set_home_location ` or + :py:attr:`Vehicle.sync_set_home_location `. + + Both variants require that the home location have previously been read as shown above and the write will + fail if the new location is not within 50 km of the EKF origin. + + The main difference is that the ``sync_set`` variant re-downloads the home location in order to verify that + the value actually changed. This is more "robust" and a lot easier to use, but can take a long time to complete: .. code:: python - vehicle.home_location=vehicle.location.global_frame - - There are some caveats: - - * You must be able to read a non-``None`` value before you can write it - (the autopilot has to set the value initially before it can be written or read). - * The new location must be within 50 km of the EKF origin or setting the value will silently fail. - * The value is cached in the ``home_location``. If the variable can potentially change on the vehicle - you will need to re-download the ``Vehicle.commands`` in order to confirm the value. - + # Set the home location to the current location + vehicle.sync_set_home_location(vehicle.location.global_frame) + * The attribute is not observable. @@ -339,6 +376,7 @@ waypoints is set relative to this position. We hope to improve this attribute in later versions of ArduPilot, where there may be specific commands to get the home location from the vehicle. + .. _vehicle_state_parameters: @@ -451,9 +489,6 @@ for "any parameter") using the vehicle.parameters.add_attribute_listener('*', any_parameter_callback) - - - .. _api-information-known-issues: Known issues diff --git a/dronekit/__init__.py b/dronekit/__init__.py index 3bf612108..681195704 100644 --- a/dronekit/__init__.py +++ b/dronekit/__init__.py @@ -1530,7 +1530,23 @@ def _is_mode_available(self, mode_code): @property def mode(self): """ - This attribute is used to get and set the current flight mode (:py:class:`VehicleMode`). + This attribute is used to get the current vehicle mode (:py:class:`VehicleMode`). + + .. code:: python + + # Print the vehicle mode + print "Mode: %s" % vehicle.mode + + # Print the vehicle mode name + print "Mode name: %s" % vehicle.mode.name + + The value of the attribute can be changed using :py:func:`sync_set_mode` or + :py:func:`set_mode`. + + .. warning:: + + This attribute can also be used to directly *set* the mode. + This approach is deprecated, and may be removed in a future version. """ if not self._flightmode: return None @@ -1539,6 +1555,84 @@ def mode(self): @mode.setter def mode(self, v): self._master.set_mode(self._mode_mapping[v.name]) + + + def set_mode(self, value): + """ + Send a message to attempt to change the vehicle mode and return immediately (without checking the result). + + .. warning:: + + It is possible for the message to be lost or ignored by the connected vehicle. + If using this method you may need to explicitly check that the mode has changed. + + .. tip:: + + Use :py:func:`sync_set_mode` to robustly wait for the mode to change before continuing. + + The message is not sent if the target mode is the current mode. + + :param VehicleMode value: The target :py:class:`VehicleMode` (or mode name, as a string). + """ + # Allow users to specify the target mode as a string. + if type(value)==str: + value=VehicleMode(value) + # Return immediately if target value is current value. + if value.name == self.mode.name: + return + + #If method is non waiting send command immediately. + self._master.set_mode(self._mode_mapping[value.name]) + + + def sync_set_mode(self, value, retries=2, timeout=3): + """ + Send a message to change the vehicle mode and synchronously wait for success. + + The API should primarily be used as shown below: + + .. code-block:: python + + # Set the mode using a VehicleMode + vehicle.sync_set_mode(VehicleMode("GUIDED")) + + # Set the mode using a string + vehicle.sync_set_mode("STABILIZE") + + The method will send a message (with retries) to set the new mode + and will either return when the :py:attr:`mode` has changed or raise an exception + on failure. You can also set the number of retries and the timeout + between re-sending the message, if needed. + + The function will return immediately if the new value is the same as the current value. + + .. tip:: + + The :py:func:`set_mode` method should be used if you don't want to synchronously wait for the mode change. + + :param VehicleMode value: The new :py:class:`VehicleMode` (or mode name, as a string). + :param int retries: Number of attempts to resend the message. + :param int timeout: Time to wait for the value to change before retrying/exiting (in seconds). + """ + # Allow users to specify the target mode as a string. + if type(value)==str: + value=VehicleMode(value) + # Return immediately if target value is current value. + if value.name == self.mode.name: + return + + #Otherwise execute retry code + for retry_num in range(0,retries): + self._master.set_mode(self._mode_mapping[value.name]) + start_time=time.time() + while time.time()-start_time <= timeout: + if value.name == self.mode.name: + return + time.sleep(0.1) + + #No more retries. Raise exception. + raise APIException('Unable to change mode.') + @property def location(self): @@ -1660,20 +1754,19 @@ def gps_0(self): @property def armed(self): """ - This attribute can be used to get and set the ``armed`` state of the vehicle (``boolean``). - - The code below shows how to read the state, and to arm/disarm the vehicle: + This attribute can be used to get the ``armed`` state of the vehicle (``boolean``). .. code:: python # Print the armed state for the vehicle print "Armed: %s" % vehicle.armed + + To arm/disarm the vehicle use :py:func:`sync_set_armed` or :py:func:`set_armed`. - # Disarm the vehicle - vehicle.armed = False - - # Arm the vehicle - vehicle.armed = True + .. warning:: + + The attribute can also be used to *set* the armed state. + This is deprecated, and may be removed in a future version. """ return self._armed @@ -1684,11 +1777,102 @@ def armed(self, value): self._master.arducopter_arm() else: self._master.arducopter_disarm() + + + def set_armed(self, value=True): + """ + Send a message to attempt to change the :py:attr:`armed` state (armed/disarmed) of the vehicle and then return immediately (without checking the result). + + .. warning:: + + It is possible for the message to be lost or ignored by the connected vehicle. + If using this method you may need to explicitly check that the armed state has changed. + + .. tip:: + + Use :py:func:`sync_set_armed` to synchronously wait for the armed state to change before continuing. + + The message is not sent if the target armed state is the current state. The method will raise an exception + if called to arm the vehicle when it is not armable (see :py:attr:`is_armable`). + + :param Bool value: ``True`` (default) to arm, ``False`` to disarm. + """ + # Return immediately if target value is current value. + if bool(value) == self._armed: + return + + # Raise exception if attempting to arm when not armable. + if self._armed==False and not self.is_armable and bool(value)==True: + raise APIException('Attempting to arm when not armable.') + + #Send arm or disarm command then return. + if value: + self._master.arducopter_arm() + else: + self._master.arducopter_disarm() + + + + + + def sync_set_armed(self, value=True, wait_ready=True, retries=2, timeout=3): + """ + Send a message to arm (default) or disarm the vehicle and synchronously wait for success. + + The API should primarily be used as shown below: + + .. code-block:: python + + # Arm the vehicle (first checking it is armable) + if vehicle.is_armable: //Required! + vehicle.sync_set_armed() #returns when armed + + # Disarm the vehicle + vehicle.sync_set_armed(value=False) #returns when disarmed + + The method will send a message (with retries) to arm/disarm + the vehicle and will either return when the :py:attr:`armed` state has changed or + raise an exception on failure. You can also set the number of retries and the timeout + between re-sending the message, if needed. + + The function will return immediately if the new value is the same as the current value. + The function will raise an exception if called to arm a vehicle that is not + armable (see :py:attr:`is_armable`). + + + :param Bool value: ``True`` (default) to arm, ``False`` to disarm. + :param int retries: Number of attempts to resend the message. + :param int timeout: Time to wait for the value to change before retrying/exiting (in seconds). + """ + # Return immediately if target value is current value. + if bool(value) == self._armed: + return + + # Raise exception if attempting to arm when not armable. + if self._armed==False and not self.is_armable and bool(value)==True: + raise APIException('Attempting to arm when not armable.') + + #Execute retry code + for retry_num in range(0,retries): + if value: + self._master.arducopter_arm() + else: + self._master.arducopter_disarm() + start_time=time.time() + while time.time()-start_time <= timeout: + if bool(value) == self._armed: + return + time.sleep(0.1) + + #No more retries. Raise exception. + raise APIException('Unable to arm.') + + @property def is_armable(self): """ - Returns ``True`` if the vehicle is ready to arm, false otherwise (``Boolean``). + Returns ``True`` if the vehicle is ready to :py:attr:`arm `, ``false`` otherwise (``Boolean``). This attribute wraps a number of pre-arm checks, ensuring that the vehicle has booted, has a good GPS fix, and that the EKF pre-arm is complete. @@ -1738,9 +1922,12 @@ def groundspeed(self): """ Current groundspeed in metres/second (``double``). - This attribute is settable. The set value is the default target groundspeed - when moving the vehicle using :py:func:`simple_goto` (or other position-based - movement commands). + To set the groundspeed use :py:func:`set_target_groundspeed`. + + .. warning:: + + The ability to directly set the airspeed using this attribute + is deprecated, and may be removed in a future version. """ return self._groundspeed @@ -1759,15 +1946,58 @@ def groundspeed(self, speed): # send command to vehicle self.send_mavlink(msg) + + def set_target_groundspeed(self, speed): + """ + Send a message to change the target vehicle :py:attr:`groundspeed` and return immediately (without checking the result). + + The set value is the default target speed when moving the vehicle using :py:func:`simple_goto` + (or other position-based movement commands). + + The API should be used as shown below: + + .. code-block:: python + + # Set the speed + vehicle.set_target_groundspeed(5) + + .. warning:: + + It is possible for the message to be lost or ignored by the connected vehicle. + If using this method you may need to explicitly check that the speed has changed. + + .. note:: + + We do not provide a synchronous setter that confirms successful update of the groundspeed value. + This is because there is no robust way to trust the COMMAND_ACK and currently no method + to read back the current speed setting: https://github.com/diydrones/ardupilot/issues/3636 + + :param float speed: The target speed. + """ + speed_type = 1 # ground speed + msg = self.message_factory.command_long_encode( + 0, 0, # target system, target component + mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, #command + 0, #confirmation + speed_type, #param 1 + speed, # speed in metres/second + -1, 0, 0, 0, 0 #param 3 - 7 + ) + + self.send_mavlink(msg) + @property def airspeed(self): """ Current airspeed in metres/second (``double``). - - This attribute is settable. The set value is the default target airspeed - when moving the vehicle using :py:func:`simple_goto` (or other position-based - movement commands). + + To set the airspeed use :py:func:`set_target_airspeed`. + + .. warning:: + + The ability to directly set the airspeed using this attribute + is deprecated, and may be removed in a future version. """ return self._airspeed @@ -1785,6 +2015,48 @@ def airspeed(self, speed): # send command to vehicle self.send_mavlink(msg) + + + def set_target_airspeed(self, speed): + """ + Send a message to change the target vehicle :py:attr:`airspeed` and return immediately (without checking the result). + + The set value is the default target speed when moving the vehicle using :py:func:`simple_goto` + (or other position-based movement commands). + + The API should be used as shown below: + + .. code-block:: python + + # Set the speed + vehicle.set_target_airspeed(5) + + .. warning:: + + It is possible for the message to be lost or ignored by the connected vehicle. + If using this method you may need to explicitly check that the speed has changed. + + .. note:: + + We do not provide a synchronous setter that confirms successful update of the airspeed value. + This is because there is no robust way to trust the COMMAND_ACK and currently no method + to read back the current speed setting: https://github.com/diydrones/ardupilot/issues/3636 + + :param float speed: The target speed. + """ + speed_type = 0 # air speed + msg = self.message_factory.command_long_encode( + 0, 0, # target system, target component + mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, #command + 0, #confirmation + speed_type, #param 1 + speed, # speed in metres/second + -1, 0, 0, 0, 0 #param 3 - 7 + ) + + self.send_mavlink(msg) + + @property def gimbal(self): @@ -1866,16 +2138,18 @@ def home_location(self): home = vehicle.home_location The ``home_location`` is not observable. - - The attribute can be written (in the same way as any other attribute) after it has successfully - been populated from the vehicle. The value sent to the vehicle is cached in the attribute - (and can potentially get out of date if you don't re-download ``Vehicle.commands``): - + + The attribute can be written using :py:func:`sync_set_home_location` or :py:func:`set_home_location` + *after* it has successfully been populated from the vehicle. + .. warning:: - - Setting the value will fail silently if the specified location is more than 50km from the EKF origin. - - + + This setter is deprecated. Instead use :py:func:`sync_set_home_location` or :py:func:`set_home_location`. + + If you use this method the value sent to the vehicle is cached in the attribute + (and can potentially get out of date if you don't re-download ``Vehicle.commands``): + + Setting the value with this attribute will fail silently if the specified location is more than 50km from the EKF origin. """ return copy.copy(self._home_location) @@ -1890,10 +2164,14 @@ def home_location(self, pos): .. note:: Setting the value will fail silently if the specified location is more than 50km from the EKF origin. + + .. warning:: + + This setter is deprecated. Instead use :py:func:`sync_set_home_location` or :py:func:`set_home_location`. """ if not isinstance(pos, LocationGlobal): - raise Exception('Excepting home_location to be set to a LocationGlobal.') + raise Exception('Expecting home_location to be set to a LocationGlobal.') # Set cached home location. self._home_location = copy.copy(pos) @@ -1906,6 +2184,113 @@ def home_location(self, pos): 2, # param 1: 1 to use current position, 2 to use the entered values. 0, 0, 0, # params 2-4 pos.lat, pos.lon, pos.alt)) + + + def set_home_location(self, pos): + """ + Sends a message to attempt to set the home location (``LocationGlobal``) and returns immediately (without checking for success). + + Setting the value can fail silently: + + * The value cannot be set until after the autopilot has first set the value (on getting GPS). + * The value cannot be set until after it has successfully been read from the vehicle. + * Setting the value will silently fail if the target location is more than 50km from the EKF origin. + + The method will raise an exception if it is called with anything other than a ``LocationGlobal``. + + It should called as shown below (this example re-downloads the home location so you can verify the value has changed): + + .. code-block:: python + + a_location = LocationGlobal(-34.364114, 149.166022, 30) + # Set home location + vehicle.set_home_location(a_location) #Returns immediately + + # Get new value of home location by re-downloading commands + cmds = vehicle.commands + cmds.download() + cmds.wait_ready() + print " New Home Location (from vehicle): %s" % vehicle.home_location + + .. tip:: + + The :py:func:`sync_set_home_location` method can be use to synchronously set the home location and then + return when the value change is confirmed. This method can take a long time to complete + if the autopilot has a large mission (On ArduPilot the home_location is stored in the mission data). + By contrast, this method is fast, but can silently fail. + + :param LocationGlobal pos: The `LocationGlobal` to set as home location. + """ + + if not isinstance(pos, LocationGlobal): + raise Exception('Expecting home_location to be set to a LocationGlobal.') + + # Send MAVLink update. + self.send_mavlink(self.message_factory.command_long_encode( + 0, 0, # target system, target component + mavutil.mavlink.MAV_CMD_DO_SET_HOME, # command + 0, # confirmation + 2, # param 1: 1 to use current position, 2 to use the entered values. + 0, 0, 0, # params 2-4 + pos.lat, pos.lon, pos.alt)) + + + + + def sync_set_home_location(self, pos, wait_ready=True): + """ + Sends a message to attempt to set the :py:attr:`home_location` and returns once the value has changed (or raises an exception). + + .. warning:: + + * The home location must already have been downloaded from the vehicle before this method is called. + * The method re-downloads the home location to verify the value has changed (note - not that it matches the set value!) + This can be a long-running operation if the autopilot has a large mission + (on ArduPilot the home location is stored as part of the mission data.) + + The method will raise an exception if it is called with anything other than a ``LocationGlobal`` or if the + value is not detected as having changed. Possible reasons for failure include: + + * Home location cannot be set until after the autopilot has first set the value (on getting GPS). + * Home location cannot be set using this method until after it has successfully been read from the vehicle. + * Home location must be within 50km of the EKF origin. + + The method can be called as shown: + + .. code-block:: python + + ... + #The home_location must already have been read at least once before calling this method + ... + + a_location = LocationGlobal(-34.364114, 149.166022, 30) + vehicle.sync_set_home_location(a_location) #Returns if home_location value has changed + + :param LocationGlobal pos: The `LocationGlobal` to set as home location. + """ + + if not isinstance(pos, LocationGlobal): + raise Exception('Expecting home_location to be set to a LocationGlobal.') + + # Send MAVLink update. + self.send_mavlink(self.message_factory.command_long_encode( + 0, 0, # target system, target component + mavutil.mavlink.MAV_CMD_DO_SET_HOME, # command + 0, # confirmation + 2, # param 1: 1 to use current position, 2 to use the entered values. + 0, 0, 0, # params 2-4 + pos.lat, pos.lon, pos.alt)) + + old_home_location=self.home_location + cmds = self.commands + cmds.download() + cmds.wait_ready() + # Test that home location has changed for success. + # Would be better to test that new home location is same as pos + # but that is subject to rounding errors so direct comparion difficult. + if old_home_location==self.home_location: + raise Exception('Setting home location failed. Can only be called after home first set by GPS.') + @property def commands(self): diff --git a/dronekit/test/sitl/test_110.py b/dronekit/test/sitl/test_110.py index 8386ba0b2..3c70ca59d 100644 --- a/dronekit/test/sitl/test_110.py +++ b/dronekit/test/sitl/test_110.py @@ -20,7 +20,7 @@ def test_110(connpath): wait_for(lambda : vehicle.is_armable, 60) # Change the vehicle into STABILIZE mode - vehicle.mode = VehicleMode("GUIDED") + vehicle.set_mode(VehicleMode("GUIDED")) # NOTE wait crudely for ACK on mode update time.sleep(3) @@ -40,7 +40,7 @@ def armed_callback(vehicle, attribute, value): vehicle.add_attribute_listener('armed', armed_callback) # arm and see update. - vehicle.armed = True + vehicle.set_armed() # Wait for ACK. wait_for(lambda : armed_callback.called, 10) @@ -58,7 +58,7 @@ def armed_callback(vehicle, attribute, value): callcount = armed_callback.called # Disarm and see update. - vehicle.armed = False + vehicle.set_armed(False) # Wait for ack time.sleep(3) diff --git a/dronekit/test/sitl/test_115.py b/dronekit/test/sitl/test_115.py index 28f4a3f11..c4d47db59 100644 --- a/dronekit/test/sitl/test_115.py +++ b/dronekit/test/sitl/test_115.py @@ -20,7 +20,7 @@ def mavlink_callback(*args): v.add_message_listener('*', mavlink_callback) # Change the vehicle into STABILIZE mode - v.mode = VehicleMode("STABILIZE") + v.set_mode(VehicleMode("STABILIZE")) # NOTE wait crudely for ACK on mode update time.sleep(3) @@ -32,7 +32,7 @@ def mavlink_callback(*args): savecount = mavlink_callback.count # Disarm. A callback of None should not throw errors - v.armed = False + v.set_armed(False) # NOTE wait crudely for ACK on mode update time.sleep(3) @@ -40,7 +40,7 @@ def mavlink_callback(*args): assert_equals(savecount, mavlink_callback.count) # Re-arm should not throw errors. - v.armed = True + v.set_armed() # NOTE wait crudely for ACK on mode update time.sleep(3) diff --git a/examples/simple_goto/simple_goto.py b/examples/simple_goto/simple_goto.py index b2e581dc2..093b756dc 100644 --- a/examples/simple_goto/simple_goto.py +++ b/examples/simple_goto/simple_goto.py @@ -52,12 +52,9 @@ def arm_and_takeoff(aTargetAltitude): print "Arming motors" # Copter should arm in GUIDED mode vehicle.mode = VehicleMode("GUIDED") - vehicle.armed = True - - # Confirm vehicle armed before attempting to take off - while not vehicle.armed: - print " Waiting for arming..." - time.sleep(1) + + # Arm the vehicle + vehicle.try_set_armed() #returns when armed print "Taking off!" vehicle.simple_takeoff(aTargetAltitude) # Take off to target altitude @@ -74,17 +71,19 @@ def arm_and_takeoff(aTargetAltitude): arm_and_takeoff(10) + print "Set default/target airspeed to 3" -vehicle.airspeed = 3 +vehicle.try_set_target_airspeed(3, wait_ready=False) print "Going towards first point for 30 seconds ..." point1 = LocationGlobalRelative(-35.361354, 149.165218, 20) vehicle.simple_goto(point1) + # sleep so we can see the change in map time.sleep(30) -print "Going towards second point for 30 seconds (groundspeed set to 10 m/s) ..." +print "Going towards second point for 30 seconds (groundspeed set to 10 m/s in goto) ..." point2 = LocationGlobalRelative(-35.363244, 149.168801, 20) vehicle.simple_goto(point2, groundspeed=10) diff --git a/examples/vehicle_state/vehicle_state.py b/examples/vehicle_state/vehicle_state.py index 1d73e1de4..df76c00f7 100644 --- a/examples/vehicle_state/vehicle_state.py +++ b/examples/vehicle_state/vehicle_state.py @@ -78,10 +78,10 @@ print " Heading: %s" % vehicle.heading print " Is Armable?: %s" % vehicle.is_armable print " System status: %s" % vehicle.system_status.state -print " Groundspeed: %s" % vehicle.groundspeed # settable -print " Airspeed: %s" % vehicle.airspeed # settable -print " Mode: %s" % vehicle.mode.name # settable -print " Armed: %s" % vehicle.armed # settable +print " Groundspeed: %s" % vehicle.groundspeed +print " Airspeed: %s" % vehicle.airspeed +print " Mode: %s" % vehicle.mode.name +print " Armed: %s" % vehicle.armed @@ -96,28 +96,44 @@ print "\n Home location: %s" % vehicle.home_location -# Set vehicle home_location, mode, and armed attributes (the only settable attributes) +# Set vehicle home_location, mode, armed, groundspeed and airspeed attributes (the only settable attributes) -print "\nSet new home location" -# Home location must be within 50km of EKF home location (or setting will fail silently) -# In this case, just set value to current location with an easily recognisable altitude (222) -my_location_alt = vehicle.location.global_frame -my_location_alt.alt = 222.0 -vehicle.home_location = my_location_alt -print " New Home Location (from attribute - altitude should be 222): %s" % vehicle.home_location +print "\nSet new home location using synchronous function (returns when value confirmed changed)" +# Set home location to current location but change altitude to 222) +my_location = vehicle.location.global_frame +my_location.alt = 222.0 +vehicle.sync_set_home_location(my_location) +print " New Home Location (altitude should be 222): %s" % vehicle.home_location -#Confirm current value on vehicle by re-downloading commands +print "\nSet new home location using asynchronous function (returns immediately)" +my_location = vehicle.location.global_frame +# Set home location to current location but change altitude to 333) +my_location.alt = 333.0 +vehicle.set_home_location(my_location) #Returns immediately + +# Get new value of home location by re-downloading commands cmds = vehicle.commands cmds.download() cmds.wait_ready() -print " New Home Location (from vehicle - altitude should be 222): %s" % vehicle.home_location +print " New Home Location (from vehicle - should be 333.0): %s" % vehicle.home_location -print "\nSet Vehicle.mode = GUIDED (currently: %s)" % vehicle.mode.name -vehicle.mode = VehicleMode("GUIDED") -while not vehicle.mode.name=='GUIDED': #Wait until mode has changed - print " Waiting for mode change ..." - time.sleep(1) + +print "\nSet Vehicle mode to GUIDED using synchronous setter (currently: %s)" % vehicle.mode.name +vehicle.sync_set_mode(VehicleMode("GUIDED")) +print " New mode: %s" % vehicle.mode.name + +print "\nSet Vehicle mode to STABILIZE using synchronous setter and 'mode string' (currently: %s)" % vehicle.mode.name +vehicle.sync_set_mode("STABILIZE") #return when value changed +print " New mode: %s" % vehicle.mode.name + +print "\nSet Vehicle.mode = GUIDED using asynchronous setter (currently: %s)" % vehicle.mode.name +vehicle.set_mode(value=VehicleMode("GUIDED")) +while not vehicle.mode.name=="GUIDED": + print " Waiting for mode change..." + time.sleep(0.3) +print " New mode: %s" % vehicle.mode.name + # Check that vehicle is armable @@ -126,14 +142,30 @@ time.sleep(1) # If required, you can provide additional information about initialisation # using `vehicle.gps_0.fix_type` and `vehicle.mode.name`. + +print "\nSend arm message and return when value changed (currently: %s)" % vehicle.armed +if vehicle.is_armable: + vehicle.sync_set_armed() #returns when armed + print " Vehicle is armed: %s" % vehicle.armed + +print "\nSend disarm message and return when value changed (currently: %s)" % vehicle.armed +vehicle.sync_set_armed(value=False) #returns when armed +print " Vehicle is armed: %s" % vehicle.armed -print "\nSet Vehicle.armed=True (currently: %s)" % vehicle.armed -vehicle.armed = True +print "\nSend arm message and poll in loop for value to change (currently: %s)" % vehicle.armed +vehicle.set_armed() while not vehicle.armed: print " Waiting for arming..." - time.sleep(1) + time.sleep(0.3) print " Vehicle is armed: %s" % vehicle.armed +#Set groundspeed and airspeed target values asynchronously. There is no reliable way to +# check that the target value has been set and hence no equivalent synchronous method. +print "\nSend 'set target groundspeed' message (currently: %s)" % vehicle.groundspeed +vehicle.set_target_groundspeed(5) +print "\nSend 'set target airspeed' message (currently: %s)" % vehicle.airspeed +vehicle.set_target_airspeed(5) + # Add and remove and attribute callbacks @@ -170,8 +202,8 @@ def decorated_mode_callback(self, attr_name, value): # `value` is the updated attribute value. print " CALLBACK: Mode changed to", value -print " Set mode=STABILIZE (currently: %s) and wait for callback" % vehicle.mode.name -vehicle.mode = VehicleMode("STABILIZE") +print " Set mode=STABILIZE asynchronously (currently: %s) and wait for callback" % vehicle.mode.name +vehicle.set_mode(VehicleMode("STABILIZE")) print " Wait 2s so callback invoked before moving to next example" time.sleep(2) @@ -249,8 +281,8 @@ def any_parameter_callback(self, attr_name, value): ## Reset variables to sensible values. print "\nReset vehicle attributes/parameters and exit" -vehicle.mode = VehicleMode("STABILIZE") -vehicle.armed = False +vehicle.sync_set_mode(value=VehicleMode("STABILIZE")) +vehicle.sync_set_armed(value=False) vehicle.parameters['THR_MIN']=130 vehicle.parameters['THR_MID']=500 @@ -268,3 +300,4 @@ def any_parameter_callback(self, attr_name, value): +