Pygazebo python gazebo interface
I am trying to get python and gazebo working together using pygazebo but i cannot get it to work. I know there is an old threat about it but i decided to start a new one. Old threat on python and gazebo
I am trying to make it as simple as possible and therefore only making one joint move through python. I tried to start gazebo and then insert a robot and then control one of the wheels.
Here is the model.config file:
<?xml version="1.0"?>
<model>
<name>my_robot1</name>
<version>1.0</version>
<sdf version='1.4'>model.sdf</sdf>
<author>
<name>My Name</name>
<email>me@my.email</email>
</author>
<description>
My awesome robot.
</description>
</model>
And the model.sdf file:
<?xml version='1.0'?>
<sdf version='1.4'>
<model name="my_robot">
<static>false</static>
<link name='chassis'>
<pose>0 0 .1 0 0 0</pose>
<collision name='collision'>
<geometry>
<box>
<size>.4 .2 .1</size>
</box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box>
<size>.4 .2 .1</size>
</box>
</geometry>
</visual>
<collision name='caster_collision'>
<pose>-0.15 0 -0.05 0 0 0</pose>
<geometry>
<sphere>
<radius>.05</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<slip1>1.0</slip1>
<slip2>1.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name='caster_visual'>
<pose>-0.15 0 -0.05 0 0 0</pose>
<geometry>
<sphere>
<radius>.05</radius>
</sphere>
</geometry>
</visual>
</link>
<link name="left_wheel">
<pose>0.1 0.13 0.1 0 1.5707 1.5707</pose>
<collision name="collision">
<geometry>
<cylinder>
<radius>.1</radius>
<length>.05</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder>
<radius>.1</radius>
<length>.05</length>
</cylinder>
</geometry>
</visual>
</link>
<link name="right_wheel">
<pose>0.1 -0.13 0.1 0 1.5707 1.5707</pose>
<collision name="collision">
<geometry>
<cylinder>
<radius>.1</radius>
<length>.05</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder>
<radius>.1</radius>
<length>.05</length>
</cylinder>
</geometry>
</visual>
</link>
<joint type="revolute" name="left_wheel_hinge">
<pose>0 0 -0.03 0 0 0</pose>
<child>left_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<joint type="revolute" name="right_wheel_hinge">
<pose>0 0 0.03 0 0 0</pose>
<child>right_wheel</child>
<parent>chassis</parent>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
</model>
</sdf>
And finally my pygazebo.py script:
# -*- coding: utf-8 -*-
"""
Created on Mon Nov 24 19:23:30 2014
@author: morten
"""
import trollius
from trollius import From
import pygazebo
import pygazebo.msg.joint_cmd_pb2
@trollius.coroutine
def publish_loop():
manager = yield From(pygazebo.connect())
publisher = yield From(
manager.advertise('/gazebo/default/model/joint_cmd',
'gazebo.msgs.JointCmd'))
message = pygazebo.msg.joint_cmd_pb2.JointCmd()
message.name = 'my_robot1::left_wheel_hinge'
message.axis = 0
message.force = 1.0
#while True:
yield From(publisher.publish(message))
yield From(trollius.sleep(10.0))
loop = trollius.get_event_loop()
loop.run_until_complete(publish_loop())
Any help would be appreciated.