Skip to content

Commit c4bba46

Browse files
committed
Update ROS PR to match with new APIs
1 parent a8436d0 commit c4bba46

File tree

6 files changed

+86
-21
lines changed

6 files changed

+86
-21
lines changed

PythonClient/PythonClient.pyproj

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -93,6 +93,10 @@
9393
<Compile Include="multirotor\setup_path.py" />
9494
<Compile Include="multirotor\survey.py" />
9595
<Compile Include="multirotor\takeoff.py" />
96+
<Compile Include="ros\car_image_raw.py" />
97+
<Compile Include="ros\car_pose.py" />
98+
<Compile Include="ros\drone_image_raw.py" />
99+
<Compile Include="ros\setup_path.py" />
96100
<Compile Include="setup.py">
97101
<SubType>Code</SubType>
98102
</Compile>
@@ -105,6 +109,7 @@
105109
<Folder Include="car\" />
106110
<Folder Include="computer_vision\" />
107111
<Folder Include="multirotor\" />
112+
<Folder Include="ros\" />
108113
</ItemGroup>
109114
<ItemGroup>
110115
<Content Include="install_packages.bat">

PythonClient/ROS/car_image_raw.py

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -2,27 +2,27 @@
22

33
# Example ROS node for publishing AirSim images.
44

5+
import setup_path
6+
import airsim
7+
58
import rospy
69

710
# ROS Image message
811
from sensor_msgs.msg import Image
912

10-
# AirSim Python API
11-
from AirSimClient import *
12-
1313
def airpub():
1414
pub = rospy.Publisher("airsim/image_raw", Image, queue_size=1)
1515
rospy.init_node('image_raw', anonymous=True)
1616
rate = rospy.Rate(10) # 10hz
1717

1818
# connect to the AirSim simulator
19-
client = CarClient()
19+
client = airsim.CarClient()
2020
client.confirmConnection()
2121

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

2727
for response in responses:
2828
img_rgba_string = response.image_data_uint8

PythonClient/ROS/car_pose.py

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,13 @@
11
#!/usr/bin/env python
22

3+
import setup_path
4+
import airsim
5+
36
import rospy
47
import tf
58
from std_msgs.msg import String
69
from geometry_msgs.msg import PoseStamped
7-
from AirSimClient import *
10+
811
import time
912

1013

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

1619
# connect to the AirSim simulator
17-
client = CarClient()
20+
client = airsim.CarClient()
1821
client.confirmConnection()
1922

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

2528
# get state of the car
2629
car_state = client.getCarState()
27-
pos = car_state.kinematics_true.position
28-
orientation = car_state.kinematics_true.orientation
30+
pos = car_state.kinematics_estimated.position
31+
orientation = car_state.kinematics_estimated.orientation
2932
# milliseconds = (time.time() - start) * 1000
3033

3134

PythonClient/ROS/drone_image_raw.py

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -2,27 +2,28 @@
22

33
# Example ROS node for publishing AirSim images.
44

5+
# AirSim Python API
6+
import setup_path
7+
import airsim
8+
59
import rospy
610

711
# ROS Image message
812
from sensor_msgs.msg import Image
913

10-
# AirSim Python API
11-
from AirSimClient import *
12-
1314
def airpub():
1415
pub = rospy.Publisher("airsim/image_raw", Image, queue_size=1)
1516
rospy.init_node('image_raw', anonymous=True)
1617
rate = rospy.Rate(10) # 10hz
1718

1819
# connect to the AirSim simulator
19-
client = MultirotorClient()
20+
client = airsim.MultirotorClient()
2021
client.confirmConnection()
2122

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

2728
for response in responses:
2829
img_rgba_string = response.image_data_uint8

PythonClient/ROS/setup_path.py

Lines changed: 52 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,52 @@
1+
# Import this module to automatically setup path to local airsim module
2+
# This module first tries to see if airsim module is installed via pip
3+
# If it does then we don't do anything else
4+
# Else we look up grand-parent folder to see if it has airsim folder
5+
# and if it does then we add that in sys.path
6+
7+
import os,sys,inspect,logging
8+
9+
#this class simply tries to see if airsim
10+
class SetupPath:
11+
@staticmethod
12+
def getDirLevels(path):
13+
path_norm = os.path.normpath(path)
14+
return len(path_norm.split(os.sep))
15+
16+
@staticmethod
17+
def getCurrentPath():
18+
cur_filepath = os.path.abspath(inspect.getfile(inspect.currentframe()))
19+
return os.path.dirname(cur_filepath)
20+
21+
@staticmethod
22+
def getGrandParentDir():
23+
cur_path = SetupPath.getCurrentPath()
24+
if SetupPath.getDirLevels(cur_path) >= 2:
25+
return os.path.dirname(os.path.dirname(cur_path))
26+
return ''
27+
28+
@staticmethod
29+
def getParentDir():
30+
cur_path = SetupPath.getCurrentPath()
31+
if SetupPath.getDirLevels(cur_path) >= 1:
32+
return os.path.dirname(cur_path)
33+
return ''
34+
35+
@staticmethod
36+
def addAirSimModulePath():
37+
# if airsim module is installed then don't do anything else
38+
#import pkgutil
39+
#airsim_loader = pkgutil.find_loader('airsim')
40+
#if airsim_loader is not None:
41+
# return
42+
43+
parent = SetupPath.getParentDir()
44+
if parent != '':
45+
airsim_path = os.path.join(parent, 'airsim')
46+
client_path = os.path.join(airsim_path, 'client.py')
47+
if os.path.exists(client_path):
48+
sys.path.insert(0, parent)
49+
else:
50+
logging.warning("airsim module not found in parent folder. Using installed package (pip install airsim).")
51+
52+
SetupPath.addAirSimModulePath()

docs/ros.md

Lines changed: 11 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,13 @@
11
# How to use AirSim with Robot Operating System (ROS)
22

3-
AirSim and ROS can be integrated using C++ or Python. Some example ROS nodes are provided demonstrating how to publish
4-
data from AirSim as ROS topics.
3+
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.
54

65
# Python
76

87
## Prerequisites
98

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

1312
## Setup
1413

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

2423
### Add AirSim ROS node examples to ROS package
2524

26-
In the ROS package directory you made, run '''mkdir scripts''' to create a folder for your Python code.
27-
Copy the ros examples from the AirSim/PythonClient directory to your ROS package. Change the code below to match
28-
your AirSim and catkin workspace paths.
25+
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.
2926

30-
```cp AirSim/PythonClient/ROS/*.py ../catkin_ws/src/airsim/scripts```
27+
```
28+
# copy package
29+
mkdir -p ../catkin_ws/src/airsim/scripts/airsim
30+
cp AirSim/PythonClient/airsim/*.py ../catkin_ws/src/airsim/scripts/airsim
31+
32+
# copy ROS examples
33+
cp AirSim/PythonClient/ros/*.py ../catkin_ws/src/airsim/scripts
34+
```
3135

3236

3337
### Build ROS AirSim package

0 commit comments

Comments
 (0)