Refactor image related code. (#684)

- Take immutable parameter as const ref instead of pointer.
- make kCairoFormat a global constant, since it is defined in many places in cartographer and cartographer_ros, but we rely on it actually always being the same value.
master
Holger Rapp 2017-11-16 15:07:05 +01:00 committed by Wally B. Feed
parent b9015f33a7
commit 0b4e7a9443
4 changed files with 11 additions and 14 deletions

View File

@ -31,8 +31,6 @@ cairo_status_t CairoWriteCallback(void* const closure,
return CAIRO_STATUS_WRITE_ERROR;
}
constexpr cairo_format_t kCairoFormat = CAIRO_FORMAT_ARGB32;
int StrideForWidth(int width) {
const int stride = cairo_format_stride_for_width(kCairoFormat, width);
CHECK_EQ(stride % 4, 0);

View File

@ -29,6 +29,9 @@
namespace cartographer {
namespace io {
// The only cairo image format we use for Cartographer.
constexpr cairo_format_t kCairoFormat = CAIRO_FORMAT_ARGB32;
// std::unique_ptr for Cairo surfaces. The surface is destroyed when the
// std::unique_ptr is reset or destroyed.
using UniqueCairoSurfacePtr =

View File

@ -26,12 +26,12 @@ Eigen::Affine3d ToEigen(const ::cartographer::transform::Rigid3d& rigid3) {
void CairoPaintSubmapSlices(
const double scale,
std::map<::cartographer::mapping::SubmapId, SubmapSlice>* submaps,
const std::map<::cartographer::mapping::SubmapId, SubmapSlice>& submaps,
cairo_t* cr, std::function<void(const SubmapSlice&)> draw_callback) {
cairo_scale(cr, scale, scale);
for (auto& pair : *submaps) {
auto& submap_slice = pair.second;
for (auto& pair : submaps) {
const auto& submap_slice = pair.second;
if (submap_slice.surface == nullptr) {
return;
}
@ -57,13 +57,12 @@ void CairoPaintSubmapSlices(
} // namespace
PaintSubmapSlicesResult PaintSubmapSlices(
std::map<::cartographer::mapping::SubmapId, SubmapSlice>* submaps,
const std::map<::cartographer::mapping::SubmapId, SubmapSlice>& submaps,
const double resolution) {
Eigen::AlignedBox2f bounding_box;
{
auto surface = ::cartographer::io::MakeUniqueCairoSurfacePtr(
cairo_image_surface_create(PaintSubmapSlicesResult::kCairoFormat, 1,
1));
cairo_image_surface_create(::cartographer::io::kCairoFormat, 1, 1));
auto cr =
::cartographer::io::MakeUniqueCairoPtr(cairo_create(surface.get()));
const auto update_bounding_box = [&bounding_box, &cr](double x, double y) {
@ -90,7 +89,7 @@ PaintSubmapSlicesResult PaintSubmapSlices(
auto surface =
::cartographer::io::MakeUniqueCairoSurfacePtr(cairo_image_surface_create(
PaintSubmapSlicesResult::kCairoFormat, size.x(), size.y()));
::cartographer::io::kCairoFormat, size.x(), size.y()));
{
auto cr =
::cartographer::io::MakeUniqueCairoPtr(cairo_create(surface.get()));

View File

@ -27,9 +27,6 @@ namespace cartographer {
namespace io {
struct PaintSubmapSlicesResult {
// Data format for 'surface'.
static constexpr cairo_format_t kCairoFormat = CAIRO_FORMAT_ARGB32;
PaintSubmapSlicesResult(::cartographer::io::UniqueCairoSurfacePtr surface,
Eigen::Array2f origin)
: surface(std::move(surface)), origin(origin) {}
@ -59,8 +56,8 @@ struct SubmapSlice {
};
PaintSubmapSlicesResult PaintSubmapSlices(
std::map<::cartographer::mapping::SubmapId, SubmapSlice>* submaps,
const double resolution);
const std::map<::cartographer::mapping::SubmapId, SubmapSlice>& submaps,
double resolution);
} // namespace io
} // namespace cartographer