39 #include <std_msgs/ColorRGBA.h>
49 max = std::numeric_limits<float>::min();
50 min = std::numeric_limits<float>::max();
55 if (max < costs[vH] && std::isfinite(costs[vH]))
57 if (
min > costs[vH] && std::isfinite(costs[vH]))
69 Normal ez = normal.normalized();
70 Normal ey = normal.cross(direction).normalized();
71 Normal ex = ey.cross(normal).normalized();
73 tf2::Matrix3x3 tf_basis(ex.x, ey.x, ez.x, ex.y, ey.y, ez.y, ex.z, ey.z, ez.z);
75 tf2::Vector3 tf_origin(position.
x, position.
y, position.
z);
81 geometry_msgs::Pose pose;
95 const Vector direction = next - current;
101 const float& epsilon)
104 std::array<float, 3> barycentric_coords;
110 return vec - (normal * (vec.
dot(normal) - (ref.
dot(normal))));
114 std::array<float, 3>& barycentric_coords)
121 std::array<float, 3>& barycentric_coords,
float& dist)
123 const Vector& a = vertices[0];
124 const Vector& b = vertices[1];
125 const Vector& c = vertices[2];
133 float oneOver4ASquared = 1.0 / n.
dot(n);
135 const float gamma = u.
cross(w).dot(n) * oneOver4ASquared;
137 const float beta = w.
cross(v).dot(n) * oneOver4ASquared;
138 const float alpha = 1 - gamma - beta;
140 barycentric_coords = { alpha, beta, gamma };
149 std_msgs::ColorRGBA
color(
const float& r,
const float& g,
const float& b,
const float& a)
151 std_msgs::ColorRGBA
color;
168 float denom = N.
dot(N);
176 C = edge0.
cross(vp0);
183 C = edge1.
cross(vp1);
184 if ((u = N.
dot(C)) < 0)
190 C = edge2.
cross(vp2);
191 if ((v = N.
dot(C)) < 0)
203 if (!std::isfinite(value))
204 return std_msgs::ColorRGBA();
205 std_msgs::ColorRGBA
color;
213 value = std::min(value, 1.0
f);
214 value = std::max(value, 0.0
f);
216 float h = value * 5.0f + 1.0f;
239 tf2::Vector3 v =
transform.getBasis() * axis;
246 return mesh_map::Vector(pose.pose.position.x, pose.pose.position.y, pose.pose.position.z);