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

visualize points rviz python

asked 2020-10-01 09:03:55 -0500

Spyros gravatar image

updated 2020-10-01 09:10:42 -0500

Hello. I am trying to visualize a set o points in rviz. I have a node who subscribes to a topic to get some data and and publishes a Marker msg on a topic.

#!/usr/bin/env python 
import rospy 
from std_msgs.msg import String
import time 
import numpy as np
import math 
from time import sleep 
from laser_line_extraction.msg import LineSegment 
from laser_line_extraction.msg import LineSegmentList 
from box_finder_var import *

from visualization_msgs.msg import Marker 
from geometry_msgs.msg import Quaternion, Pose, Point, Vector3 
from std_msgs.msg import Header, ColorRGBA

rospy.init_node('box_finder', anonymous=True)

marker_publisher = rospy.Publisher('box_visual', Marker, queue_size=100) 
rospy.sleep(1)

def callback(data):

    # calculate some points...

    ### Visualize the L-shape elements in rviz ###

    show_points_in_rviz(marker_publisher)

def show_points_in_rviz(marker_publisher):
    marker = Marker(
                ns='box_finder',
                type=Marker.POINTS,
                action=Marker.ADD,
                id=0,
                lifetime=rospy.Duration(),
                pose=Pose(Point(1.5, 1.5, 0.0), Quaternion(0, 0, 0, 1)),
                scale=Vector3(0.5, 0.5, 0.0),
                header=Header(frame_id='base_link'),
                color=ColorRGBA(0.0, 0.0, 1.0, 0.8),
                # lifetime=0,
                frame_locked=False)
    marker_publisher.publish(marker)

def box_finder():

    rospy.Subscriber("/line_segments", LineSegmentList, callback)
    rospy.spin()

if __name__ == '__main__':
    box_finder()

When I run the node I check with rostopic echo what is published and I see this:

image description

But when I add the Marker element in rviz I don't see any point there. It's clear that I'm missing something here. Can anyone help or give a hint?

I use Ubuntu 16.04, ROS kinetic, gazebo 7

Thank you in advance!

edit retag flag offensive close merge delete

Comments

In rviz, under "global options" do you have "Fixed Frame" set to "base_link"?

JackB gravatar image JackB  ( 2020-10-01 09:05:59 -0500 )edit

Also @Spyros can you please format your questions better, it is challenging to understand.

JackB gravatar image JackB  ( 2020-10-01 09:07:27 -0500 )edit

@JackB yes, fixted frame is set to base_link

Spyros gravatar image Spyros  ( 2020-10-01 09:09:04 -0500 )edit

Why do you never fill out the points field? Is that not what you want to visualize? See here and look how they fill out the points and then set the marker.points field. In your message you echoed the points[] field is empty

JackB gravatar image JackB  ( 2020-10-01 09:18:19 -0500 )edit

First I try to visualize a simple point to see if it works (code above). The position of the points isn't defined by the pose element of Marker? In this case, I should have a marker at 1.5, 1.5 with respect to the base_link frame, right?

Spyros gravatar image Spyros  ( 2020-10-01 09:26:37 -0500 )edit

Incorrect, see rviz display types points. The pose that you specify represents where the object containing the points will be located (i.e. "transformed to"). If you do not fill out the points[], there will be NO points.

Edit: so sure you have a marker at (1.5, 1.5) but it is empty because you didn't fill out the points and therefore you can't visualize it. Does that make sense?

JackB gravatar image JackB  ( 2020-10-01 09:38:11 -0500 )edit

@Spyros any update on this?

JackB gravatar image JackB  ( 2020-10-02 07:43:03 -0500 )edit

Yes, thanks a lot for the help. I played around a bit with it. I managed to make the points appear. If I get it correctly the points given in points[] are shown with respect to the position given in pose and the given coordinates frame, right? Also, I didn't understand what is the purpose of the frame_locked (I read the documentation but I didn't get the explanation). I tried both false and true but it didn't change anything on the output.

Spyros gravatar image Spyros  ( 2020-10-03 02:29:28 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-10-03 16:35:05 -0500

JackB gravatar image

Condensing comments into an answer:

When you make a Marker visualization_msg and you want to visualize Points there is a difference between the marker's position and the point's position. The markers positions is specified by a pose and a frame_id which essentially describes in the 3D world where the marker object will be placed. The marker object itself contains an array of points each specified by a position, which is measured relative the origin of the marker object.

Therefore in order to visualize a Marker containing Points, you need to specify the pose of the Marker itself, and then the location of the Points within that marker object.

See the comments for two links which are better understood in context in-situ.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2020-10-01 09:03:55 -0500

Seen: 1,496 times

Last updated: Oct 03 '20