Skip to content

Commit

Permalink
grpc: fixed Python examples
Browse files Browse the repository at this point in the history
  • Loading branch information
julianoes committed Nov 27, 2017
1 parent 29b0859 commit 51e67eb
Show file tree
Hide file tree
Showing 3 changed files with 35 additions and 35 deletions.
28 changes: 15 additions & 13 deletions grpc/python_client/async_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,10 @@
import time
import threading
import dronecore_pb2 as dc
import dronecore_pb2_grpc
# import action_pb2 as dc_action
# import action_pb2_grpc
import telemetry_pb2 as dc_telemetry
# import dronecore_pb2_grpc
import action_pb2 as dc_action
import action_pb2_grpc
# import telemetry_pb2 as dc_telemetry
import telemetry_pb2_grpc


Expand All @@ -26,7 +26,7 @@ def wait_until(status):
def print_altitude(telemetry_stub, stop):
for i, position in enumerate(
telemetry_stub.TelemetryPositionSubscription(
dc_telemetry.TelemetryEmpty())):
dc.Empty())):
# Position updates with SITL are too fast, we skip 9/10.
if i % 10 == 0:
print(Colors.BLUE, end="")
Expand All @@ -39,41 +39,43 @@ def print_altitude(telemetry_stub, stop):

def run():
channel = grpc.insecure_channel('0.0.0.0:50051')
stub = dronecore_pb2_grpc.DroneCoreRPCStub(channel)
# action_stub = action_pb2_grpc.ActionRPCStub(channel)
# stub = dronecore_pb2_grpc.DroneCoreRPCStub(channel)
action_stub = action_pb2_grpc.ActionRPCStub(channel)
telemetry_stub = telemetry_pb2_grpc.TelemetryRPCStub(channel)

# We use this stop event later to stop the thread.
t_stop = threading.Event()
t = threading.Thread(target=print_altitude, args=(telemetry_stub, t_stop))
t.start()

arm_result = stub.Arm.future(dc.Empty())
arm_result = action_stub.Arm.future(dc.Empty())
arm_result = wait_until(arm_result)
if arm_result.result == dc.ActionResult.Result_SUCCESS:
if arm_result.result == dc_action.ActionResult.SUCCESS:
print("arming ok")
else:
print("arming failed: " + arm_result.result_str)

time.sleep(2)

takeoff_result = stub.TakeOff.future(dc.Empty())
takeoff_result = action_stub.TakeOff.future(dc.Empty())
takeoff_result = wait_until(takeoff_result)
if takeoff_result.result == dc.ActionResult.Result_SUCCESS:
if takeoff_result.result == dc_action.ActionResult.SUCCESS:
print("takeoff ok")
else:
print("takeoff failed: " + takeoff_result.result_str)

time.sleep(5)

land_result = stub.Land.future(dc.Empty())
land_result = action_stub.Land.future(dc.Empty())
land_result = wait_until(land_result)
if land_result.result == dc.ActionResult.Result_SUCCESS:
if land_result.result == dc_action.ActionResult.SUCCESS:
print("landing ok")
else:
print("landing failed: " + land_result.result_str)
time.sleep(3)

t_stop.set()


if __name__ == '__main__':
run()
32 changes: 16 additions & 16 deletions grpc/python_client/fly_mission.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,8 @@

from __future__ import print_function
import grpc
from threading import Thread
import time
import threading
import dronecore_pb2 as dc
# import dronecore_pb2_grpc
# import dronecore_pb2_grpc
Expand Down Expand Up @@ -33,74 +33,74 @@ def run():

mission_items = []

mission_items.append(dc.MissionItem(
mission_items.append(dc_mission.MissionItem(
latitude_deg=47.398170327054473,
longitude_deg=8.5456490218639658,
relative_altitude_m=10,
speed_m_s=5,
is_fly_through=False,
gimbal_pitch_deg=20,
gimbal_yaw_deg=60,
camera_action=dc.MissionItem.CameraAction_NONE))
camera_action=dc_mission.MissionItem.NONE))

