Skip to content

Commit

Permalink
[viz] Use inlined byte array for heatmap png; remove VTK as dep (#307)
Browse files Browse the repository at this point in the history
  • Loading branch information
EricCousineau-TRI authored Oct 29, 2023
1 parent 5e77466 commit dc2f2e4
Show file tree
Hide file tree
Showing 7 changed files with 68 additions and 55 deletions.
2 changes: 0 additions & 2 deletions drake_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@ find_package(geometry_msgs REQUIRED)
find_package(tf2_ros REQUIRED)
find_package(tf2_eigen REQUIRED)
find_package(visualization_msgs REQUIRED)
find_package(VTK REQUIRED)

add_subdirectory(core)
add_subdirectory(tf2)
Expand Down Expand Up @@ -91,6 +90,5 @@ ament_export_dependencies(rosidl_typesupport_cpp)
ament_export_dependencies(tf2_eigen)
ament_export_dependencies(tf2_ros)
ament_export_dependencies(visualization_msgs)
ament_export_dependencies(VTK)

ament_package()
1 change: 0 additions & 1 deletion drake_ros/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
<buildtool_depend>eigen3_cmake_module</buildtool_depend>
<build_depend>eigen</build_depend>

<depend>libvtk9-dev</depend>
<depend>rclcpp</depend>
<depend>rclpy</depend>
<depend>rosgraph_msgs</depend>
Expand Down
2 changes: 1 addition & 1 deletion drake_ros/viz/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@ cc_library(
"@ros2//:rclcpp_cc",
"@ros2//:tf2_eigen_cc",
"@ros2//:visualization_msgs_cc",
"@vtk//:vtkIOImage",
],
)

