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

Rviz Marker LINE_STRIP is not displayed

asked 2015-02-25 10:14:48 -0500

hammel gravatar image

hello :)

   marker_pub = rospy.Publisher('visualization_marker', Marker, queue_size=100)
   line_color = ColorRGBA()       # a nice color for my line (royalblue)
   line_color.r = 0.254902
   line_color.g = 0.411765
   line_color.b = 0.882353
   line_color.a = 1.0
   start_point = Point()        #start point
   start_point.x = 0.2
   start_point.y = 0.0
   start_point.z = 0.2
   end_point = Point()        #end point
   end_point.x = 0.7
   end_point.y = 0
   end_point.z = 0.2

   marker3 = Marker()
   marker3.id = 3
   marker3.header.frame_id = 'world'
   marker3.type = Marker.LINE_STRIP
   marker3.ns = 'Testline'
   marker3.action = 0
   marker3.scale.x = 0.1
   marker3.points.append(start_point)
   marker3.points.append(end_point)
   marker3.colors.append(line_color)
   marker3.colors.append(line_color)

   marker_pub.publish(marker3)

the above code should display a simple static line between two points. it is coded in python. the code seems okay and i added the correct marker in rviz, which displays me the correct namespace set in the code. even if i remove all the color code: no line appears :( in an other rviz scene i succesfully added two spheres, so iam wondering whats wrong here.

any help to my suggestion?

edit retag flag offensive close merge delete

Comments

2

Try setting pose.orientation.w = 1.

dornhege gravatar image dornhege  ( 2015-02-25 10:28:48 -0500 )edit

Thanks for your answer. I saw this line also in "rviz /Tutorials / Markers: Points and Lines" and tried it. Unfortunately without any success. I also tried to change the type to Marker.LINE_LIST because i just want to have a single line --> no success :(

hammel gravatar image hammel  ( 2015-02-26 01:25:06 -0500 )edit

Everything is fine. I had a lazy bug in my code, which was a little different from the posted. The above code works as it should.Thank you anyway :)

hammel gravatar image hammel  ( 2015-02-26 01:47:01 -0500 )edit

Hello I know this is kinda old but i've got the same problem of having nothing showing in rviz even so my code is structured as the answer.

My data is correctly published on the topic and i can select the topic of type marker in rviz but nothing shows. Thanks for helping.

Sleipnir gravatar image Sleipnir  ( 2022-06-22 04:42:00 -0500 )edit

@Sleipnir this is not a discussion forum, it is a Q&A site. If you have a question, please open a new question. See https://wiki.ros.org/Support for more.

jarvisschultz gravatar image jarvisschultz  ( 2022-06-22 18:08:22 -0500 )edit

@Sleipnir I've deleted your answer and reposted as a comment. I had to remove the code snippet because it was too long to fit as a comment.

jarvisschultz gravatar image jarvisschultz  ( 2022-06-22 18:09:34 -0500 )edit

@Sleipnir if you are confident you are publishing the marker (which you did indicate), I'd suggest you verify that:

  • You've explicitly filled out the marker.header.stamp with a current timestamp (if the lifetime is non-zero this is required)
  • You've set rviz to use the same fixed frame that your marker is using for a frame_id (or that there is a known transform from the marker frame_id to the fixed frame used by rviz
  • Make sure the topic in rviz for the Marker display is set correctly
jarvisschultz gravatar image jarvisschultz  ( 2022-06-22 18:12:14 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
4

answered 2017-09-17 17:58:49 -0500

updated 2017-09-17 18:14:31 -0500

Here is an example code on how to publish a line (LINE_STRIP) as a marker

#!/usr/bin/env python

import rospy
from visualization_msgs.msg import Marker
from geometry_msgs.msg import Point

rospy.init_node('line_pub_example')
pub_line_min_dist = rospy.Publisher('~line_min_dist', Marker, queue_size=1)
rospy.loginfo('Publishing example line')

while not rospy.is_shutdown():
    marker = Marker()
    marker.header.frame_id = "/my_fixed_frame"
    marker.type = marker.LINE_STRIP
    marker.action = marker.ADD

    # marker scale
    marker.scale.x = 0.03
    marker.scale.y = 0.03
    marker.scale.z = 0.03

    # marker color
    marker.color.a = 1.0
    marker.color.r = 1.0
    marker.color.g = 1.0
    marker.color.b = 0.0

    # marker orientaiton
    marker.pose.orientation.x = 0.0
    marker.pose.orientation.y = 0.0
    marker.pose.orientation.z = 0.0
    marker.pose.orientation.w = 1.0

    # marker position
    marker.pose.position.x = 0.0
    marker.pose.position.y = 0.0
    marker.pose.position.z = 0.0

    # marker line points
    marker.points = []
    # first point
    first_line_point = Point()
    first_line_point.x = 0.0
    first_line_point.y = 0.0
    first_line_point.z = 0.0
    marker.points.append(first_line_point)
    # second point
    second_line_point = Point()
    second_line_point.x = 1.0
    second_line_point.y = 1.0
    second_line_point.z = 0.0
    marker.points.append(second_line_point)

    # Publish the Marker
    pub_line_min_dist.publish(marker)

    rospy.sleep(0.5)
edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2015-02-25 10:13:35 -0500

Seen: 5,852 times

Last updated: Jun 22 '22