Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Gopro wifi #665

Open
wants to merge 9 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
107 changes: 106 additions & 1 deletion dronekit/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -1120,6 +1120,45 @@ def set_rc(chnum, v):
set_rc(8, m.chan8_raw)
self.notify_attribute_listeners('channels', self.channels)

# Servo outputs
self._servo_output_raw = ServoOutputRaw()

# Create a message listener using the decorator.
@self.on_message('SERVO_OUTPUT_RAW')
def listener(self, name, message):
"""
The listener is called for messages that contain the string specified in the decorator,
passing the vehicle, message name, and the message.

The listener writes the message to the (newly attached) ``vehicle.raw_imu`` object
and notifies observers.
"""
self._servo_output_raw.time_boot_us = message.time_usec
self._servo_output_raw.port = message.port
self._servo_output_raw.servo1_raw = message.servo1_raw
self._servo_output_raw.servo2_raw = message.servo2_raw
self._servo_output_raw.servo3_raw = message.servo3_raw
self._servo_output_raw.servo4_raw = message.servo4_raw
self._servo_output_raw.servo5_raw = message.servo5_raw
self._servo_output_raw.servo6_raw = message.servo6_raw
self._servo_output_raw.servo7_raw = message.servo7_raw
self._servo_output_raw.servo8_raw = message.servo8_raw

if hasattr(message,'servo9_raw'): #Some ArduPilot implementations only send 8 channels over mavlink
self._servo_output_raw.servo9_raw = message.servo9_raw
self._servo_output_raw.servo10_raw = message.servo10_raw
self._servo_output_raw.servo11_raw = message.servo11_raw
self._servo_output_raw.servo12_raw = message.servo12_raw
self._servo_output_raw.servo13_raw = message.servo13_raw
self._servo_output_raw.servo14_raw = message.servo14_raw
self._servo_output_raw.servo15_raw = message.servo15_raw
self._servo_output_raw.servo16_raw = message.servo16_raw

# Notify all observers of new message (with new value)
# Note that argument `cache=False` by default so listeners
# are updated with every new message
self.notify_attribute_listeners('servo_output_raw', self._servo_output_raw)

self._voltage = None
self._current = None
self._level = None
Expand Down Expand Up @@ -1148,7 +1187,10 @@ def listener(self, name, m):

@self.on_message(['WAYPOINT_CURRENT', 'MISSION_CURRENT'])
def listener(self, name, m):
self._current_waypoint = m.seq
if m.seq != self._current_waypoint:
self._current_waypoint = m.seq
self.notify_attribute_listeners('commands.next',self._current_waypoint)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

can you please add a space between the , self



self._ekf_poshorizabs = False
self._ekf_constposmode = False
Expand Down Expand Up @@ -1521,6 +1563,10 @@ def flush(self):
# Private sugar methods
#

@property
def servo_output_raw(self):
return self._servo_output_raw

@property
def _mode_mapping(self):
return self._master.mode_mapping()
Expand Down Expand Up @@ -2748,6 +2794,65 @@ def __setitem__(self, index, value):
self._vehicle._wpts_dirty = True


class ServoOutputRaw(object):
"""
The RAW servo readings from the OUTPUT of the autopilot
This contains the true raw values without any scaling to allow data capture and system debugging.

The message definition is here: https://pixhawk.ethz.ch/mavlink/#SERVO_OUTPUT_RAW


Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

can you plz the extra new lines here?, and throughout if there are any other not needed newlines/spaces

"""

def __init__(self,
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this is quite the signature, did you explore any other options to the servo attributes?, perhaps kwargs?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

thinking about it kwargs makes sense here, if you don't have all the servo messages in kwargs, you won't be able to set them on the internal attrs of the class, you would then need to create a helper perhaps to get the servo message you are looking for .get(1) or some sort of helper that makes sense (this is just an idea)

time_boot_us=None, # Timestamp (microseconds since system boot)
port=None, # Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
servo1_raw=None, # Servo output 1 value, in microseconds
servo2_raw=None, # Etc..
servo3_raw=None,
servo4_raw=None,
servo5_raw=None,
servo6_raw=None,
servo7_raw=None,
servo8_raw=None,
servo9_raw=None,
servo10_raw=None,
servo11_raw=None,
servo12_raw=None,
servo13_raw=None,
servo14_raw=None,
servo15_raw=None,
servo16_raw=None):

