Gazebo | Ignition | Community
Ask Your Question
1

How to set a model's position using /gazebo/set_model_state service in python

asked 2019-03-20 08:26:33 -0600

kumpakri gravatar image

I want to set a model's position to origin after each measure loop, so that I can make automatically several measurements in the same conditions.

The /gazebo/set_model_state service enables us to transport the model to set position. How do I use it in python node?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2019-03-20 08:33:27 -0600

kumpakri gravatar image

The code below shows a node written in python, that will set the my_robot's position to the origin of the map. The service requires a message of type gazebo_msgs::ModelState.

import rospy 
import rospkg 
from gazebo_msgs.msg import ModelState 
from gazebo_msgs.srv import SetModelState

def main():
    rospy.init_node('set_pose')

    state_msg = ModelState()
    state_msg.model_name = 'my_robot'
    state_msg.pose.position.x = 0
    state_msg.pose.position.y = 0
    state_msg.pose.position.z = 0.3
    state_msg.pose.orientation.x = 0
    state_msg.pose.orientation.y = 0
    state_msg.pose.orientation.z = 0
    state_msg.pose.orientation.w = 0

    rospy.wait_for_service('/gazebo/set_model_state')
    try:
        set_state = rospy.ServiceProxy('/gazebo/set_model_state', SetModelState)
        resp = set_state( state_msg )

    except rospy.ServiceException, e:
        print "Service call failed: %s" % e

if __name__ == '__main__':
    try:
        main()
    except rospy.ROSInterruptException:
        pass
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2019-03-20 08:26:33 -0600

Seen: 22,031 times

Last updated: Mar 20 '19