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

Error publishing data to topic

asked 2021-09-11 09:08:34 -0500

horvath.daniel gravatar image

updated 2021-09-11 09:09:08 -0500

Hello! I was working on a small python program to control a robot arm in Gazebo. My goal with this small program is to make the arm do an oscillating motion and I use /joint_group_pos_controller/command to publish the joint states.

This is the code:

#!/usr/bin/env python
# license removed for brevity
import rospy
from std_msgs.msg import String
from std_msgs.msg import Float64MultiArray
#from trajectory_msgs import JointTrajectory

def talker():
    pub = rospy.Publisher('/joint_group_pos_controller/command', Float64MultiArray, queue_size=10)
    rospy.init_node('arm_move_control', anonymous=True)
    rate = rospy.Rate(10) # 10hz

    while not rospy.is_shutdown():
        hello_str = "hello world %s" % rospy.get_time()
        rospy.loginfo(hello_str)
        data = [0.0, -2.0, 0.0, -1.57, 0.0, -0.5]
        pub.publish(1,data)
        rospy.sleep(4)
        data = [0.0, -1.57, 0.0, -2.0, 0.0, -1.5]
        pub.publish(1,data)
        rospy.sleep(4)

    if rospy.is_shutdown():
        rospy.loginfo("---- SHUTTING DOWN ----")

if __name__ == '__main__':
    try:
        talker()
    except rospy.ROSInterruptException:
        pass

So when I run the code I get this error:

[INFO] [1631362769.809577, 0.000000]: hello world 0.0
Traceback (most recent call last):
  File "/home/hdani-ros/catkin_ws/src/ur_keyboard_teleop/scripts/ur_keyboard_teleop.py", line 28, in <module>
    talker()
  File "/home/hdani-ros/catkin_ws/src/ur_keyboard_teleop/scripts/ur_keyboard_teleop.py", line 17, in talker
    pub.publish(data)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rospy/topics.py", line 879, in publish
    data = args_kwds_to_message(self.data_class, args, kwds)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rospy/msg.py", line 122, in args_kwds_to_message
    return data_class(*args)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/std_msgs/msg/_Float64MultiArray.py", line 74, in __init__
    super(Float64MultiArray, self).__init__(*args, **kwds)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/genpy/message.py", line 344, in __init__
    raise TypeError('Invalid number of arguments, args should be %s' % str(self.__slots__) + ' args are' + str(args))
TypeError: Invalid number of arguments, args should be ['layout', 'data'] args are([0.0, -2.0, 0.0, -1.57, 0.0, -0.5],)

Can someone clarify as to what I need to change in order to send just the joint states? Thanks in advance!

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2021-09-11 19:20:27 -0500

Mike Scheutzow gravatar image

The pub.publish() takes a single message, a std_msgs/Float64MultiArrray in this case.

$ rosmsg info std_msgs/Float64MultiArray
std_msgs/MultiArrayLayout layout
  std_msgs/MultiArrayDimension[] dim
    string label
    uint32 size
    uint32 stride
  uint32 data_offset
float64[] data

You need to create an instance of this message, then populate all the required fields before you pass it to publish(). Unless you can find documentation for some magic shortcut for a single-dimension array, you've got to fill in the msg accurately.

edit flag offensive delete link more

Comments

Ok, so I changed the code to this:

movement_data = Float64MultiArray()

jointStates = [0.0, -2.0, 0.0, -1.57, 0.0, -0.5]
movement_data.data = [' ', 0, 0, 0, jointStates]
pub.publish(movement_data)
rospy.sleep(4)

It now publishes and runs without errors, but the robot arm in gazebo doesn't move at all.

horvath.daniel gravatar image horvath.daniel  ( 2021-09-12 04:53:07 -0500 )edit

That does not look like a valid description of a 1-dimensional array to me, but I don't know what the receiving side is looking for.

Mike Scheutzow gravatar image Mike Scheutzow  ( 2021-09-12 08:27:34 -0500 )edit

This is what the message looks like when I publish it from the terminal (which is the method that works):

rostopic pub /joint_group_position_controller/command std_msgs/Float64MultiArray "layout:
    dim:
    - label: ' '
      size: 0
      stride: 0
    data_offset: 0
data: [0.0, -1.57, 0.0, -1.57, 0.0, 0.0]"
horvath.daniel gravatar image horvath.daniel  ( 2021-09-12 08:45:03 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2021-09-11 09:08:34 -0500

Seen: 946 times

Last updated: Sep 11 '21