Expand All @@ -22,6 +21,7 @@ cc_library(
[
"*.cc",
"*.h",
"heatmap_png.inc",
],
),
hdrs = glob(
Expand Down
3 changes: 1 addition & 2 deletions drake_ros/viz/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ foreach(hdr ${HEADERS})
endforeach()

add_library(drake_ros_viz
heatmap_png.inc
name_conventions.cc
rviz_visualizer.cc
scene_markers_system.cc
Expand All @@ -29,8 +30,6 @@ target_link_libraries(drake_ros_viz PUBLIC
${geometry_msgs_TARGETS}
${visualization_msgs_TARGETS}
)
target_link_libraries(drake_ros_viz PRIVATE
VTK::IOImage)

target_include_directories(drake_ros_viz
PUBLIC
Expand Down
52 changes: 3 additions & 49 deletions drake_ros/viz/contact_markers_system.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,11 +30,6 @@
#include <tf2_eigen/tf2_eigen.hpp>
#include <visualization_msgs/msg/marker.hpp>
#include <visualization_msgs/msg/marker_array.hpp>
#include <vtkImageData.h>
#include <vtkNew.h>
#include <vtkPNGWriter.h>
#include <vtkSmartPointer.h>
#include <vtkUnsignedCharArray.h>

namespace drake_ros {
namespace viz {
Expand Down Expand Up @@ -91,51 +86,10 @@ double calc_uv(double pressure, double min_pressure, double max_pressure) {
return std::clamp(u, 0.0, 1.0);
}

void create_color(double value, double& red, double& green, double& blue) {
red = std::clamp(((value - 0.25) * 4.0), 0.0, 1.0);
green = std::clamp(((value - 0.5) * 4.0), 0.0, 1.0);
if (value < 0.25) {
blue = std::clamp(value * 4.0, 0.0, 1.0);
} else if (value > 0.75) {
blue = std::clamp((value - 0.75) * 4.0, 0.0, 1.0);
} else {
blue = std::clamp(1.0 - (value - 0.25) * 4.0, 0.0, 1.0);
}
}

std::vector<uint8_t> GenerateHeatmapPng() {
// Make a heatmap texture
size_t kWidth = 1024;
size_t kHeight = 1;
size_t kNumChannels = 4;
vtkNew<vtkImageData> vtk_image;
vtk_image->SetDimensions(kWidth, kHeight, 1);
vtk_image->AllocateScalars(VTK_UNSIGNED_CHAR, kNumChannels);

auto image_ptr =
reinterpret_cast<unsigned char*>(vtk_image->GetScalarPointer());
double red, green, blue;
for (size_t w = 0; w < kWidth; ++w) {
const size_t offset = w * kNumChannels;
create_color(static_cast<double>(w) / kWidth, red, green, blue);
image_ptr[offset + 0] = static_cast<unsigned char>(red * 255.0);
image_ptr[offset + 1] = static_cast<unsigned char>(green * 255.0);
image_ptr[offset + 2] = static_cast<unsigned char>(blue * 255.0);
image_ptr[offset + 3] = 255;
}

auto image_writer = vtkSmartPointer<vtkPNGWriter>::New();
image_writer->SetWriteToMemory(true);
image_writer->SetInputData(vtk_image.GetPointer());
image_writer->Write();
auto vtk_results = image_writer->GetResult();
auto data_itr = vtk_results->Begin();
std::vector<uint8_t> texture;
while (data_itr != vtk_results->End()) {
texture.push_back(*data_itr);
++data_itr;
}
return texture;
return
#include "./heatmap_png.inc"
;
}

} // namespace
Expand Down
9 changes: 9 additions & 0 deletions drake_ros/viz/heatmap_png.inc
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
// AUTOGENERATED, DO NOT EDIT
{
137, 80, 78, 71, 13, 10, 26, 10, 0, 0, 0, 13, 73, 72, 68, 82, 0, 0, 4, 0, 0,
0, 0, 1, 8, 2, 0, 0, 0, 207, 108, 75, 98, 0, 0, 0, 44, 73, 68, 65, 84,
120, 156, 237, 212, 193, 13, 0, 48, 12, 194, 64, 188, 255, 208, 205, 167,
91, 216, 209, 45, 0, 72, 97, 255, 72, 148, 198, 158, 150, 60, 126, 232,
247, 155, 181, 62, 85, 16, 175, 3, 112, 247, 1, 14, 225, 11, 252, 43, 0,
0, 0, 0, 73, 69, 78, 68, 174, 66, 96, 130,
}
54 changes: 54 additions & 0 deletions drake_ros/viz/heatmap_png_generate.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,54 @@
#!/usr/bin/env python
"""
PNG encoding of a heatmap for hydroelastic.
Requires Python, PIL, and NumPy.
"""

import io
import os

import numpy as np
from PIL import Image


def main():
h = 1
w = 1024
c = 3
array = np.zeros((h, w, c), dtype=np.uint8)
values = np.linspace(0, 1, w)

red = np.clip((values - 0.25) * 4.0, 0.0, 1.0)
green = np.clip((values - 0.5) * 4.0, 0.0, 1.0)
blue = np.clip(1.0 - (values - 0.25) * 4.0, 0.0, 1.0)
mask = values < 0.25
blue[mask] = np.clip(values[mask] * 4.0, 0.0, 1.0)
mask = values > 0.75
blue[mask] = np.clip((values[mask] - 0.75) * 4.0, 0.0, 1.0)
mask = values > 0.75

array[0, :, 0] = red * 255.0
array[0, :, 1] = green * 255.0
array[0, :, 2] = blue * 255.0

image = Image.fromarray(array)
stream = io.BytesIO()
image.save(stream, format='png')
raw = stream.getvalue()

out = "// AUTOGENERATED, DO NOT EDIT\n"
out += "{\n"
for byte in raw:
out += str(int(byte)) + ", "
out += "\n}\n"

os.chdir(os.path.dirname(__file__))
with open("heatmap_png.inc", "w") as f:
f.write(out)

print("This may need to get reformatted by ament_clang_format")


if __name__ == "__main__":
main()

0 comments on commit dc2f2e4

Please sign in to comment.