0
$\begingroup$

Rosanswers logo

Hi there,

I would like to place a visual marker representing the goal line (through which the robot should pass) in rviz. IMHO, this code should do the trick

#include <ros/ros.h>
#include <visualization_msgs/Marker.h>

int main( int argc, char** argv )
{
  ros::init(argc, argv, "goal_marker");
  ros::NodeHandle n;
  ros::Publisher marker_pub = n.advertise<visualization_msgs::Marker>("visualization_marker", 1);

  // Set our initial shape type to be a cube
  uint32_t shape = visualization_msgs::Marker::ARROW;

  visualization_msgs::Marker marker;

  // Set the frame ID and timestamp.  See the TF tutorials for information on these.
  marker.header.frame_id = "/map";
  marker.header.stamp = ros::Time::now();

  // set other marker properties
  ...
  // set other marker properties end
  
  marker.lifetime = ros::Duration();

  // Publish the marker
  marker_pub.publish(marker);

}

However the marker does not appear in rviz. So in practice I end up doing this (based on Markers:Sending Basic Shapes)

int main( int argc, char** argv )
{
  ros::init(argc, argv, "goal_marker");
  ros::NodeHandle n;
  ros::Rate r(100);
  ros::Publisher marker_pub = n.advertise<visualization_msgs::Marker>("visualization_marker", 1);

  // Set our initial shape type to be a cube
  uint32_t shape = visualization_msgs::Marker::ARROW;

 for (int x=0; x<2; x++){
    visualization_msgs::Marker marker;

    // Set the frame ID and timestamp.  See the TF tutorials for information on these.
    marker.header.frame_id = "/map";
    marker.header.stamp = ros::Time::now();

    // set other marker properties
    ...
    // set other marker properties end

    marker.lifetime = ros::Duration();

    // Publish the marker
    marker_pub.publish(marker);

    r.sleep();
  }
}

Both the two iterations and the r.sleep are necessary, after their removal the marker does not appear in rviz. Any ideas why the first approach doesn't work and second does?

Would appreciate any help. Cheers!


Originally posted by popolvar on ROS Answers with karma: 3 on 2012-07-30

Post score: 0

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

I'd suspect your first program quickly returns and doesn't run a loop?

In that case, the publisher just hasn't connected yet, when you try to send the message and then your program quits, so it can never resend messages.

You should wait until publisher.getNumSubscribers() > 0, before you publish.

Here is some code snippet that I use:

bool waitForSubscribers(ros::Publisher & pub, ros::Duration timeout)
{
    if(pub.getNumSubscribers() > 0)
        return true;
    ros::Time start = ros::Time::now();
    ros::Rate waitTime(0.5);
    while(ros::Time::now() - start < timeout) {
        waitTime.sleep();
        if(pub.getNumSubscribers() > 0)
            break;
    }
    return pub.getNumSubscribers() > 0;
}

Originally posted by dornhege with karma: 31395 on 2012-07-31

This answer was ACCEPTED on the original site

Post score: 1

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.