Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Forward port of #1132 for kinetic (same issue #1120 occurs in kinetic) #1134

Closed
wants to merge 1 commit into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 1 addition & 2 deletions src/rviz/default_plugin/markers/mesh_resource_marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -192,8 +192,7 @@ void MeshResourceMarker::onNewMessage(const MarkerConstPtr& old_message, const M
entity_->setMaterial(default_material);
}



update_color = true;

handler_.reset(new MarkerSelectionHandler(this, MarkerID(new_message->ns, new_message->id), context_));
handler_->addTrackedObject(entity_);
Expand Down
179 changes: 142 additions & 37 deletions src/test/mesh_marker_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,16 +8,54 @@

ros::Publisher g_marker_pub;

void publishMesh( int id, float x, float y, float r, float g, float b, float a, bool use_embedded_materials, bool mesh )
void
publishText(int id, float x, float y, const std::string & text)
{
visualization_msgs::Marker marker;
marker.header.frame_id = "/base_link";
marker.header.stamp = ros::Time::now();
marker.ns = "mesh";
marker.type = mesh ? (int) visualization_msgs::Marker::MESH_RESOURCE : (int) visualization_msgs::Marker::SPHERE;
marker.type = visualization_msgs::Marker::TEXT_VIEW_FACING;
marker.action = visualization_msgs::Marker::ADD;
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.color.r = 1;
marker.color.g = 1;
marker.color.b = 1;
marker.color.a = 1;
marker.scale.x = 0.2;
marker.scale.y = 0.2;
marker.scale.z = 0.2;
marker.text = text;
marker.id = id;
marker.pose.position.x = x;
marker.pose.position.y = y;

g_marker_pub.publish(marker);
}

