#include "sensor_msgs/image_encodings.h"
#include <stdexcept>
Go to the source code of this file.
Namespaces | |
namespace | sensor_msgs |
Convert between the old (sensor_msgs::PointCloud) and the new (sensor_msgs::PointCloud2) format. | |
namespace | sensor_msgs::image_encodings |
Defines | |
#define | CHECK_BIT_DEPTH(B, T) |
#define | CHECK_CHANNELS(N) |
Functions | |
int | sensor_msgs::image_encodings::bitDepth (const std::string &encoding) |
bool | sensor_msgs::image_encodings::hasAlpha (const std::string &encoding) |
bool | sensor_msgs::image_encodings::isBayer (const std::string &encoding) |
bool | sensor_msgs::image_encodings::isColor (const std::string &encoding) |
bool | sensor_msgs::image_encodings::isMono (const std::string &encoding) |
int | sensor_msgs::image_encodings::numChannels (const std::string &encoding) |
#define CHECK_BIT_DEPTH | ( | B, | |||
T | ) |
if (encoding == TYPE_##B##T##C1 || \ encoding == TYPE_##B##T##C2 || \ encoding == TYPE_##B##T##C3 || \ encoding == TYPE_##B##T##C4) \ return B; \
#define CHECK_CHANNELS | ( | N | ) |
if (encoding == TYPE_8UC##N || \ encoding == TYPE_8SC##N || \ encoding == TYPE_16UC##N || \ encoding == TYPE_16SC##N || \ encoding == TYPE_32SC##N || \ encoding == TYPE_32FC##N || \ encoding == TYPE_64FC##N) \ return N; \