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

gazebo spawn_model from .py source code

asked 2016-10-25 10:05:17 -0500

r0josh gravatar image

updated 2016-10-25 10:09:15 -0500

env: Ubuntu 14.04, ROS Indigo. Is there a way to spawn models from the code? I was referring to gazebo_msgs/SpawnModel.srv. Tried,

#!/usr/bin/env python

import rospy, tf
from gazebo_msgs.srv import DeleteModel, SpawnModel
from geometry_msgs.msg import *

if __name__ == '__main__':
    print("Waiting for gazebo services...")
    rospy.init_node("spawn_products_in_bins")
    rospy.wait_for_service("gazebo/delete_model")
    rospy.wait_for_service("gazebo/spawn_model")
    print("Got it.")
    delete_model = rospy.ServicePoxy("gazebo/delete_model", DeleteModel)
    spawn_model = rospy.ServiceProxy("gazebo/spawn_model", SpawnModel)

    with open("$GAZEBO_MODEL_PATH/product_0/model.sdf", "r") as f:
        product_xml = f.read()

    orient = Quaternion(tf.transformations.quaternion_from_euler(0,0,0))

    for num in xrange(0,12):
        item_name = "product_{0}_0".format(num)
        print("Deleting model:%s", item_name)
        delete_model(item_name)

    for num in xrange(0,12):
        bin_y   =   2.8 *   (num    /   6)  -   1.4 
        bin_x   =   0.5 *   (num    %   6)  -   1.5
        item_name   =   "product_{0}_0".format(num)
        print("Spawning model:%s", item_name)
        item_pose   =   Pose(Point(x=bin_x, y=bin_y,    z=2),   orient)
        spawn_model(item_name, product_xml, "", item_pose, "world")

But the services never start,

josh@jUbuntu:~/ros/stockroom_ws$ rosrun stock_bot spawn_products_in_bins.py
Waiting for gazebo services...

Could not find any topics with /gazebo/spawn_model or /gazebo/delete_model even with rostopic list

PS: I'm running a gazebo simulation during the whole time.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2016-10-25 10:23:46 -0500

alienmon gravatar image

updated 2016-10-25 21:08:05 -0500

I'm running a gazebo simulation during the whole time.

I suspect that you run the gazebo ^ using gazebo command.

You need to run gazebo_ros instead.. Try :

rosrun gazebo_ros gazebo

Then you can find the gazebo services and topics when you call rostopic list and rosservice list.

PS: Make sure you've called roscore first

EDIT:

First, spawn and delete are services NOT topics. So you must check it using rosservice NOT rostopic!

When you rosservice list, the service you'll see is /gazebo/spawn_sdf_model NOT gazebo/spawn_model, which means that gazebo/spawn_model is NOT the correct service name. Therefore you should

change this line below

rospy.wait_for_service("gazebo/spawn_model")

to

rospy.wait_for_service("gazebo/spawn_sdf_model")

AND this line below

spawn_model = rospy.ServiceProxy("gazebo/spawn_model", SpawnModel)

to

s = rospy.ServiceProxy("gazebo/spawn_sdf_model", SpawnModel)
edit flag offensive delete link more

Comments

Yeah, tried that. These are the topics listed

/clock
/gazebo/link_states
/gazebo/model_states
/gazebo/parameter_descriptions
/gazebo/parameter_updates
/gazebo/set_link_state
/gazebo/set_model_state
/rosout
/rosout_agg

No sign of /spawn_model :(

r0josh gravatar image r0josh  ( 2016-10-25 11:06:12 -0500 )edit

Of course gazebo_msgs/SpawnModel shows up after rossv list. But that does not mean its 'ACTIVE' or the server is up, does it?

r0josh gravatar image r0josh  ( 2016-10-25 12:03:22 -0500 )edit

First, spawn and delete are service , so you suppose to check it using rosservice

alienmon gravatar image alienmon  ( 2016-10-25 20:51:37 -0500 )edit
1

When you rosservice you will see that there are : gazebo/spawn_sdf_model so in your code instead of gazebo/spawn_model it should be gazebo/spawn_sdf_model

alienmon gravatar image alienmon  ( 2016-10-25 20:53:13 -0500 )edit

@r0josh I edited my answer.

alienmon gravatar image alienmon  ( 2016-10-25 21:00:18 -0500 )edit

Thanks a bunch!

r0josh gravatar image r0josh  ( 2016-10-26 04:47:03 -0500 )edit
1

answered 2016-10-25 16:12:11 -0500

ElizabethA gravatar image

The "Could not find any topics with /gazebo/spawn_model or /gazebo/delete_model even with rostopic list" part stuck out to me. The services (such as /gazebo/delete_model ) are listed when you call

rosservice list

ie, use rosservice, not rostopic, to check if the spawn/delete services are available.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2016-10-25 10:05:17 -0500

Seen: 5,873 times

Last updated: Oct 25 '16