void
publishMesh(
int id, float x, float y,
float r, float g, float b, float a,
bool use_embedded_materials, bool mesh)
{
using visualization_msgs::Marker;

Marker marker;
marker.header.frame_id = "/base_link";
marker.header.stamp = ros::Time::now();
marker.ns = "mesh";
if (mesh) {
marker.type = Marker::MESH_RESOURCE;
} else {
marker.type = Marker::SPHERE;
}
marker.action = Marker::ADD;
marker.pose.orientation.x = 0.0;
marker.pose.orientation.y = 0.0;
marker.pose.orientation.z = 0.1;
marker.pose.orientation.w = 1.0;
marker.scale.x = 1;
Expand All @@ -37,94 +75,161 @@ void publishMesh( int id, float x, float y, float r, float g, float b, float a,
g_marker_pub.publish(marker);
}

void publishCallback(const ros::TimerEvent&)
void
publishMeshes()
{
static uint32_t counter = 0;

ROS_INFO("Publishing");

int id = 0;
float x = 0;
float y = 0;

publishMesh( id, x, y, 1, 1, 1, 1, true, true);
publishText(id, x - 1, y, "mesh, use_embedded_materials = true");
id++;
publishText(id, x, y - 1, "rbg: 0.0 0.0 0.0, a: 0");
id++;
publishMesh(id, x, y, 0, 0, 0, 0, true, true);
id++; x++;
publishMesh( id, x, y, 1, 1, 1, .5, true, true);
publishText(id, x, y - 1, "rbg: 1.0 1.0 1.0, a: 1");
id++;
publishMesh(id, x, y, 1, 1, 1, 1, true, true);
id++; x++;
publishMesh( id, x, y, 1, 1, 1, 0, true, true);
publishText(id, x, y - 1, "rbg: 1.0 1.0 1.0, a: 0.5");
id++;
publishMesh(id, x, y, 1, 1, 1, .5, true, true);
id++; x++;
publishMesh( id, x, y, 1, 0, 0, 1, true, true);
publishText(id, x, y - 1, "rbg: 1.0 1.0 1.0, a: 0");
id++;
publishMesh(id, x, y, 1, 1, 1, 0, true, true);
id++; x++;
publishMesh( id, x, y, 1, 0, 0, .5, true, true);
publishText(id, x, y - 1, "rbg: 1.0 0.0 0.0, a: 1");
id++;
publishMesh(id, x, y, 1, 0, 0, 1, true, true);
id++; x++;
publishMesh( id, x, y, 1, 0, 0, 0, true, true);
publishText(id, x, y - 1, "rbg: 1.0 0.0 0.0, a: 0.5");
id++;
publishMesh(id, x, y, 1, 0, 0, .5, true, true);
id++; x++;
publishMesh( id, x, y, 1, .5, .5, 1, true, true);
publishText(id, x, y - 1, "rbg: 1.0 0.0 0.0, a: 0");
id++;
publishMesh(id, x, y, 1, 0, 0, 0, true, true);
id++; x++;
publishMesh( id, x, y, 1, .5, .5, .5, true, true);
publishText(id, x, y - 1, "rbg: 1.0 0.5 0.5, a: 1");
id++;
publishMesh(id, x, y, 1, .5, .5, 1, true, true);
id++; x++;
publishMesh( id, x, y, 1, .5, .5, 0, true, true);
publishText(id, x, y - 1, "rbg: 1.0 0.5 0.5, a: 0.5");
id++;
publishMesh(id, x, y, 1, .5, .5, .5, true, true);
id++; x++;
publishText(id, x, y - 1, "rbg: 1.0 0.5 0.5, a: 0");
id++;
publishMesh(id, x, y, 1, .5, .5, 0, true, true);
id++; x++;

y++; x = 0;

publishMesh( id, x, y, 1, 1, 1, 1, false, true);
publishText(id, x - 1, y, "mesh, use_embedded_materials = false");
id++;
publishMesh(id, x, y, 0, 0, 0, 0, false, true);
id++; x++;
publishMesh(id, x, y, 1, 1, 1, 1, false, true);
id++; x++;
publishMesh( id, x, y, 1, 1, 1, .5, false, true);
publishMesh(id, x, y, 1, 1, 1, .5, false, true);
id++; x++;
publishMesh( id, x, y, 1, 1, 1, 0, false, true);
publishMesh(id, x, y, 1, 1, 1, 0, false, true);
id++; x++;
publishMesh( id, x, y, 1, 0, 0, 1, false, true);
publishMesh(id, x, y, 1, 0, 0, 1, false, true);
id++; x++;
publishMesh( id, x, y, 1, 0, 0, .5, false, true);
publishMesh(id, x, y, 1, 0, 0, .5, false, true);
id++; x++;
publishMesh( id, x, y, 1, 0, 0, 0, false, true);
publishMesh(id, x, y, 1, 0, 0, 0, false, true);
id++; x++;
publishMesh( id, x, y, 1, .5, .5, 1, false, true);
publishMesh(id, x, y, 1, .5, .5, 1, false, true);
id++; x++;
publishMesh( id, x, y, 1, .5, .5, .5, false, true);
publishMesh(id, x, y, 1, .5, .5, .5, false, true);
id++; x++;
publishMesh( id, x, y, 1, .5, .5, 0, false, true);
publishMesh(id, x, y, 1, .5, .5, 0, false, true);
id++; x++;

y++; x = 0;

publishMesh( id, x, y, 1, 1, 1, 1, true, false);
publishText(id, x - 1, y, "sphere, use_embedded_materials = true");
id++;
publishMesh(id, x, y, 0, 0, 0, 0, true, false);
id++; x++;
publishMesh(id, x, y, 1, 1, 1, 1, true, false);
id++; x++;
publishMesh( id, x, y, 1, 1, 1, .5, true, false);
publishMesh(id, x, y, 1, 1, 1, .5, true, false);
id++; x++;
publishMesh( id, x, y, 1, 1, 1, 0, true, false);
publishMesh(id, x, y, 1, 1, 1, 0, true, false);
id++; x++;
publishMesh( id, x, y, 1, 0, 0, 1, true, false);
publishMesh(id, x, y, 1, 0, 0, 1, true, false);
id++; x++;
publishMesh( id, x, y, 1, 0, 0, .5, true, false);
publishMesh(id, x, y, 1, 0, 0, .5, true, false);
id++; x++;
publishMesh( id, x, y, 1, 0, 0, 0, true, false);
publishMesh(id, x, y, 1, 0, 0, 0, true, false);
id++; x++;
publishMesh( id, x, y, 1, .5, .5, 1, true, false);
publishMesh(id, x, y, 1, .5, .5, 1, true, false);
id++; x++;
publishMesh( id, x, y, 1, .5, .5, .5, true, false);
publishMesh(id, x, y, 1, .5, .5, .5, true, false);
id++; x++;
publishMesh( id, x, y, 1, .5, .5, 0, true, false);
publishMesh(id, x, y, 1, .5, .5, 0, true, false);
id++; x++;

y++; x = 0;

publishMesh( id, x, y, 0, 0, 0, 0, true, true);
publishText(id, x - 1, y, "sphere, use_embedded_materials = false");
id++;
publishMesh(id, x, y, 0, 0, 0, 0, false, false);
id++; x++;
publishMesh(id, x, y, 1, 1, 1, 1, false, false);
id++; x++;
publishMesh(id, x, y, 1, 1, 1, .5, false, false);
id++; x++;
publishMesh(id, x, y, 1, 1, 1, 0, false, false);
id++; x++;
publishMesh(id, x, y, 1, 0, 0, 1, false, false);
id++; x++;
publishMesh(id, x, y, 1, 0, 0, .5, false, false);
id++; x++;
publishMesh(id, x, y, 1, 0, 0, 0, false, false);
id++; x++;
publishMesh(id, x, y, 1, .5, .5, 1, false, false);
id++; x++;
publishMesh(id, x, y, 1, .5, .5, .5, false, false);
id++; x++;
publishMesh(id, x, y, 1, .5, .5, 0, false, false);
id++; x++;
}

++counter;
void publishCallback(const ros::TimerEvent&)
{
return publishMeshes();
}

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

g_marker_pub = n.advertise<visualization_msgs::Marker> ("mesh_markers", 0);
ros::Timer publish_timer = n.createTimer(ros::Duration(1), publishCallback);
bool latch_only = false;
if (argc == 2) {
if (std::string(argv[1]) == "--latch-only") {
latch_only = true;
}
}

g_marker_pub = n.advertise<visualization_msgs::Marker>("mesh_markers", 0, /*latch*/ latch_only);


ros::Duration(0.1).sleep();
ros::Timer publish_timer;
if (latch_only) {
ros::Duration(1.0).sleep();
publishMeshes();
} else {
publish_timer = n.createTimer(ros::Duration(1), publishCallback);
}

ros::spin();
}