mission_items.append(dc.MissionItem(
mission_items.append(dc_mission.MissionItem(
latitude_deg=47.398241338125118,
longitude_deg=8.5455360114574432,
relative_altitude_m=10,
speed_m_s=2,
is_fly_through=True,
gimbal_pitch_deg=0,
gimbal_yaw_deg=-60,
camera_action=dc.MissionItem.CameraAction_TAKE_PHOTO))
camera_action=dc_mission.MissionItem.TAKE_PHOTO))

mission_items.append(dc.MissionItem(
mission_items.append(dc_mission.MissionItem(
latitude_deg=47.398139363821485,
longitude_deg=8.5453846156597137,
relative_altitude_m=10,
speed_m_s=5,
is_fly_through=True,
gimbal_pitch_deg=-45,
gimbal_yaw_deg=0,
camera_action=dc.MissionItem.CameraAction_START_VIDEO))
camera_action=dc_mission.MissionItem.START_VIDEO))

mission_items.append(dc.MissionItem(
mission_items.append(dc_mission.MissionItem(
latitude_deg=47.398058617228855,
longitude_deg=8.5454618036746979,
relative_altitude_m=10,
speed_m_s=2,
is_fly_through=False,
gimbal_pitch_deg=-90,
gimbal_yaw_deg=30,
camera_action=dc.MissionItem.CameraAction_STOP_VIDEO))
camera_action=dc_mission.MissionItem.STOP_VIDEO))

mission_items.append(dc.MissionItem(
mission_items.append(dc_mission.MissionItem(
latitude_deg=47.398100366082858,
longitude_deg=8.5456969141960144,
relative_altitude_m=10,
speed_m_s=5,
is_fly_through=False,
gimbal_pitch_deg=-45,
gimbal_yaw_deg=-30,
camera_action=dc.MissionItem.CameraAction_START_PHOTO_INTERVAL))
camera_action=dc_mission.MissionItem.START_PHOTO_INTERVAL))

mission_items.append(dc.MissionItem(
mission_items.append(dc_mission.MissionItem(
latitude_deg=47.398001890458097,
longitude_deg=8.5455576181411743,
relative_altitude_m=10,
speed_m_s=5,
is_fly_through=False,
gimbal_pitch_deg=0,
gimbal_yaw_deg=0,
camera_action=dc.MissionItem.CameraAction_STOP_PHOTO_INTERVAL))
camera_action=dc_mission.MissionItem.STOP_PHOTO_INTERVAL))

mission_stub.SendMission(dc.Mission(mission_items=mission_items))
mission_stub.SendMission(dc_mission.Mission(mission_items=mission_items))
time.sleep(1)

action_stub.Arm(dc.Empty())
time.sleep(1)

future_status = mission_stub.StartMission.future(dc_mission.MissionEmpty())
t = Thread(target=wait_func, args=(future_status,))
future_status = mission_stub.StartMission.future(dc.Empty())
t = threading.Thread(target=wait_func, args=(future_status,))
t.start()

while(thread_status):
Expand Down
10 changes: 4 additions & 6 deletions grpc/python_client/sync_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,34 +4,32 @@
import grpc
import time
import dronecore_pb2 as dc
# import dronecore_pb2_grpc
# import action_pb2 as dc_action
import action_pb2 as dc_action
import action_pb2_grpc


def run():
channel = grpc.insecure_channel('0.0.0.0:50051')
# stub = dronecore_pb2_grpc.DroneCoreRPCStub(channel)
action_stub = action_pb2_grpc.ActionRPCStub(channel)

arm_result = action_stub.Arm(dc.Empty())
if arm_result.result == dc.ActionResult.SUCCESS:
if arm_result.result == dc_action.ActionResult.SUCCESS:
print("arming ok")
else:
print("arming failed: " + arm_result.result_str)

time.sleep(2)

takeoff_result = action_stub.TakeOff(dc.Empty())
if takeoff_result.result == dc.ActionResult.SUCCESS:
if takeoff_result.result == dc_action.ActionResult.SUCCESS:
print("takeoff ok")
else:
print("takeoff failed: " + takeoff_result.result_str)

time.sleep(5)

land_result = action_stub.Land(dc.Empty())
if land_result.result == dc.ActionResult.SUCCESS:
if land_result.result == dc_action.ActionResult.SUCCESS:
print("landing ok")
else:
print("landing failed: " + land_result.result_str)
Expand Down

0 comments on commit 51e67eb

Please sign in to comment.