self.time_boot_us = time_boot_us
self.port = port
self.servo1_raw = servo1_raw
self.servo2_raw = servo2_raw
self.servo3_raw = servo3_raw
self.servo4_raw = servo4_raw
self.servo5_raw = servo5_raw
self.servo6_raw = servo6_raw
self.servo7_raw = servo7_raw
self.servo8_raw = servo8_raw
self.servo9_raw = servo9_raw
self.servo10_raw = servo10_raw
self.servo11_raw = servo11_raw
self.servo12_raw = servo12_raw
self.servo13_raw = servo13_raw
self.servo14_raw = servo14_raw
self.servo15_raw = servo15_raw
self.servo16_raw = servo16_raw

def __str__(self):
"""
String representation used to print the ServoOutputRaw object.
"""
return "SERVO_OUTPUT_RAW: time_boot_us={},port={},servo1_raw={},servo2_raw={},servo3_raw={},servo4_raw={},servo5_raw={},servo6_raw={},servo7_raw={},servo8_raw={},servo9_raw={},servo10_raw={},servo11_raw={},servo12_raw={},servo13_raw={},servo14_raw={},servo15_raw={},servo16_raw={}".format(
self.time_boot_us, self.port, self.servo1_raw, self.servo2_raw, self.servo3_raw, self.servo4_raw,
self.servo5_raw, self.servo6_raw, self.servo7_raw, self.servo8_raw, self.servo9_raw, self.servo10_raw,
self.servo11_raw, self.servo12_raw, self.servo13_raw, self.servo14_raw, self.servo15_raw, self.servo16_raw)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We have been using the __str__ decorator for debugging purposes on all of our top-level classes, do you think this is the most useful representation of data we can get out of this class?, would you typically expect all of the variables to be set and by reading make something out of it?, what if we are logging this, do you think this is the appropriate way to read it?



from dronekit.mavlink import MAVConnection


Expand Down
138 changes: 138 additions & 0 deletions dronekit/cameras.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,138 @@
__author__ = 'anton'

# Camera module
"""
This is a library for controlling cameras. It's a typical thing for companion computers to do,
so it's a handy extensions of dronekit.

The lib is primariliy meant for cams with wifi capability. But USB and Ir might be possible too.

Creating an camera object supposes your computer is connected to the wifi hotspot of the camera you are trying to control

----
"""

from urllib2 import urlopen
from time import localtime
import signal
from . import errprinter
import logging

class Timeout():
"""Timeout class using ALARM signal."""
class Timeout(Exception):
pass

def __init__(self, sec):
self.sec = sec

def __enter__(self):
signal.signal(signal.SIGALRM, self.raise_timeout)
signal.alarm(self.sec)

def __exit__(self, *args):
signal.alarm(0) # disable alarm

def raise_timeout(self, *args):
raise Timeout.Timeout()


class GeoTagger(object):
def __init__(self, vehicle=None):
self.vehicle = vehicle
FORMAT = '%(asctime)s, %(message)s'
DATEFORMAT = "%d-%m-%Y, %H:%M:%S"
logging.basicConfig(format=FORMAT, datefmt=DATEFORMAT, filename="camera_log.csv", filemode='w', level=logging.INFO)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

i would expect the logging to be part of some other utility, or at least to be able to change the file name and formats used by it, what do you think?

logging.info("picture number, waypoint, gimbal pitch, gimbal yaw, gimbal roll, att pitch, att yaw, att roll, latitude, longitude, altitude, camera message")

def log_vehicle_state(self, num_picture, cam_message):
if self.vehicle:
log_msg = ",".join(map(str,[num_picture, self.vehicle.commands.next,
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I wonder if we should use the CSV lib for this, did you consider that when exploring this solution?

self.vehicle.gimbal.pitch,
self.vehicle.gimbal.yaw,
self.vehicle.gimbal.roll,
self.vehicle.attitude.pitch,
self.vehicle.attitude.yaw,
self.vehicle.attitude.roll,
self.vehicle.location.global_frame.lat,
self.vehicle.location.global_frame.lon,
self.vehicle.location.global_frame.alt,
cam_message
]))
else:
log_msg = str(num_picture)
logging.info(log_msg)
pass


def send_http_cmd(cmd):
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this should def live inside the gopro class

try:
with Timeout(1):
data = urlopen(cmd).read()
return data
except Exception as e:
errprinter('>>> Exception in http command: ' + str(e))
return str(e)


