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

How to remap from geometry_msgs/PoseStamped to move_base_msgs/MoveBaseActionGoal in ROS node

asked 2018-08-20 04:05:54 -0500

dkrivet gravatar image

I am writing a node where I subscribe to the topic /move_base_simple/goal which is of message tip geometry_msgs/PoseStamped and I am wanting to publish this information to the topic /move_base/move/goal which is of message type move_base_msgs/MoveBaseActionGoal. I have the following script to try to do what I have described:

#!/usr/bin/env python

import rospy
import roslib
import actionlib

from std_msgs.msg import String, Empty
from geometry_msgs.msg import PoseStamped
from move_base_msgs.msg import MoveBaseActionGoal



def callback(data):
    rospy.loginfo(rospy.get_caller_id() + 'I HEARD %s', data.pose.position)
    rospy.loginfo(rospy.get_caller_id() + 'I heard %s', data.pose.orientation)
    pub = rospy.Publisher('move_base/move/goal', MoveBaseActionGoal, queue_size = 10)
    stuff_to_publish = data
    pub.publish(stuff_to_publish)


def listener():

    # In ROS, nodes are uniquely named. If two nodes with the same
    # name are launched, the previous one is kicked off. The
    # anonymous=True flag means that rospy will choose a unique
    # name for our 'listener' node so that multiple listeners can
    # run simultaneously.
    rospy.init_node('navgoallistener', anonymous=True)

    rospy.Subscriber('move_base_simple/goal', PoseStamped, callback)

    #message = rospy.Subscriber('move_base_simple/goal', PoseStamped, callback)
    #print message.pose.orientation

    # spin() simply keeps python from exiting until this node is stopped
    rospy.spin()

"""def talker():
    pub = rospy.Publisher('move_base/move/goal', MoveBaseActionGoal, queue_size = 10)
    rospy.init_node('navgoalsetter', anonymous = True)"""


if __name__ == '__main__':
    listener()

However I am having a problem because the messages are of different type. The relevant documentation for the message types can be found here http://docs.ros.org/diamondback/api/g... and here http://docs.ros.org/diamondback/api/m... . Basically I am wondering how to populate the header and goal_id section of the move_base_msgs message.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-08-20 14:02:07 -0500

For a typical application, you can just increment up 1 the goal ID, or even just leave it as 0. It's only important if you're trying to track multiple goals through the action server. For a typical navigation application where you have 1 goal at a time or have some knowledge of the state outside of move base (which it looks like you do) this is unnecssary. Its primarily for book keeping.

You can remap the arguments into the MoveBaseGoal object and then the actionlib_msgs/GoalID just fill in the header and increment the goal_ID by 1 for completion sake.

edit flag offensive delete link more

Comments

1

or even just leave it as 0.

it might appear that way, but you'd be violating the contract between clients and servers and then run the risk of undefined and/or unexpected behaviour.

Even if you only have a single goal active at a time, the message documentation of actionlib_msgs/GoalId ..

gvdhoorn gravatar image gvdhoorn  ( 2018-08-21 01:22:49 -0500 )edit

.. states (from here):

The id provides a way to associate feedback and result message with specific goal requests. The id specified must be unique.

Servers will assume ..

gvdhoorn gravatar image gvdhoorn  ( 2018-08-21 01:23:29 -0500 )edit

.. that is the case, and not all server implementations will be able to handle non-unique goal ids.

The Python actionlib module has a generator available: goal_id_generator.

gvdhoorn gravatar image gvdhoorn  ( 2018-08-21 01:25:34 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-08-20 04:05:54 -0500

Seen: 1,526 times

Last updated: Aug 20 '18