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

Imaging interop #8

Merged
merged 6 commits into from
May 17, 2019
Merged
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
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1 +1,2 @@
*.pyc
.vscode
11 changes: 4 additions & 7 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,16 +2,13 @@ cmake_minimum_required(VERSION 2.8.3)
project(interop_pkg)

find_package(catkin REQUIRED COMPONENTS
roscpp
rosflight_msgs
rospy
sniper_cam
rosflight_msgs
std_msgs
uav_msgs
)

catkin_package()

include_directories(
${catkin_INCLUDE_DIRS}
catkin_package(
CATKIN_DEPENDS rosflight_msgs std_msgs uav_msgs
)

22 changes: 8 additions & 14 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,21 +1,15 @@
<?xml version="1.0"?>
<package>
<package format="2">
<name>interop_pkg</name>
<version>0.0.0</version>
<version>0.0.1</version>
<description>The interop_pkg package</description>
<maintainer email="[email protected]">michael</maintainer>
<license>TODO</license>
<license>BSD</license>

<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>rosflight_msgs</build_depend>
<build_depend>rospy</build_depend>
<build_depend>sniper_cam</build_depend>
<build_depend>std_msgs</build_depend>
<run_depend>roscpp</run_depend>
<run_depend>rosflight_msgs</run_depend>
<run_depend>rospy</run_depend>
<run_depend>sniper_cam</run_depend>
<run_depend>std_msgs</run_depend>

<depend>rospy</depend>
<depend>rosflight_msgs</depend>
<depend>std_msgs</depend>
<depend>uav_msgs</depend>

</package>
2 changes: 0 additions & 2 deletions param/client_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -6,5 +6,3 @@ MAX_RETRIES: 10 # number of times client will try to connect to server before gi
init_lat: 38.144692
init_lon: -76.428007
r_earth: 6370027
BACKUP_OBJECT_PATH: "~/Desktop/objects/"
unique_id: 0 # id that we will use to write images when we don't get one assigned from server
Binary file modified scripts/ClientObjects.pyc
Binary file not shown.
130 changes: 40 additions & 90 deletions scripts/InteropClient.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,23 +15,21 @@
from std_msgs.msg import Float64
from sensor_msgs.msg import NavSatFix
from rosplane_msgs.msg import State
from sniper_cam.msg import interopImages
from uav_msgs.srv import SubmitImage, SubmitImageResponse
from uav_msgs.srv import GetMissionWithId
from uav_msgs.msg import *
from ClientObjects import PostFailedException, Telemetry, Target

class InteropClient(object):
def __init__(self, server_ip, server_port, server_url, retry_max, backup_path,
unique_id, init_lat, init_lon, r_earth, sleep_sec):
def __init__(self, server_ip, server_port, server_url, retry_max,
init_lat, init_lon, r_earth, sleep_sec):
self.SERVERADDR = server_ip
self.SERVERPORT = server_port
self.SERVERURL = server_url
self.GLOBALCOOKIE = None
self.CONNECTED = False
self.RETRY_MAX = retry_max
self.SESSION = requests.Session()
self.BACKUP_OBJECT_PATH = backup_path
self.unique_id = unique_id
self.connectedLock = threading.Lock()
# For NED to LatLon conversions
self.HOME = [init_lat, init_lon]
Expand All @@ -47,28 +45,10 @@ def __init__(self, server_ip, server_port, server_url, retry_max, backup_path,
self.listenerThread.start()
self.talker()

def target_callback(self, data):
def target_submission_handler(self, data):
# Setup target model and pass to post_target() and post_target_image()
# TODO: create thread for this
orientation_deg = data.orientation % 360
if (orientation_deg <= 22.5 or orientation_deg >= 337.5):
orientation = "n"
elif (orientation_deg >= 22.5 and orientation_deg <= 67.5):
orientation = "nw"
elif (orientation_deg >= 67.5 and orientation_deg <= 112.5):
orientation = "w"
elif (orientation_deg >= 112.5 and orientation_deg <= 157.5):
orientation = "sw"
elif (orientation_deg >= 157.5 and orientation_deg <= 202.5):
orientation = "s"
elif (orientation_deg >= 202.5 and orientation_deg <= 247.5):
orientation = "se"
elif (orientation_deg >= 247.5 and orientation_deg <= 292.5):
orientation = "e"
else:
orientation = "ne"

target = Target(data.type, data.gps_lati, data.gps_longit, orientation, data.target_shape, data.target_color, data.symbol, data.symbol_color, data.description, data.autonomous)

target = Target(data.type, data.latitude, data.longitude, data.orientation, data.shape, data.background_color, data.alphanumeric, data.alphanumeric_color, data.description, data.autonomous)

cv2_img = None
try:
Expand All @@ -82,45 +62,23 @@ def target_callback(self, data):
try:
target_id = self.post_target(target) # Throws if posting the target fails after retries
except PostFailedException:
# Write target / target image to object file
target_id = self.pick_unique_id()
print("Writing target data and image to file with generated id: {}".format(target_id))
self.write_target_data_to_file(target, target_id)
self.write_target_image_to_file(cv2_img, target_id)
return

# If posting the target data succeeded, now post the target image
self.post_target_image(target_id, cv2_img)

def write_target_data_to_file(self, target_data, target_id):
self.make_directory_if_not_exists(self.BACKUP_OBJECT_PATH)
# if the post failed, then dont put the image.
# imaging subsystem has already saved a copy of the image in odlc format on disk
# let them know that we failed to submit
return SubmitImageResponse(False)

name = self.BACKUP_OBJECT_PATH + str(target_id) + ".json"

# Write target_data as json to name path
params = {'type': target_data.type, 'latitude': target_data.latitude, 'longitude': target_data.longitude,
'orientation': target_data.orientation, 'shape': target_data.shape, 'background_color': target_data.background_color,
'alphanumeric': target_data.alphanumeric, 'alphanumeric_color': target_data.alphanumeric_color,
'description': target_data.description, 'autonomous':target_data.autonomous}

json_params = json.dumps(params)
with open(name, "w") as f:
f.write(json_params)

def write_target_image_to_file(self, image, target_id):
self.make_directory_if_not_exists(self.BACKUP_OBJECT_PATH)

name = self.BACKUP_OBJECT_PATH + str(target_id) + ".jpg"
cv2.imwrite(name, image)

def make_directory_if_not_exists(self, directory):
if not os.path.exists(directory):
os.makedirs(directory)
try:
# If posting the target data succeeded, now post the target image
self.post_target_image(target_id, cv2_img)
except PostFailedException:
# the image failed to post. remove the target from the judge server
# if possible and return failure
print("WARN: Failed to post image for target {}".format(target_id))
if not delete_target(target_id):
print("WARN: Failed to remove target with id {} from judge server".format(target_id))
return SubmitImageResponse(False)

def pick_unique_id(self):
# global unique_id
self.unique_id += 1
return self.unique_id
return SubmitImageResponse(True)

def state_callback(self, data):
# These come in as NED, so convert to lat / lon
Expand All @@ -145,7 +103,7 @@ def nedToLatLon(self, ned):
def listener(self):
print('Listening')
rospy.Subscriber("/state", State, self.state_callback) # state info from ros_plane
rospy.Subscriber("/plans", interopImages, self.target_callback) # images + metadata from imaging gui
rospy.Service("/imaging/target", SubmitImage, self.target_submission_handler) # images + metadata from imaging gui
# processing
rospy.spin()

Expand Down Expand Up @@ -257,16 +215,6 @@ def talker(self):
json_obstacles = json.loads(string)
print("Got obstacles!")

# def get_cookie():
# global self.GLOBALCOOKIE
# return GLOBALCOOKIE


# def set_cookie(cookie):
# global GLOBALCOOKIE
# GLOBALCOOKIE = cookie


def is_connected(self):
# global CONNECTED

Expand All @@ -276,15 +224,13 @@ def is_connected(self):

return connected


def set_is_connected(self, connected):
# global CONNECTED

self.connectedLock.acquire()
self.CONNECTED = connected
self.connectedLock.release()


def connect(self):
# params = {"username": "testuser", "password": "testpass"}
params = {"username": "testuser", "password": "testpass"}
Expand Down Expand Up @@ -313,7 +259,6 @@ def connect(self):
print("could not connect to server. (address=" + self.SERVERADDR + ", port=" + str(self.SERVERPORT) + ", " + ", ".join(str(params).split("&")) + "). exiting...")
exit()


def send_request(self, method, resource, params, headers):
response = None

Expand All @@ -328,9 +273,11 @@ def send_request(self, method, resource, params, headers):
response = self.SESSION.get(self.SERVERURL+resource, headers=headers)
elif method == 'POST':
response = self.SESSION.post(self.SERVERURL+resource, headers=headers, data=params)
print("Successfully posted: {}, {}, {}".format(resource,params,headers))
print("Successfully posted: {}, {}".format(resource,headers))
elif method == 'PUT':
response = self.SESSION.put(self.SERVERURL+resource, headers=headers, data=params)
elif method == 'DELETE':
response = self.SESSION.delete(self.SERVERURL+resource, headers=headers, data=params)

if response.status_code == 200 or response.status_code == 201:
break
Expand Down Expand Up @@ -360,12 +307,10 @@ def send_request(self, method, resource, params, headers):

return response


def get_obstacles(self):
response = self.send_request('GET', '/api/obstacles', None, headers={'Cookie': self.GLOBALCOOKIE})
return response.text


def get_missions(self):
response = self.send_request('GET', '/api/missions', None, headers={'Cookie': self.GLOBALCOOKIE})
return response.text
Expand All @@ -377,7 +322,6 @@ def post_telemetry(self, telemetry):
headers = {"Content-Type": "application/x-www-form-urlencoded", "Accept": "text/plain", 'Cookie': self.GLOBALCOOKIE}
response = self.send_request('POST', '/api/telemetry', params, headers)


def post_target(self, target):
params = {'type': target.type, 'latitude': target.latitude, 'longitude': target.longitude,
'orientation': target.orientation, 'shape': target.shape, 'background_color': target.background_color,
Expand All @@ -391,14 +335,21 @@ def post_target(self, target):

for retry in range(self.RETRY_MAX):
if response.status_code == 201:
ROS_WARN("Target was submitted successfully on try {}!".format(retry + 1))
print("Target was submitted successfully on try {}!".format(retry + 1))
return response.json()['id']
else:
print("Something went wrong with posting a target, trying again")
# actually try again...
response = self.send_request('POST', '/api/odlcs', json_params, headers)

print("Target failed after {} tries".format(self.RETRY_MAX))
raise PostFailedException()

def delete_target(self, target_id):
headers = {'Cookie': self.GLOBALCOOKIE}
response = self.send_request('DELETE', '/api/odlcs/' + str(target_id), None, headers)
return response.status_code == 200

def post_target_image(self, target_id, image):
encoded_image = cv2.imencode(".jpg", image)[1].tostring()

Expand All @@ -407,12 +358,13 @@ def post_target_image(self, target_id, image):

for retry in range(self.RETRY_MAX):
if response.status_code == 200:
ROS_WARN("Target image was submitted successfully on try {}!".format(retry + 1))
print("Target image was submitted successfully on try {}!".format(retry + 1))
return
else:
print("Something went wrong with posting an image, trying again")
print("Writing target image to file with id: {}".format(target_id))
self.write_target_image_to_file(image, target_id)

print("Failed to post target image with id: {}".format(target_id))
raise PostFailedException()

def feetToMeters(self, feet):
return feet * 0.3048
Expand All @@ -429,16 +381,14 @@ def metersToFeet(self, meters):
server_port = rospy.get_param("~SERVER_PORT")
server_url = "http://" + server_ip + ":" + str(server_port)
retry_max = rospy.get_param("~MAX_RETRIES")
backup_path = os.path.expanduser(rospy.get_param("~BACKUP_OBJECT_PATH"))
unique_id = rospy.get_param("~unique_id")
init_lat = rospy.get_param("~init_lat")
init_lon = rospy.get_param("~init_lon")
r_earth = rospy.get_param("~r_earth")
sleep_sec = rospy.get_param("~sleep_sec")

# initialize client
client = InteropClient(server_ip, server_port, server_url, retry_max, backup_path,
unique_id, init_lat, init_lon, r_earth, sleep_sec)
client = InteropClient(server_ip, server_port, server_url, retry_max,
init_lat, init_lon, r_earth, sleep_sec)

# keep the program running until manually killed
while not rospy.is_shutdown():
Expand All @@ -447,4 +397,4 @@ def metersToFeet(self, meters):
except KeyboardInterrupt:
print('Kill signal received.')

print 'Shutting down interop client...'
print('Shutting down interop client...')
4 changes: 2 additions & 2 deletions scripts/spawn_server.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,13 +8,13 @@
disable_signals=True)

os.system('docker start interop-server')
print 'SERVER RUNNING'
print('SERVER RUNNING')

while not rospy.is_shutdown():
try:
rospy.spin()
except KeyboardInterrupt:
print('Kill signal received.')

print 'Shutting down interop server...'
print('Shutting down interop server...')
os.system('docker stop interop-server')
1 change: 1 addition & 0 deletions setup/pip-requirements.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
requests==2.21.0