Skip to content

Commit 55d2f41

Browse files
committed
ROS progress
1 parent 70f713a commit 55d2f41

File tree

4 files changed

+158
-0
lines changed

4 files changed

+158
-0
lines changed

examples/ros.py

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
#!/usr/bin/env python
2+
"""
3+
@author Jesse Haviland
4+
"""
5+
6+
import roboticstoolbox as rtb
7+
import spatialmath as sm
8+
import numpy as np
9+
import os
10+
11+
# Launch the simulator Swift
12+
env = rtb.backends.ROS()
13+
env.launch(ros_master_uri='http://localhost:11311')
14+
15+
os.system('rostopic list')
16+
17+
# # Create a Panda robot object
18+
# panda = rtb.models.Panda()
19+
20+
# # Set joint angles to ready configuration
21+
# panda.q = panda.qr
22+
23+
# # Add the Panda to the simulator
24+
# env.add(panda)
25+
26+
Lines changed: 126 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,126 @@
1+
#!/usr/bin/env python
2+
"""
3+
@author Jesse Haviland
4+
"""
5+
6+
from roboticstoolbox.backends.Connector import Connector
7+
import roboticstoolbox as rtb
8+
import numpy as np
9+
import spatialmath as sm
10+
11+
import time
12+
import subprocess
13+
import os
14+
import rospy
15+
from std_msgs.msg import Float32MultiArray
16+
17+
18+
class ROS(Connector): # pragma nocover
19+
"""
20+
21+
"""
22+
def __init__(self):
23+
super(ROS, self).__init__()
24+
25+
self.robots = []
26+
27+
#
28+
# Basic methods to do with the state of the external program
29+
#
30+
31+
def launch(self, roscore=False, ros_master_uri=None, ros_ip=None):
32+
"""
33+
"""
34+
35+
super().launch()
36+
37+
# Launch roscore in seperate process
38+
if roscore:
39+
print('Launching ROS core\n')
40+
self.roscore = subprocess.Popen('roscore')
41+
42+
# Give it some time to launch
43+
time.sleep(1)
44+
45+
if ros_master_uri:
46+
os.environ["ROS_MASTER_URI"] = ros_master_uri
47+
48+
if ros_ip:
49+
os.environ["ROS_IP"] = ros_ip
50+
51+
v = VelPub(rtb.models.Panda())
52+
53+
def step(self, dt=0.05):
54+
"""
55+
"""
56+
57+
super().step
58+
59+
def reset(self):
60+
"""
61+
"""
62+
63+
super().reset
64+
65+
def restart(self):
66+
"""
67+
"""
68+
69+
super().restart
70+
71+
def close(self):
72+
"""
73+
"""
74+
75+
super().close()
76+
77+
def hold(self):
78+
"""
79+
"""
80+
81+
super().hold()
82+
83+
#
84+
# Methods to interface with the robots created in other environemnts
85+
#
86+
87+
def add(
88+
self, ob):
89+
"""
90+
91+
"""
92+
93+
super().add()
94+
95+
def remove(self):
96+
"""
97+
Remove a robot to the graphical scene
98+
99+
``env.remove(robot)`` removes the ``robot`` from the graphical
100+
environment.
101+
"""
102+
103+
# TODO - shouldn't this have an id argument? which robot does it remove
104+
# TODO - it can remove any entity?
105+
106+
super().remove()
107+
108+
109+
class VelPub:
110+
111+
def __init__(self, robot):
112+
rospy.init_node('RTB_VelocityPublisher')
113+
self.robot = robot
114+
self.v = np.zeros(robot.n)
115+
116+
self.velocity_publisher = rospy.Publisher(
117+
'/joint_velocity',
118+
Float32MultiArray, queue_size=1)
119+
120+
self.relay()
121+
122+
def relay(self):
123+
124+
while True:
125+
data = Float32MultiArray(data=self.robot.q)
126+
self.velocity_publisher.publish(data)
Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
from roboticstoolbox.backends.ROS.ROS import ROS
2+
3+
__all__ = [
4+
'ROS'
5+
]

roboticstoolbox/backends/__init__.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
from roboticstoolbox.backends.PyPlot import * # noqa
22
from roboticstoolbox.backends.Swift import * # noqa
3+
from roboticstoolbox.backends.ROS import * # noqa
34

45
try:
56
from roboticstoolbox.backends.VPython import * # noqa

0 commit comments

Comments
 (0)