class GoProHero3(object):
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I wonder if having a base class Camera object would be best here, you could inherit when creating a new camera object, that would allow us to maybe have a external modules, I would prefer that approach so we can standardize behind the same interfaces for cameras, this would allow for greater code re-use between apps.

def __init__(self, wifi_password="goprohero3", geotag=True, myvehicle=None):
self.wifipassword = wifi_password
self.num_picture = 0
self.geotagger = None
if geotag:
self.geotagger = GeoTagger(vehicle=myvehicle)

# See https://github.com/KonradIT/goprowifihack/blob/master/WiFi-Commands.mkdn
# for a list of http commands to control the GoPro camera

#TODO: convert these into methods.
self.on = "http://10.5.5.9/bacpac/PW?t=" + self.wifipassword + "&p=%01"
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

can you create a url builder util for this class?, and perhaps add the IP as a variable too

self.off = "http://10.5.5.9/bacpac/PW?t=" + self.wifipassword + "&p=%00"
self.stop = "http://10.5.5.9/bacpac/SH?t=" + self.wifipassword + "&p=%00"
self.videoMode = "http://10.5.5.9/camera/CM?t=" + self.wifipassword + "&p=%00"
self.burstMode = "http://10.5.5.9/camera/CM?t=" + self.wifipassword + "&p=%02"
self.timeLapseMode = "http://10.5.5.9/camera/CM?t=" + self.wifipassword + "&p=%03"
self.previewOn = "http://10.5.5.9/camera/PV?t=" + self.wifipassword + "&p=%02"
self.previewOff = "http://10.5.5.9/camera/PV?t=" + self.wifipassword + "&p=%00"
self.wvga60 = "http://10.5.5.9/camera/VR?t=" + self.wifipassword + "&p=%00"
self.wvga120 = "http://10.5.5.9/camera/VR?t=" + self.wifipassword + "&p=%01"
self.v720p30 = "http://10.5.5.9/camera/VR?t=" + self.wifipassword + "&p=%02"
self.v720p60 = "http://10.5.5.9/camera/VR?t=" + self.wifipassword + "&p=%03"
self.v960p30 = "http://10.5.5.9/camera/VR?t=" + self.wifipassword + "&p=%04"
self.v960p48 = "http://10.5.5.9/camera/VR?t=" + self.wifipassword + "&p=%05"
self.v1080p30 = "http://10.5.5.9/camera/VR?t=" + self.wifipassword + "&p=%06"
self.viewWide = "http://10.5.5.9/camera/FV?t=" + self.wifipassword + "&p=%00"
self.viewMedium = "http://10.5.5.9/camera/FV?t=" + self.wifipassword + "&p=%01"
self.viewNarrow = "http://10.5.5.9/camera/FV?t=" + self.wifipassword + "&p=%02"
self.res11mpWide = "http://10.5.5.9/camera/PR?t=" + self.wifipassword + "&p=%00"
self.res8mpMedium = "http://10.5.5.9/camera/PR?t=" + self.wifipassword + "&p=%01"
self.res5mpWide = "http://10.5.5.9/camera/PR?t=" + self.wifipassword + "&p=%02"
self.res5mpMedium = "http://10.5.5.9/camera/PR?t=" + self.wifipassword + "&p=%03"
self.noSound = "http://10.5.5.9/camera/BS?t=" + self.wifipassword + "&p=%00"
self.sound70 = "http://10.5.5.9/camera/BS?t=" + self.wifipassword + "&p=%01"
self.sound100 = "http://10.5.5.9/camera/BS?t=" + self.wifipassword + "&p=%02"
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

are you planning on adding all of these to the gopro interface? I wonder if we should have a generic command class which is handling all of them, and expose shutter as a top level user of command('shutter')?


self.sync_time()


def sync_time(self):
lt = localtime()
goprotime = "%{:02x}%{:02x}%{:02x}%{:02x}%{:02x}%{:02x}".format(lt.tm_year-2000,
lt.tm_mon,
lt.tm_mday,
lt.tm_hour,
lt.tm_min,
lt.tm_sec)
send_http_cmd("http://10.5.5.9/camera/TM?t=" + self.wifipassword + "&p=" + goprotime)

def shutter(self):
self.num_picture +=1
result = send_http_cmd("http://10.5.5.9/bacpac/SH?t=" + self.wifipassword + "&p=%01")
if self.geotagger:
self.geotagger.log_vehicle_state(self.num_picture, result)



def photo_mode(self):
send_http_cmd("http://10.5.5.9/camera/CM?t=" + self.wifipassword + "&p=%01")
Loading