Skip to content

Commit a8436d0

Browse files
authored
Merge pull request #1135 from TritonSailor/ROS
ROS: add sample airsim ROS nodes for PythonClient and ROS integration…
2 parents ee41cc7 + 6914e87 commit a8436d0

File tree

4 files changed

+212
-0
lines changed

4 files changed

+212
-0
lines changed

PythonClient/ROS/car_image_raw.py

Lines changed: 53 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,53 @@
1+
#!/usr/bin/env python
2+
3+
# Example ROS node for publishing AirSim images.
4+
5+
import rospy
6+
7+
# ROS Image message
8+
from sensor_msgs.msg import Image
9+
10+
# AirSim Python API
11+
from AirSimClient import *
12+
13+
def airpub():
14+
pub = rospy.Publisher("airsim/image_raw", Image, queue_size=1)
15+
rospy.init_node('image_raw', anonymous=True)
16+
rate = rospy.Rate(10) # 10hz
17+
18+
# connect to the AirSim simulator
19+
client = CarClient()
20+
client.confirmConnection()
21+
22+
while not rospy.is_shutdown():
23+
# get camera images from the car
24+
responses = client.simGetImages([
25+
ImageRequest(1, AirSimImageType.Scene, False, False)]) #scene vision image in uncompressed RGBA array
26+
27+
for response in responses:
28+
img_rgba_string = response.image_data_uint8
29+
30+
# Populate image message
31+
msg=Image()
32+
msg.header.stamp = rospy.Time.now()
33+
msg.header.frame_id = "frameId"
34+
msg.encoding = "rgba8"
35+
msg.height = 360 # resolution should match values in settings.json
36+
msg.width = 640
37+
msg.data = img_rgba_string
38+
msg.is_bigendian = 0
39+
msg.step = msg.width * 4
40+
41+
# log time and size of published image
42+
rospy.loginfo(len(response.image_data_uint8))
43+
# publish image message
44+
pub.publish(msg)
45+
# sleep until next cycle
46+
rate.sleep()
47+
48+
49+
if __name__ == '__main__':
50+
try:
51+
airpub()
52+
except rospy.ROSInterruptException:
53+
pass

PythonClient/ROS/car_pose.py

Lines changed: 57 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
1+
#!/usr/bin/env python
2+
3+
import rospy
4+
import tf
5+
from std_msgs.msg import String
6+
from geometry_msgs.msg import PoseStamped
7+
from AirSimClient import *
8+
import time
9+
10+
11+
def airpub():
12+
pub = rospy.Publisher("airsimPose", PoseStamped, queue_size=1)
13+
rospy.init_node('airpub', anonymous=True)
14+
rate = rospy.Rate(10) # 10hz
15+
16+
# connect to the AirSim simulator
17+
client = CarClient()
18+
client.confirmConnection()
19+
20+
# start = time.time()
21+
22+
23+
while not rospy.is_shutdown():
24+
25+
# get state of the car
26+
car_state = client.getCarState()
27+
pos = car_state.kinematics_true.position
28+
orientation = car_state.kinematics_true.orientation
29+
# milliseconds = (time.time() - start) * 1000
30+
31+
32+
# populate PoseStamped ros message
33+
simPose = PoseStamped()
34+
simPose.pose.position.x = pos.x_val
35+
simPose.pose.position.y = pos.y_val
36+
simPose.pose.position.z = pos.z_val
37+
simPose.pose.orientation.w = orientation.w_val
38+
simPose.pose.orientation.x = orientation.x_val
39+
simPose.pose.orientation.y = orientation.y_val
40+
simPose.pose.orientation.z = orientation.z_val
41+
simPose.header.stamp = rospy.Time.now()
42+
simPose.header.seq = 1
43+
simPose.header.frame_id = "simFrame"
44+
45+
# log PoseStamped message
46+
rospy.loginfo(simPose)
47+
#publish PoseStamped message
48+
pub.publish(simPose)
49+
# sleeps until next cycle
50+
rate.sleep()
51+
52+
53+
if __name__ == '__main__':
54+
try:
55+
airpub()
56+
except rospy.ROSInterruptException:
57+
pass
Lines changed: 53 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,53 @@
1+
#!/usr/bin/env python
2+
3+
# Example ROS node for publishing AirSim images.
4+
5+
import rospy
6+
7+
# ROS Image message
8+
from sensor_msgs.msg import Image
9+
10+
# AirSim Python API
11+
from AirSimClient import *
12+
13+
def airpub():
14+
pub = rospy.Publisher("airsim/image_raw", Image, queue_size=1)
15+
rospy.init_node('image_raw', anonymous=True)
16+
rate = rospy.Rate(10) # 10hz
17+
18+
# connect to the AirSim simulator
19+
client = MultirotorClient()
20+
client.confirmConnection()
21+
22+
while not rospy.is_shutdown():
23+
# get camera images from the car
24+
responses = client.simGetImages([
25+
ImageRequest(1, AirSimImageType.Scene, False, False)]) #scene vision image in uncompressed RGBA array
26+
27+
for response in responses:
28+
img_rgba_string = response.image_data_uint8
29+
30+
# Populate image message
31+
msg=Image()
32+
msg.header.stamp = rospy.Time.now()
33+
msg.header.frame_id = "frameId"
34+
msg.encoding = "rgba8"
35+
msg.height = 360 # resolution should match values in settings.json
36+
msg.width = 640
37+
msg.data = img_rgba_string
38+
msg.is_bigendian = 0
39+
msg.step = msg.width * 4
40+
41+
# log time and size of published image
42+
rospy.loginfo(len(response.image_data_uint8))
43+
# publish image message
44+
pub.publish(msg)
45+
# sleep until next cycle
46+
rate.sleep()
47+
48+
49+
if __name__ == '__main__':
50+
try:
51+
airpub()
52+
except rospy.ROSInterruptException:
53+
pass

docs/ros.md

Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
1+
# How to use AirSim with Robot Operating System (ROS)
2+
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.
5+
6+
# Python
7+
8+
## Prerequisites
9+
10+
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.
12+
13+
## Setup
14+
15+
16+
### Create a new ROS package in your catkin workspace following these instructions.
17+
18+
Create a new ROS package called airsim or whatever you like.
19+
20+
[Create ROS package](http://wiki.ros.org/ROS/Tutorials/CreatingPackage)
21+
22+
If you don't already have a catkin workspace, you should first work through the ROS beginner tutorials.
23+
24+
### Add AirSim ROS node examples to ROS package
25+
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.
29+
30+
```cp AirSim/PythonClient/ROS/*.py ../catkin_ws/src/airsim/scripts```
31+
32+
33+
### Build ROS AirSim package
34+
35+
Change directory to your top level catkin workspace folder i.e. ```cd ~/catkin_ws``` and run ```catkin_make```
36+
This will build the airsim package. Next, run ```source devel/setup.bash``` so ROS can find the new package.
37+
You can add this command to your ~/.bashrc to load your catkin workspace automatically.
38+
39+
## How to run ROS AirSim nodes
40+
41+
First make sure UE4 is running an airsim project, the car or drone should be selected, and the simulations is playing.
42+
Examples support car or drone. Make sure to have the correct vehicle for the ros example running.
43+
44+
The example airsim nodes can be run using ```rosrun airsim example_name.py``` The output of the node
45+
can be viewed in another terminal by running ```rostopic echo /example_name``` You can view a list of the
46+
topics currently published via tab completion after typing ```rostopic echo``` in the terminal.
47+
Rviz is a useful visualization tool that can display the published data.
48+
49+
# C++ (coming soon)

0 commit comments

Comments
 (0)