Skip to content

Commit

Permalink
Update ROS PR to match with new APIs
Browse files Browse the repository at this point in the history
  • Loading branch information
sytelus committed Jun 22, 2018
1 parent a8436d0 commit c4bba46
Show file tree
Hide file tree
Showing 6 changed files with 86 additions and 21 deletions.
5 changes: 5 additions & 0 deletions PythonClient/PythonClient.pyproj
Expand Up @@ -93,6 +93,10 @@
<Compile Include="multirotor\setup_path.py" />
<Compile Include="multirotor\survey.py" />
<Compile Include="multirotor\takeoff.py" />
<Compile Include="ros\car_image_raw.py" />
<Compile Include="ros\car_pose.py" />
<Compile Include="ros\drone_image_raw.py" />
<Compile Include="ros\setup_path.py" />
<Compile Include="setup.py">
<SubType>Code</SubType>
</Compile>
Expand All @@ -105,6 +109,7 @@
<Folder Include="car\" />
<Folder Include="computer_vision\" />
<Folder Include="multirotor\" />
<Folder Include="ros\" />
</ItemGroup>
<ItemGroup>
<Content Include="install_packages.bat">
Expand Down
10 changes: 5 additions & 5 deletions PythonClient/ROS/car_image_raw.py
Expand Up @@ -2,27 +2,27 @@

# Example ROS node for publishing AirSim images.

import setup_path
import airsim

import rospy

# ROS Image message
from sensor_msgs.msg import Image

# AirSim Python API
from AirSimClient import *

def airpub():
pub = rospy.Publisher("airsim/image_raw", Image, queue_size=1)
rospy.init_node('image_raw', anonymous=True)
rate = rospy.Rate(10) # 10hz

# connect to the AirSim simulator
client = CarClient()
client = airsim.CarClient()
client.confirmConnection()

while not rospy.is_shutdown():
# get camera images from the car
responses = client.simGetImages([
ImageRequest(1, AirSimImageType.Scene, False, False)]) #scene vision image in uncompressed RGBA array
airsim.ImageRequest("1", airsim.ImageType.Scene, False, False)]) #scene vision image in uncompressed RGBA array

for response in responses:
img_rgba_string = response.image_data_uint8
Expand Down
11 changes: 7 additions & 4 deletions PythonClient/ROS/car_pose.py
@@ -1,10 +1,13 @@
#!/usr/bin/env python

import setup_path
import airsim

import rospy
import tf
from std_msgs.msg import String
from geometry_msgs.msg import PoseStamped
from AirSimClient import *

import time


Expand All @@ -14,7 +17,7 @@ def airpub():
rate = rospy.Rate(10) # 10hz

# connect to the AirSim simulator
client = CarClient()
client = airsim.CarClient()
client.confirmConnection()

# start = time.time()
Expand All @@ -24,8 +27,8 @@ def airpub():

# get state of the car
car_state = client.getCarState()
pos = car_state.kinematics_true.position
orientation = car_state.kinematics_true.orientation
pos = car_state.kinematics_estimated.position
orientation = car_state.kinematics_estimated.orientation
# milliseconds = (time.time() - start) * 1000


Expand Down
11 changes: 6 additions & 5 deletions PythonClient/ROS/drone_image_raw.py
Expand Up @@ -2,27 +2,28 @@

# Example ROS node for publishing AirSim images.

# AirSim Python API
import setup_path
import airsim

import rospy

# ROS Image message
from sensor_msgs.msg import Image

# AirSim Python API
from AirSimClient import *

def airpub():
pub = rospy.Publisher("airsim/image_raw", Image, queue_size=1)
rospy.init_node('image_raw', anonymous=True)
rate = rospy.Rate(10) # 10hz

# connect to the AirSim simulator
client = MultirotorClient()
client = airsim.MultirotorClient()
client.confirmConnection()

while not rospy.is_shutdown():
# get camera images from the car
responses = client.simGetImages([
ImageRequest(1, AirSimImageType.Scene, False, False)]) #scene vision image in uncompressed RGBA array
airsim.ImageRequest("1", airsim.ImageType.Scene, False, False)]) #scene vision image in uncompressed RGBA array

for response in responses:
img_rgba_string = response.image_data_uint8
Expand Down
52 changes: 52 additions & 0 deletions PythonClient/ROS/setup_path.py
@@ -0,0 +1,52 @@
# Import this module to automatically setup path to local airsim module
# This module first tries to see if airsim module is installed via pip
# If it does then we don't do anything else
# Else we look up grand-parent folder to see if it has airsim folder
# and if it does then we add that in sys.path

import os,sys,inspect,logging

#this class simply tries to see if airsim
class SetupPath:
@staticmethod
def getDirLevels(path):
path_norm = os.path.normpath(path)
return len(path_norm.split(os.sep))

@staticmethod
def getCurrentPath():
cur_filepath = os.path.abspath(inspect.getfile(inspect.currentframe()))
return os.path.dirname(cur_filepath)

@staticmethod
def getGrandParentDir():
cur_path = SetupPath.getCurrentPath()
if SetupPath.getDirLevels(cur_path) >= 2:
return os.path.dirname(os.path.dirname(cur_path))
return ''

@staticmethod
def getParentDir():
cur_path = SetupPath.getCurrentPath()
if SetupPath.getDirLevels(cur_path) >= 1:
return os.path.dirname(cur_path)
return ''

@staticmethod
def addAirSimModulePath():
# if airsim module is installed then don't do anything else
#import pkgutil
#airsim_loader = pkgutil.find_loader('airsim')
#if airsim_loader is not None:
# return

parent = SetupPath.getParentDir()
if parent != '':
airsim_path = os.path.join(parent, 'airsim')
client_path = os.path.join(airsim_path, 'client.py')
if os.path.exists(client_path):
sys.path.insert(0, parent)
else:
logging.warning("airsim module not found in parent folder. Using installed package (pip install airsim).")

SetupPath.addAirSimModulePath()
18 changes: 11 additions & 7 deletions docs/ros.md
@@ -1,14 +1,13 @@
# How to use AirSim with Robot Operating System (ROS)

AirSim and ROS can be integrated using C++ or Python. Some example ROS nodes are provided demonstrating how to publish
data from AirSim as ROS topics.
AirSim and ROS can be integrated using C++ or Python. Some example ROS nodes are provided demonstrating how to publish data from AirSim as ROS topics.

# Python

## Prerequisites

These instructions are for Ubuntu 16.04, ROS Kinetic, UE4 4.18 or higher, and latest AirSim release.
You should have these components installed and working before proceding.
You should have these components installed and working before proceeding

## Setup

Expand All @@ -23,11 +22,16 @@ If you don't already have a catkin workspace, you should first work through the

### Add AirSim ROS node examples to ROS package

In the ROS package directory you made, run '''mkdir scripts''' to create a folder for your Python code.
Copy the ros examples from the AirSim/PythonClient directory to your ROS package. Change the code below to match
your AirSim and catkin workspace paths.
In the ROS package directory you made, copy the ros examples from the AirSim/PythonClient directory to your ROS package. Change the code below to match your AirSim and catkin workspace paths.

```cp AirSim/PythonClient/ROS/*.py ../catkin_ws/src/airsim/scripts```
```
# copy package
mkdir -p ../catkin_ws/src/airsim/scripts/airsim
cp AirSim/PythonClient/airsim/*.py ../catkin_ws/src/airsim/scripts/airsim
# copy ROS examples
cp AirSim/PythonClient/ros/*.py ../catkin_ws/src/airsim/scripts
```


### Build ROS AirSim package
Expand Down

0 comments on commit c4bba46

Please sign in to comment.