ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

[SOLVED] Return a value from a callback function (subscribing to topics for moveit_python_interface)

asked 2022-05-05 05:33:22 -0500

jon.aztiria gravatar image

updated 2022-05-19 06:12:08 -0500

I'm trying to return a value from a callback function, just like in this post.

The objective is to run the MoveIt-Python interface to program robot trajectories from topics defined in the terminal with rostopic pub /<topic> "data: <number>".

So, what I've made until know is creating 3 subscribers, one for each coordinate value (x, y, z). I'm running them in a single node, which is created in the group_interface.py. I'm not sure if it's the best way, but I think it should work.

The problem is that I need to return the values from the subscriber callbacks to send them to the group interface of MoveIt. After trying different approaches presented in the mentioned post, the solution has been using a class (OOP ROS node) and save the values as member variables to the class.

I'm attaching the code for future possible help (note that probably it could be simplified):

#!/usr/bin/env python

import rospy
from std_msgs.msg import Float64

import group_interface

class ListenerX:
    def __init__(self, parent):
        self.parent = parent
        self.value = 0
        self.subs = rospy.Subscriber("/trajectPos_mtx_1_4_", Float64, self.callback_x)

    def callback_x(self, msg):
        # rospy.loginfo(rospy.get_caller_id() + "I heard: x = %s", msg.data)

        self.value = msg.data
        self.parent.receive_data("x", msg.data)

class ListenerY:
    def __init__(self, parent):
        self.parent = parent
        self.value = 0
        self.subs = rospy.Subscriber("/trajectPos_mtx_2_4_", Float64, self.callback_y)

    def callback_y(self, msg):
        # rospy.loginfo(rospy.get_caller_id() + "I heard: y = %s", msg.data)

        self.value = msg.data
        self.parent.receive_data("y", msg.data)


class ListenerZ:
    def __init__(self, parent):
        self.parent = parent
        self.value = 0
        self.subs = rospy.Subscriber("/trajectPos_mtx_3_4_", Float64, self.callback_z)

    def callback_z(self, msg):
        # rospy.loginfo(rospy.get_caller_id() + "I heard: z = %s", msg.data)

        self.value = msg.data
        self.parent.receive_data("z", msg.data)



class Listener:
    def __init__(self):
        self.interface = group_interface.GroupInterface() # this generates the node

        print("")
        print("MoveIt group: manipulator")
        print("Current joint states (radians): {}".format(self.interface.get_joint_state("manipulator")))
        print("Current joint states (degrees): {}".format(self.interface.get_joint_state("manipulator", degrees=True)))
        print("Current cartesian pose: {}".format(self.interface.get_cartesian_pose("manipulator")))

        print("")
        print("Planning group: manipulator")

        print("  |-- Reaching named pose...")
        self.interface.reach_named_pose("manipulator", "up") # robotic arm completely up

        print("  |-- Reaching cartesian pose...")
        self.pose = self.interface.get_cartesian_pose("manipulator")
        self.pose.orientation.w = 1.0

        self.cont = 0

        print("")
        print('[INFO] Waiting for target position...')
        self.listener_x = ListenerX(self)
        self.listener_y = ListenerY(self)
        self.listener_z = ListenerZ(self)


    def receive_data(self, id, val):
        if (id == "x"):
            self.pose.position.x = self.listener_x.value
            self.cont += 1
        if (id == "y"):
            self.pose.position.y = self.listener_y.value
            self.cont += 1
        if (id == "z"):
            self.pose.position.z = self.listener_z.value
            self.cont += 1

        if (self.cont == 3):
            print("")
            print('[INFO] Target position already set!')
            print("")
            print('[INFO] Reaching target position...')

            self.interface.reach_cartesian_pose("manipulator", self.pose)

            print("")
            print('[INFO] Target position already reached!')
            print("")
            print("Current cartesian pose: {}".format(self.interface.get_cartesian_pose("manipulator")))



if __name__ == '__main__':
    # rospy.init_node('listener_xyz')

    listen = Listener ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2022-05-05 08:40:32 -0500

Joe28965 gravatar image

Not necessarily an answer to your question, but an answer to your problem.

Why do you publish the 3 numbers separately? Would it not be easier to use a vector?

You could use the vector3 message from geometry_msgs and publish the 3 points in one go. This would remove a lot of headache, I feel.

If you do want to publish them individually, the answer to the question you posted suggested using a class and save the values as member variables to the class. Have you tried this?

edit flag offensive delete link more

Comments

1

Here's a good reference on how to write an OPP ROS node. https://roboticsbackend.com/oop-with-...

Alex-SSoM gravatar image Alex-SSoM  ( 2022-05-05 09:53:00 -0500 )edit
1

Thanks Joe and Alex, your answers were spot on. I've updated the question with my solution based on your approach.

jon.aztiria gravatar image jon.aztiria  ( 2022-05-11 09:03:21 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2022-05-05 05:33:22 -0500

Seen: 361 times

Last updated: May 19 '22