viz_mesh.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018-2022 Michael Ferguson
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 // Author: Michael Ferguson
18 
19 #include <ros/ros.h>
20 #include <urdf/model.h>
22 #include <visualization_msgs/MarkerArray.h>
23 
24 int main(int argc, char** argv)
25 {
26  // What mesh to visualize
27  if (argc == 1)
28  {
29  std::cerr << std::endl;
30  std::cerr << "usage:" << std::endl;
31  std::cerr << " viz_mesh link_name" << std::endl;
32  std::cerr << std::endl;
33  return -1;
34  }
35  std::string link_name = argv[1];
36 
37  // Start up ROS
38  ros::init(argc, argv, "robot_calibration_mesh_viz");
39  ros::NodeHandle nh("~");
40 
41  // Setup publisher
42  ros::Publisher pub = nh.advertise<visualization_msgs::MarkerArray>("data", 10);
43 
44  // Get robot description
45  std::string robot_description;
46  if (!nh.getParam("/robot_description", robot_description))
47  {
48  ROS_FATAL("robot_description not set!");
49  return -1;
50  }
51 
52  // Load URDF and root link name
53  urdf::Model model;
54  if (!model.initString(robot_description))
55  {
56  ROS_FATAL("Failed to parse URDF.");
57  return -1;
58  }
59  std::string root_name = model.getRoot()->name;
60 
61  // Create mesh loader
62  robot_calibration::MeshLoader loader(model);
63 
64  // Get mesh
65  robot_calibration::MeshPtr mesh = loader.getCollisionMesh(link_name);
66  if (!mesh)
67  {
68  ROS_FATAL("Unable to load mesh");
69  return -1;
70  }
71 
72  // Publish vertices as marker array
73  visualization_msgs::MarkerArray markers;
74  for (size_t t = 0; t < mesh->triangle_count; ++t)
75  {
76  // Create marker
77  visualization_msgs::Marker msg;
78  msg.header.frame_id = link_name;
79  msg.header.stamp = ros::Time::now();
80  msg.ns = link_name;
81  msg.id = t;
82  msg.type = msg.LINE_STRIP;
83  msg.pose.orientation.w = 1.0;
84  msg.scale.x = 0.005;
85  msg.scale.y = 0.005;
86  msg.scale.z = 0.005;
87  msg.color.r = 1;
88  msg.color.g = 0;
89  msg.color.b = 0;
90  msg.color.a = 1;
91  // Extract the triangle
92  int v1_idx = mesh->triangles[(3 * t) + 0];
93  int v2_idx = mesh->triangles[(3 * t) + 1];
94  int v3_idx = mesh->triangles[(3 * t) + 2];
95  geometry_msgs::Point v1;
96  v1.x = mesh->vertices[(3 * v1_idx) + 0];
97  v1.y = mesh->vertices[(3 * v1_idx) + 1];
98  v1.z = mesh->vertices[(3 * v1_idx) + 2];
99  geometry_msgs::Point v2;
100  v2.x = mesh->vertices[(3 * v2_idx) + 0];
101  v2.y = mesh->vertices[(3 * v2_idx) + 1];
102  v2.z = mesh->vertices[(3 * v2_idx) + 2];
103  geometry_msgs::Point v3;
104  v3.x = mesh->vertices[(3 * v3_idx) + 0];
105  v3.y = mesh->vertices[(3 * v3_idx) + 1];
106  v3.z = mesh->vertices[(3 * v3_idx) + 2];
107  // Add triangle as 3 line segments v1->v2, v2->v3 and v3->v1
108  msg.points.push_back(v1);
109  msg.points.push_back(v2);
110  msg.points.push_back(v3);
111  msg.points.push_back(v1);
112  // Add marker
113  markers.markers.push_back(msg);
114  }
115 
116  while (ros::ok())
117  {
118  pub.publish(markers);
119  ros::Duration(1.0).sleep();
120  }
121 
122  return 0;
123 }
ros::Publisher
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
ros.h
urdf::Model
robot_description
std::string robot_description
Definition: calibration_offset_parser_tests.cpp:7
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ok
ROSCPP_DECL bool ok()
robot_calibration::MeshPtr
std::shared_ptr< shapes::Mesh > MeshPtr
Definition: mesh_loader.h:32
robot_calibration::MeshLoader::getCollisionMesh
MeshPtr getCollisionMesh(const std::string &link_name)
Get the collision mesh associated with a link in a URDF.
Definition: mesh_loader.cpp:32
model.h
robot_calibration::MeshLoader
Definition: mesh_loader.h:34
mesh_loader.h
urdf::Model::initString
URDF_EXPORT bool initString(const std::string &xmlstring)
ROS_FATAL
#define ROS_FATAL(...)
main
int main(int argc, char **argv)
Definition: viz_mesh.cpp:24
ros::Duration::sleep
bool sleep() const
ros::Duration
t
geometry_msgs::TransformStamped t
ros::NodeHandle
ros::Time::now
static Time now()


robot_calibration
Author(s): Michael Ferguson
autogenerated on Fri Sep 1 2023 02:52:01