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

Design a bounding box in Rviz using poses information

asked 2018-06-13 15:55:22 -0500

sdorman gravatar image

I'm using ROS Kinetic on Ubuntu 16.04 LTS.

I'm trying to draw a bounding box around four poses which are displayed as arrows in Rviz. I looked at using the Rviz Basic Shapes tutorial but I don't know how to adapt that code so that the box would remain around the poses if the position of the poses changed. From what I can tell, you have to manually set specific values for the vertices of the box in the Basic Shapes tutorial. I need the vertices to be determined from the pose positions.

The poses are output as <geometry_msgs/PoseArray> and represent positions of Whycon targets tracked using a usb_cam. These targets might have to move around for the desired application.

Is it possible to create this box?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2018-06-19 10:35:58 -0500

sdorman gravatar image

So I figured out how to do this. I used the Points and Lines tutorial as a reference and used the line strip function of the Rviz Markers Display types.

ros::Publisher marker_pub;
void VisPoseCallback(const geometry_msgs::PoseArrayConstPtr& msg)
{
const std::vector<geometry_msgs::Pose>& ps = msg->poses;
visualization_msgs::Marker line_strip;
line_strip.header.frame_id = "/whycon";

line_strip.header.stamp = ros::Time::now();
line_strip.ns = "lines";
line_strip.pose.orientation.w = 1.0;
line_strip.id = 0; //tag id
line_strip.type = visualization_msgs::Marker::LINE_STRIP;  //tag type
line_strip.scale.x = 0.05;
line_strip.color.b = 1.0;
line_strip.color.a = 1.0;

geometry_msgs::Point p;
p.x = ps[0].position.x;
p.y = ps[0].position.y;
p.z = ps[0].position.z;
line_strip.points.push_back(p);

I repeated the position bit for each of my poses then I subscribed to my poses message.

int main(int argc, char** argv)
{
  ros::init(argc, argv, "VisPose");
  ros::NodeHandle n;

   marker_pub = n.advertise<visualization_msgs::Marker>("line_visualization_marker", 10);
  ros::Rate r(100);
  ros::Subscriber pose_sub = n.subscribe<geometry_msgs::PoseArray>("/whycon/poses", 1, &VisPoseCallback);

  ros::spin();
}

This created a box between which moves as the poses change.

edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2018-06-13 15:55:22 -0500

Seen: 4,242 times

Last updated: Jun 19 '18