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

Revision history [back]

As far as I know there is no RViz plugin for this type of sensor. In my work I've regularly used the marker message type to visualise complex information that isn't currently supported. Using this type you can visualise any 3D color mesh data you can generate. It's a bit tricky if you're new to ROS but I can post some code examples if you're using C++.

As far as I know there is no RViz plugin for this type of sensor. In my work I've regularly used the marker message type to visualise complex information that isn't currently supported. Using this type you can visualise any 3D color mesh data you can generate. It's a bit tricky if you're new to ROS but I can post some code examples if you're using C++.

Here is an example code segment that creates a marker mesh message, you'll then need to publish this message to a topic to see it in RVIZ. Once the message has been created and setup you're basically adding a color value then three vertices for each triangle, each triangle can be a different color (in my example they're all the same).

This example uses a vector of Eigen::Vector3f to represent the vertices and a vector of custom triangle structures, you can replace this with anything you wish for your own project.

// create Mesh message
visualization_msgs::Marker meshMarker;

// setup Triangle_List marker message
meshMarker.header.frame_id = "Coordinate_frame_id";
meshMarker.header.stamp = ros::Time();
meshMarker.ns = "custom_mesh";
meshMarker.id = 0;
meshMarker.type = visualization_msgs::Marker::TRIANGLE_LIST;
meshMarker.action = visualization_msgs::Marker::ADD;
meshMarker.pose.position.x = 0;
meshMarker.pose.position.y = 0;
meshMarker.pose.position.z = 0;
meshMarker.pose.orientation.x = 0.0;
meshMarker.pose.orientation.y = 0.0;
meshMarker.pose.orientation.z = 0.0;
meshMarker.pose.orientation.w = 1.0;
meshMarker.scale.x = 1;
meshMarker.scale.y = 1;
meshMarker.scale.z = 1;
meshMarker.color.a = 1.0;

// create temp vertex and color objects.
geometry_msgs::Point    vertex;
std_msgs::ColorRGBA meshColor;

// add triangles
for (int f=0; f<triangles.size(); ++f)
{
    meshColor.r = 1.0;
    meshColor.g = 0.5;
    meshColor.b = 0.0;

    meshMarker.colors.push_back(meshColor);

    // add triangle to mesh
    vertex.x = vertices[triangles[f].v1][0];
    vertex.y = vertices[triangles[f].v1][1];
    vertex.z = vertices[triangles[f].v1][2];
    meshMarker.points.push_back(vertex);

    vertex.x = vertices[triangles[f].v2][0];
    vertex.y = vertices[triangles[f].v2][1];
    vertex.z = vertices[triangles[f].v2][2];
    meshMarker.points.push_back(vertex);

    vertex.x = vertices[triangles[f].v3][0];
    vertex.y = vertices[triangles[f].v3][1];
    vertex.z = vertices[triangles[f].v3][2];
    meshMarker.points.push_back(vertex);
}