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

Flickering in rviz

asked 2016-05-27 10:02:01 -0600

ravijoshi gravatar image

Hi, I am trying to visualize Baxter Robot while providing joint trajectory in rviz. I am calling rviz from following launch file-

<launch>
    <arg name="file" default="$(find kinematics_animation)/demos/baxter/joint_states.csv" />
    <param name="robot_description" command="$(find xacro)/xacro.py
    --inorder $(find baxter_description)/urdf/baxter.urdf.xacro"/>
    <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
    <node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher"/>
    <node pkg="rviz" type="rviz" respawn="false" name="rviz"
      args="-d $(find kinematics_animation)/demos/baxter/baxter_rviz_config.rviz" />
    <node pkg="kinematics_animation" type="player.py" name="baxter_animation">
        <param name="file" value="$(arg file)" />
    </node>
</launch>

Below is the snippet from python file-

def __init__(self):
    freq = 50
    self.rate = 1.0

    rospy.loginfo("Publishing frequency = "+str(freq))
    fname = rospy.get_param("~file", None)
    if fname is None:
        rospy.logerr("Must provide private param '~file'")
        rospy.signal_shutdown("No CSV file provided")
    else:
        rospy.loginfo("Animation file = "+fname)
    rospy.loginfo("Time scaling = " + str(self.rate))
    # load data:
    with open(fname, 'r') as f:
        fline = f.readline()
    self.names = fline.rstrip('\r\n').split(',')
    self.names = self.names[1:]
    self.dat = np.loadtxt(fname, skiprows=1, delimiter=',')
    self._fint = interp1d(1/float(self.rate)*self.dat[:,0], self.dat[:,1:], kind='linear', axis=0)
    self.base_time = rospy.Time.now()
    # create publisher:
    self.state_pub = rospy.Publisher("joint_states", JointState, latch=True, queue_size=3)
    # create timer:
    self.pbtimer = rospy.Timer(rospy.Duration(1/float(freq)), self.timercb)
    return

def timercb(self, time_dat):
    t = (rospy.Time.now() - self.base_time).to_sec()
    try :
        q = self._fint(t)
    except ValueError:
        q = self._fint.y[-1]
        if (t - self._fint.x[-1]) > 2.0:
            rospy.loginfo("Resetting animation!")
            self.base_time = rospy.Time.now()
    js = JointState(name=self.names, position=q)
    js.header.stamp = rospy.Time.now()
    self.state_pub.publish(js)
    return

The problem is that after calling the launch file, rvis starts flickering the Baxter arms. It feels to me that everytime, arms are going back to home position. How can I resolve this problem?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2016-05-27 10:08:29 -0600

gvdhoorn gravatar image

You cannot have two nodes publishing to the JointStates topic for the same set of joints at the same time. In your launch file you have

<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />

and you start your own node, that also publishes joint states. So the robot_state_publisher now receives joint states telling it that the joints are at their default joint position (which is probably 0, published by the joint_state_publisher) and the ones your kinematics_animation node is publishing. As a result, it publishes transforms for the '0 position' and the other positions after each other in rapid succession, resulting in what you describe as a flicker.

edit flag offensive delete link more

Comments

Oh. my mistake. Sorry. I removed the above suggested line from launch file. Animation is smooth. However, I don't see Baxter Head, Display etc. Please see the attached screenshot of rviz here. It is not able to find out various transformations

ravijoshi gravatar image ravijoshi  ( 2016-05-27 10:22:20 -0600 )edit
1

Yes, that is how things work. You'll have to have something that provides either the joint states or the TF frames. I suggest you read up on some of the involved packages.

gvdhoorn gravatar image gvdhoorn  ( 2016-05-27 10:41:53 -0600 )edit

If you want to display trajectories for only certain sets of joints, I suggest using something like moveit_visual_tools by Dave Coleman.

JointStates are really only for reporting the state of joints, nothing else.

gvdhoorn gravatar image gvdhoorn  ( 2016-05-27 10:43:17 -0600 )edit
1

Alternatively you should publish JointStates for all joints of Baxter, but keep the ones you don't want to change at their defaults (which could be 0).

gvdhoorn gravatar image gvdhoorn  ( 2016-05-27 10:47:27 -0600 )edit

Really appreciate your efforts. Thanks a lot. I want to move both the arms as decribed in input csv file, which contains joint angle for all joints. It is working but I can't see Baxter head. I am attaching screenshot please see https://dl.dropboxusercontent.com/u/5...

ravijoshi gravatar image ravijoshi  ( 2016-05-27 11:05:27 -0600 )edit

Have you read the pages I linked to? I can't really tell you anything more than I already wrote in the comments.

gvdhoorn gravatar image gvdhoorn  ( 2016-05-27 11:14:14 -0600 )edit
1

I encountered flickering in rviz when publishing to a marker_array topic from two different publishers (I assumed unique namespace id combinations would be sufficient), changed to two separate topics and now it looks good.

lucasw gravatar image lucasw  ( 2019-10-17 19:19:37 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2016-05-27 10:02:01 -0600

Seen: 2,037 times

Last updated: May 27 '16