-
Notifications
You must be signed in to change notification settings - Fork 1.5k
Closed
Milestone
Description
@tcr3dr My initial test code for #445 is below. This adds a listener on_attribute for 'location' and a listener on_message for 'GLOBAL_POSITION_INT'.
The problem is that the on_message is not reporting any messages. Worse, if I enable it the vehicle will not arm (even though it reports is_armable) and only gives ONE update of the location information. Removing the offending code means that the example takes off and reports location as normal. You can verify this for yourself using the code below - simply (un)comment out the code marked up as #### DISABLE BELOW CODE TO ALLOW ARMING
The create_attribute.py still works, so probably I am doing something wrong here ... but even so, we need to know why because this is very odd.
from dronekit import connect
from dronekit.lib import VehicleMode, LocationGlobal
import time
#Set up option parsing to get connection string
import argparse
parser = argparse.ArgumentParser(description='Print out vehicle state information. Connects to SITL on local PC by default.')
parser.add_argument('--connect', default='127.0.0.1:14550',
help="vehicle connection target. Default '127.0.0.1:14550'")
args = parser.parse_args()
# Connect to the Vehicle
print 'Connecting to vehicle on: %s' % args.connect
vehicle = connect(args.connect, wait_ready=True)
print "Got connected baby"
@vehicle.on_attribute('location')
def listener(self, attr_name, value):
# `attr_name` is the observed attribute (used if callback is used for multiple attributes)
# `attr_name` - the observed attribute (used if callback is used for multiple attributes)
# `value` is the updated attribute value.
print "ATTR: %s changed to: %s" % (attr_name, value)
print " GlobalF: %s" % self.location.global_frame
print " LocalF: %s" % self.location.local_frame
#### DISABLE BELOW CODE TO ALLOW ARMING
# Create a message listener using the decorator.
@vehicle.on_message('GLOBAL_POSITION_INT')
def listener(self, name, message):
print "gpi alt: %s" % message.alt/1000
print "gpi relative_alt: %s" % message.relative_alt/1000
#### DISABLE ABOVE CODE TO ALLOW ARMING
# Create an attribute listener using the decorator.
# If this changes but we don't get on_message notifications we know there is a problem
@vehicle.on_attribute('location')
def listener(self, attr_name, value):
# `attr_name` is the observed attribute (used if callback is used for multiple attributes)
# `attr_name` - the observed attribute (used if callback is used for multiple attributes)
# `value` is the updated attribute value.
print " ATTR: %s changed to: %s" % (attr_name, value)
def arm_and_takeoff(aTargetAltitude):
"""
Arms vehicle and fly to aTargetAltitude.
"""
print "Basic pre-arm checks"
# Don't let the user try to arm until autopilot is ready
while not vehicle.is_armable:
print " Waiting for vehicle to initialise..."
print " GPS: %s" % vehicle.gps_0
print " Is Armable?: %s" % vehicle.is_armable
print " System status: %s" % vehicle.system_status.state
print " Mode: %s" % vehicle.mode.name # settable
time.sleep(1)
print "Arming motors"
# Copter should arm in GUIDED mode
vehicle.mode = VehicleMode("GUIDED")
vehicle.armed = True
count_to_arm=0
while not vehicle.armed:
count_to_arm+=1
print " Waiting for arming...: %s" % count_to_arm
print " GPS: %s" % vehicle.gps_0
print " Is Armable?: %s" % vehicle.is_armable
print " System status: %s" % vehicle.system_status.state
print " Mode: %s" % vehicle.mode.name # settable
print " Armed: %s" % vehicle.armed
vehicle.armed = True
time.sleep(1)
print "Taking off!"
vehicle.commands.takeoff(aTargetAltitude) # Take off to target altitude
# Wait until the vehicle reaches a safe height before processing the goto (otherwise the command
# after Vehicle.commands.takeoff will execute immediately).
while True:
print " Altitude: ", vehicle.location.global_frame.alt
if vehicle.location.global_frame.alt>=aTargetAltitude*0.95: #Trigger just below target alt.
print "Reached target altitude"
break
time.sleep(1)
arm_and_takeoff(20)
print "Going to first point..."
point1 = LocationGlobal(-35.361354, 149.165218, 20, is_relative=True)
vehicle.commands.goto(point1)
# sleep so we can see the change in map
time.sleep(30)
print "Going to second point..."
point2 = LocationGlobal(-35.363244, 149.168801, 20, is_relative=True)
vehicle.commands.goto(point2)
# sleep so we can see the change in map
time.sleep(30)
print "Returning to Launch"
vehicle.mode = VehicleMode("RTL")
#Close vehicle object before exiting script
print "Close vehicle object"
vehicle.close()
Metadata
Metadata
Assignees
Labels
No labels