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

Programmatically get ModelState from Gazebo

asked 2011-04-20 06:24:00 -0500

IanAlden gravatar image

updated 2014-11-22 17:05:23 -0500

ngrennan gravatar image

Hello, I am trying to programmatically get information about the pose of a PR2 in Gazebo. The examples on the wiki seem to be based upon command line using rosservice. Based upon the Publisher/Subscriber example on the ROS wiki I would imagine it would be something like:

rospy.Subscriber("gazebo/model_states", Pose, callback)

but when I try something similar to this Gazebo sends and error msg and breaks the connection. I would think it is just finding the right combination of topic and msg but I am having troubles figuring that out. Any help would be appreciate.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2011-04-26 08:15:13 -0500

hsu gravatar image

gazebo expects a ModelStates topic, not Pose, try changing your callback to accept ModelStates and see if it fixes the issue. To access the returned variables, please take a look at the following python service client example:

#!/usr/bin/env python
import roslib; roslib.load_manifest('gazebo')

import sys

import rospy
from gazebo.srv import *

def gms_client(model_name,relative_entity_name):
    rospy.wait_for_service('/gazebo/get_model_state')
    try:
        gms = rospy.ServiceProxy('/gazebo/get_model_state', GetModelState)
        resp1 = gms(model_name,relative_entity_name)
        return resp1
    except rospy.ServiceException, e:
        print "Service call failed: %s"%e


def usage():
    return "%s [model_name] [relative_entity_name]"%sys.argv[0]

if __name__ == "__main__":
    if len(sys.argv) == 3:
        model_name = sys.argv[1]
        relative_entity_name = sys.argv[2]
    else:
        print usage()
        sys.exit(1)
    res = gms_client(model_name,relative_entity_name)
    print "returnd x position ",res.pose.position.x
edit flag offensive delete link more

Comments

My objective is to synchronize the position of the robot in Gazebo and RViz. My node is controlling the robot's position through move_base node while in RViz the robot is remaining in the origin. I'm using this service client with the "gplane robot_description::base_footprint" arguments, how I could modify this client code(and which parameters to set) in order to update the pose in RVIz. Thank you!
szokei gravatar image szokei  ( 2011-05-12 22:52:32 -0500 )edit

Question Tools

Stats

Asked: 2011-04-20 06:24:00 -0500

Seen: 6,587 times

Last updated: Apr 26 '11