Publish Joint_State with Python to RVIZ
I have a robot that I built in URDF that I am visualizing in RVIZ. I can control the joints using the gui tool or a rostopic pub command, but I am unable to build a publisher node to interface with the rviz visualization.
The rostopic pub works fine so I tried to build a ros package that would publish the joint information to the rviz visualization. "Rostopic echo /joint_states" lists the newly published command, but the rviz model does not move.
I am able to use the following command to move the robot using a terminal:
rostopic pub -1 /joint_states sensor_msgs/JointState '{header: auto, name: ['joint0', 'joint1', 'joint2', 'joint3'], position: [1, 0.5418, -1.7297, -3.1017], velocity: [], effort: []}'
Here is the code I am trying to build to publish the same information. I built it into a package that I am running:
#!/usr/bin/env python
import rospy
from sensor_msgs.msg import JointState
from std_msgs.msg import Header
def talker():
pub = rospy.Publisher('joint_states', JointState, queue_size=10)
rospy.init_node('joint_state_publisher')
rate = rospy.Rate(10) # 10hz
hello_str = JointState()
hello_str.header = Header()
hello_str.header.stamp = rospy.Time.now()
hello_str.name = ['joint0', 'joint1', 'joint2', 'joint3']
hello_str.position = [3, 0.5418, -1.7297, -3.1017]
hello_str.velocity = []
hello_str.effort = []
pub.publish(hello_str)
rate.sleep()
if __name__ == '__main__':
try:
talker()
except rospy.ROSInterruptException:
pass
After I run the package to move the robot, rostopic list shows the new state, but the robot has not moved in RVIZ.
Which tool are you referring to here?
rqt_publisher
,joint_state_publisher
or something else?he is referring to joint_state_publisher_gui, http://wiki.ros.org/joint_state_publi...
That package didn't exist in 2015.