Skip to content

zanellar/superros

 
 

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

38 Commits
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

Super ROS

SuperROS

Why SuperROS?

SuperROS is something "super" (above) the Robot Operating System (ROS). First of all, SuperROS allows you to separate your business logic from the ROS framework making more transparent the transition to another middleware (e.g. ROS2 in the years to come). But, more importantly, allows you to Write Less and Do More.

You can use SuperROS as a classical ROS package or just include the scripts folder to your PYTHONPATH.

Basic usage: Publisher/Subscribers

In this simple example we want to design a simple Amplifier reading a Float32 data which is then published (doubled) on another topic at a certain frequency. Although in this snippet the code reduction is not astonishing, it is a basic example to introduce the Publisher/Subscriber paradigm in SuperROS.

Super ROS Plain ROS
from superros.comm import RosNode
from std_msgs.msg import Float32
node = RosNode("amplifier")
node.setHz(node.setupParameter("hz", 30))
node.createBufferedSubscriber("in", Float32)
node.createPublisher("out", Float32)

while node.isActive():
    data = Float32(node.getBufferedData("in").data * 2.0)
    node.getPublisher("out").publish(data)
    node.tick()
import rospy
from std_msgs.msg import Float32

current_value = 0.0
def newData(msg):
    global current_value
    current_value = msg.data

rospy.init_node('amplifier', anonymous=True)
rate = rospy.Rate(rospy.get_param("~hz", 30))
sub = rospy.Subscriber("in", Float32, newData)
pub = rospy.Publisher("out", Float32)

while not rospy.is_shutdown():
    data = Float32(current_value*2.0)
    pub.publish(data)
    rate.sleep()

You can run directly the Amplifier Example with:

roslaunch superros example_subpub.launch

TF Transforms made easy

In this example (a simple TF Listener/Broadcaster with some 3D transformations) it is clear the benefit of an unified proxy (ie. the RosNode) in order to reduce UserApp<->ROS interactions. Moreover, SuperROS uses the robust PyKDL library as shared model for 3D Transformations, simplifying code readability and portability.

Super ROS Plain ROS
from superros.comm import RosNode
import PyKDL

node = RosNode("tf_manipulator")
node.setHz(node.setupParameter("hz", 30))

while node.isActive():
    # Fetches Frame from TF Tree
    frame = node.retrieveTransform("base_link", "odom")
   
    if frame is not None:
        # Creates a relative transformation frame
        t = PyKDL.Frame(
            PyKDL.Rotation.RotZ(1.57),
            PyKDL.Vector(0, 0, 0.5)
        )
        
        # Applies transformation
        frame = frame * t
        
        # Send Frame to TF Tree
        node.broadcastTransform(
            frame, "base_link_2", "odom", 
            node.getCurrentTime()
        )
        
    node.tick()
import rospy
import tf
import numpy as np

rospy.init_node('tf_manipulator')
rate = rospy.Rate(rospy.get_param("hz", 30))

listener = tf.TransformListener()
br = tf.TransformBroadcaster()

while not rospy.is_shutdown():
    # Fetches Frame (T,R) from TF Tree. May fail
    try:
        (trans1, rot1) = listener.lookupTransform(
            '/odom', '/base_link',
            rospy.Time(0)
        )
    except (tf.LookupException):
        continue
    
    # Packs T,R in a single 4x4 matrix 
    trans1_mat = tf.transformations.translation_matrix(trans1)
    rot1_mat = tf.transformations.quaternion_matrix(rot1)
    mat1 = np.dot(trans1_mat, rot1_mat)
  
    # Creates a relative transformation frame
    t = tf.transformations.rotation_matrix(1.57, [0, 0, 1])
    t[:3, 3] = np.array([0, 0, 0.5]).T
    
    # Creates a relative transformation frame
    mat2 = np.dot(mat1, t)
    
    # Unpacks T,R from the 4x4 matrix
    trans2 = tf.transformations.translation_from_matrix(mat2)
    rot2 = tf.transformations.quaternion_from_matrix(mat2)
  
    # Send Frame to TF Tree
    br.sendTransform(
        trans2,  rot2, rospy.get_rostime(),
        "base_link2", "odom"
    )

    rate.sleep()

3D Scene Visualization

In this example an animated 3D Scene was presented using the SuperROS simplified library. The communication between Rviz and your node is -- surely -- made with topics but this behaviour is masked by the VisualizationScene object.

Super ROS Plain ROS
from superros.comm import RosNode
from visualization_msgs.msg import MarkerArray
from superros.draw import VisualizationScene, Color
import PyKDL
import math

node = RosNode("example_3dscene")
node.setHz(node.setupParameter("hz", 30))

pub = node.createPublisher("test", MarkerArray)

# Visualization Scene
scene = VisualizationScene(node, "test")
scene.createCone(name="cone1", color=Color.pickFromPalette(0))
scene.createCone(name="cone2", color=Color.pickFromPalette(1))
scene.createCube(
    name="cube1",
    color=Color.pickFromPalette(2),
    transform=PyKDL.Frame(PyKDL.Vector(-2.0, 0, 0))
)

# Cone2 Frame
cone_2_frame = PyKDL.Frame(PyKDL.Vector(2.0, 0, 0))

while node.isActive():

    # Update Cone2 Pose getting stored Object
    cone_2_frame.M.DoRotZ(0.02)
    scene.getObjectByName("cone2").setTransform(cone_2_frame)

    # Update Cone1 Pose overwriting old Object
    scene.createCone(name="cone1", transform=PyKDL.Frame(
        PyKDL.Vector(
                     0.0,
                     0.0,
                     math.sin(1.0+2*math.pi*1.0*node.getCurrentTimeInSecs())
                     )
    ))

    # Publish World Frame
    node.broadcastTransform(PyKDL.Frame(), "world",
                            "base", node.getCurrentTime())

    # Update Scene
    scene.show()
    # Node Forward
    node.tick()
Ehm...?

You can run directly the 3DScene Example with:

roslaunch superros example_3dscene.launch

About

Super Ros Package

Resources

License

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published

Languages

  • Python 98.5%
  • CMake 1.5%