Boyoon Jung's Library Manual |
bj Namespace ReferenceBoyoon Jung's Library.
More...
|
Classes |
class | bj::EMCluster |
| A model-based clustering algorithm using Expectation-Maximization method. More...
|
class | bj::SMEMCluster |
| A model-based clustering algorithm using Split-Merge EM algorithm. More...
|
class | bj::VeryFastEMCluster |
| A very fast EM-based clustering algorithm using multiresolution kd-trees. More...
|
class | bj::MultivariateGaussian |
| A multivariate gaussian distribution. More...
|
class | bj::KalmanFilter |
| A Kalman Filter class for linear systems. More...
|
class | bj::ExtendedKalmanFilter |
| An Extended Kalman Filter class for non-linear systems. More...
|
class | bj::UnscentedKalmanFilter |
| An Unscented Kalman Filter class for non-linear systems. More...
|
class | bj::KDCluster |
| A fast data clustering algorithm using a kernel density tree. More...
|
class | bj::KDClusterSimple |
| A fast data clustering algorithm using a kernel density tree. More...
|
struct | bj::kd_node |
| Data structure for a node of a KD-tree. More...
|
struct | bj::mrkd_node |
| Data structure for a node of a multiresolution KD-tree. More...
|
class | bj::KDTree |
| A KD-Tree data structure class. More...
|
class | bj::MRKDTree |
| A multiresolution KD-Tree data structure class. More...
|
class | bj::MDP |
| A Markov Decision Process Solver. More...
|
class | bj::MDPs |
| A Markov Decision Process Solver using a sparse matrix. More...
|
class | bj::MDPf |
| A Markov Decision Process Solver without storing matrices. More...
|
class | bj::ParticleFilter |
| A regular particle filter class. More...
|
class | bj::AdaptiveParticleFilter |
| An adaptive particle filter class. More...
|
struct | bj::sm_item< element_t > |
| Data structure of an element in a sparse matrix. More...
|
class | bj::SparseMatrix< element_t > |
| A multi-dimensional sparse matrix using a STL list. More...
|
class | bj::AviCamera |
| A wrapper class for avifile APIs. More...
|
class | bj::Camera |
| An abstract class for camera devices. More...
|
class | bj::DC1394Camera |
| A wrapper class for libdc1394 APIs. More...
|
class | bj::DC1394Stereo |
| A device driver for synchronized firewire stereo heads. More...
|
class | bj::DV1394Camera |
| A wrapper class for libdv APIs. More...
|
class | bj::GazeboCamera |
| A simulated camera class for Gazebo simulator. More...
|
class | bj::GazeboStereo |
| A simulated stereo head class for Gazebo simulator. More...
|
class | bj::IndependentStereo |
| A convenient way to access two independent cameras like a stereo head. More...
|
class | bj::MovieWriter |
| A movie recoder class using libquicktime library. More...
|
class | bj::MpegCamera |
| A wrapper class for libmpeg3 APIs. More...
|
class | bj::QuicktimeCamera |
| A wrapper class for libquicktime APIs. More...
|
class | bj::Stereo |
| An abstract class for stereo camera devices. More...
|
class | bj::V4L2Camera |
| A wrapper class for Video4Linux2 APIs. More...
|
class | bj::V4LCamera |
| A wrapper class for Video4Linux APIs. More...
|
class | bj::PThread |
| A wrapper class for POSIX thread functions. More...
|
class | bj::PMutex |
| A wrapper class for a POSIX mutex device. More...
|
class | bj::PCondition |
| A wrapper class for a POSIX condition variable. More...
|
class | bj::PSemaphore |
| A wrapper class for a POSIX semaphore. More...
|
class | bj::RS232 |
| A RS-232 serial port interface. More...
|
class | bj::RS422 |
| A RS-422 serial port interface. More...
|
class | bj::Inhibition |
| An inhibition signal class for Subsumption architecture. More...
|
class | bj::Behavior |
| A base class to implement robot behaviors. More...
|
class | bj::GzClient |
| A client interface to Gazebo simulator. More...
|
class | bj::GzCamera |
| A camera interface to Gazebo simulator. More...
|
class | bj::GzFactory |
| A factory interface to Gazebo simulator. More...
|
class | bj::GzFiducial |
| A fiducial interface to Gazebo simulator. More...
|
class | bj::GzGPS |
| A GPS interface to Gazebo simulator. More...
|
class | bj::GzGripper |
| A gripper interface to Gazebo simulator. More...
|
class | bj::GzHUD |
| A HUD interface to Gazebo simulator. More...
|
class | bj::GzLaser |
| A laser interface to Gazebo simulator. More...
|
class | bj::GzPosition |
| A position interface to Gazebo simulator. More...
|
class | bj::GzPower |
| A power interface to Gazebo simulator. More...
|
class | bj::GzPTZ |
| A PTZ interface to Gazebo simulator. More...
|
class | bj::GzSonar |
| A sonar interface to Gazebo simulator. More...
|
class | bj::GzStereo |
| A stereo head interface to Gazebo simulator. More...
|
class | bj::GzTruth |
| A truth interface to Gazebo simulator. More...
|
class | bj::GzWifi |
| A wifi interface to Gazebo simulator. More...
|
struct | bj::canbus_param_t |
| Data structure for CAN bus parameters. More...
|
struct | bj::can_message_t |
| Data structure for CAN messages. More...
|
class | bj::KvaserCAN |
| A wrapper class to Kvaser canlib library. More...
|
class | bj::OccupancyMap |
| A local occupancy grid map. More...
|
class | bj::Pioneer |
| A device driver for robots using P2OS. More...
|
class | bj::PlayerUpdater |
| A POSIX thread to update sensory data from a Player server. More...
|
class | bj::SegwayRMP |
| A device driver for Segway RMP robots. More...
|
class | bj::VFH |
| A Vector Field Histogram (VFH) algorithm. More...
|
struct | bj::VFH::pc_t |
| Pre-computed element data type.
|
struct | bj::VFH::candidate_t |
| Candidate direction data type.
|
class | bj::SDLReader |
| A data retriever from a SDLog file. More...
|
struct | bj::sdl_odometer_t |
| Data structure for odometer data. More...
|
struct | bj::sdl_gps_t |
| Data structure for GPS data. More...
|
struct | bj::sdl_sonar_t |
| Data structure for sonar data. More...
|
struct | bj::sdl_laser_t |
| Data structure for laser data. More...
|
struct | bj::sdl_imu_t |
| Data structure for IMU data. More...
|
struct | bj::sdl_camera_t |
| Data structure for camera data. More...
|
struct | bj::sdl_stereo_t |
| Data structure for stereo camera data. More...
|
struct | bj::sdl_motor_t |
| Data structure for motor commands. More...
|
struct | bj::sdl_data_t |
| Data structure for all data. More...
|
class | bj::SDLWriter |
| A data logger into a SDLog file. More...
|
struct | bj::satinfo_t |
| Data structure for satellite information. More...
|
class | bj::NMEAParser |
| Tokenizer for NMEA sentences. More...
|
class | bj::GPS |
| A device driver for GPS units. More...
|
class | bj::DGPS |
| A device driver for differential GPS units. More...
|
struct | bj::imu_vector_t |
| Data structure for IMU raw vectors. More...
|
struct | bj::imu_matrix_t |
| Data structure for an IMU matrix. More...
|
struct | bj::imu_quaternion_t |
| Data structure for an IMU quaternion. More...
|
struct | bj::imu_euler_t |
| Data structure for IMU Euler angles. More...
|
struct | bj::imu_voltage_t |
| Data structure for IMU raw voltage values. More...
|
struct | bj::imu_temperature_t |
| Data structure for IMU temperature. More...
|
class | bj::MicroStrain3DMG |
| A device driver for MicroStrain 3DM-G IMU. More...
|
class | bj::Joystick |
| A device driver for joystick devices. More...
|
struct | bj::laser_data_t |
| Data structure for laser data. More...
|
class | bj::SICKLaser |
| A device driver for a SICK laser rangefinder. More...
|
class | bj::Visca |
| A device driver for Sony VISCA protocol. More...
|
class | bj::BayesianMotionFilter |
| A bayesian filter for motion tracking. More...
|
class | bj::BjImage |
| A wrapper class for IplImage data structure. More...
|
class | bj::CameraEgomotion |
| An egomotion compensation algorithm. More...
|
class | bj::DewarpFilter |
| A dewarping filter for omni-directional camera images. More...
|
class | bj::FeatureTracker |
| A salient feature tracking algorithm. More...
|
class | bj::ImageServerThread |
| A thread to manage a ImageClient list. More...
|
class | bj::ImageServer |
| A thread-based server to send images to ImageClient. More...
|
class | bj::ImageClient |
| A client to receive images from ImageServer. More...
|
class | bj::ParticleMotionFilter |
| A particle filter for motion tracking. More...
|
class | bj::ModelEstimation |
| A Model estimation algorithm using Linear Regression method. More...
|
class | bj::Transform |
| Image transformation methods using various models. More...
|
Enumerations |
enum | camera_t {
V4L_CAMERA,
V4L2_CAMERA,
DC1394_CAMERA,
DV1394_CAMERA,
QUICKTIME_CAMERA,
MPEG_CAMERA,
AVI_CAMERA,
GAZEBO_CAMERA,
NO_CAMERA
} |
| Camera device type. More...
|
enum | bayer_t {
BAYER_BGGR,
BAYER_GRBG,
BAYER_GBRG,
BAYER_RGGB,
BAYER_NONE
} |
| Bayer tiling format. More...
|
enum | stereo_t { DC1394_STEREO,
GAZEBO_STEREO,
INDEPENDENT_STEREO,
NO_STEREO
} |
| Stereo camera device type. More...
|
enum | pioneer_t { P2DX = 0,
P2DXe = 1,
P2AT = 2,
UNKNOWN_PIONEER = 3
} |
enum | robot_t { PIONEER = 0,
SEGWAYRMP = 1,
GAZEBO = 2,
UNKNOWN_ROBOT = -1
} |
| Robot type. More...
|
enum | transform_t { NoTransform,
Linear,
BiLinear,
PseudoPerspective
} |
Functions |
camera_t | check_camera_type (char *file) |
| Check a camera type.
|
Camera * | open_camera (char *file, int width=320, int height=240, int channel=-1, float fps=30, bool realtime=true, bool color=true) |
| Open a camera device.
|
Camera * | open_camera (char *file, bool realtime, bool color) |
| Open a camera device.
|
Camera * | open_camera (char *file, int width, int height, bool realtime, bool color) |
| Open a camera device.
|
Camera * | open_camera (char *file, int width, int height, int channel, bool realtime, bool color) |
| Open a camera device.
|
stereo_t | check_stereo_type (char *file) |
| Check a stereo camera type.
|
Stereo * | open_stereo (char *leftfile, int leftchannel=-1, char *rightfile=0, int rightchannel=-1, int width=320, int height=240, float fps=30, bool realtime=true, bool color=true, bayer_t bayer=BAYER_NONE) |
| Open a stereo camera device.
|
bool | load_calibration_parameters (char *file, float *intrinsic, float *distortion) |
| Load the parameters for camera calibration from a file.
|
bool | save_calibration_parameters (char *file, float *intrinsic, float *distortion) |
| Save the parameters for camera calibration into a file.
|
int | v4l_check_version (const char *file) |
| Determine the V4L version of a device file.
|
bool | gazebo_check_ipc_camera (const char *camera_id, int server_id=0) |
| Check if a string is a valid gazebo camera.
|
bool | gazebo_check_ipc_stereo (const char *stereo_id, int server_id=0) |
| Check if a string is a valid gazebo stereo head.
|
void | cvt_rgb555_rgb (int w, int h, unsigned char *rgb555, unsigned char *rgb) |
| Convert RGB555 to RGB888.
|
void | cvt_rgb565_rgb (int w, int h, unsigned char *rgb565, unsigned char *rgb) |
| Convert RGB565 to RGB888.
|
void | cvt_rgb888_rgb (int w, int h, unsigned char *rgb888, unsigned char *rgb) |
| Convert RGB888 to RGB888.
|
void | cvt_rgb8888_rgb (int w, int h, unsigned char *rgb8888, unsigned char *rgb) |
| Convert RGB8888 to RGB888.
|
void | cvt_bgr888_rgb (int w, int h, unsigned char *bgr888, unsigned char *rgb) |
| Convert BGR888 to RGB888.
|
void | cvt_bgr8888_rgb (int w, int h, unsigned char *bgr8888, unsigned char *rgb) |
| Convert BGR8888 to RGB888.
|
void | cvt_yuv444_rgb (int w, int h, unsigned char *yuv444, unsigned char *rgb) |
| Convert YUV444 to RGB888.
|
void | cvt_yuv422_rgb (int w, int h, unsigned char *yuv422, unsigned char *rgb) |
| Convert YUV422 to RGB888.
|
void | cvt_yuv411_rgb (int w, int h, unsigned char *yuv411, unsigned char *rgb) |
| Convert YUV411 to RGB888.
|
void | cvt_yuv420p_rgb (int w, int h, unsigned char *yuv420p, unsigned char *rgb) |
| Convert YUV420P to RGB888.
|
void | cvt_yuv410p_rgb (int w, int h, unsigned char *yuv410p, unsigned char *rgb) |
| Convert YUV410P to RGB888.
|
void | cvt_yvu420p_rgb (int w, int h, unsigned char *yvu420p, unsigned char *rgb) |
| Convert YVU420P to RGB888.
|
void | cvt_yvu410p_rgb (int w, int h, unsigned char *yvu410p, unsigned char *rgb) |
| Convert YVU410P to RGB888.
|
void | cvt_gray8_rgb (int w, int h, unsigned char *gray8, unsigned char *rgb) |
| Convert GRAY8 to RGB888.
|
void | cvt_gray16_rgb (int w, int h, unsigned char *gray16, unsigned char *rgb) |
| Convert GRAY16 to RGB888.
|
void | cvt_rgb555_bgr (int w, int h, unsigned char *rgb555, unsigned char *bgr) |
| Convert RGB555 to BGR888.
|
void | cvt_rgb555_bgr (int w, int h, int wstep, unsigned char *rgb555, char *bgr) |
| Convert RGB555 to BGR888.
|
void | cvt_rgb565_bgr (int w, int h, unsigned char *rgb565, unsigned char *bgr) |
| Convert RGB565 to BGR888.
|
void | cvt_rgb565_bgr (int w, int h, int wstep, unsigned char *rgb565, char *bgr) |
| Convert RGB565 to BGR888.
|
void | cvt_rgb888_bgr (int w, int h, unsigned char *rgb888, unsigned char *bgr) |
| Convert RGB888 to BGR888.
|
void | cvt_rgb888_bgr (int w, int h, int wstep, unsigned char *rgb888, char *bgr) |
| Convert RGB888 to BGR888.
|
void | cvt_rgb8888_bgr (int w, int h, unsigned char *rgb8888, unsigned char *bgr) |
| Convert RGB8888 to BGR888.
|
void | cvt_rgb8888_bgr (int w, int h, int wstep, unsigned char *rgb8888, char *bgr) |
| Convert RGB8888 to BGR888.
|
void | cvt_bgr888_bgr (int w, int h, unsigned char *bgr888, unsigned char *bgr) |
| Convert BGR888 to BGR888.
|
void | cvt_bgr888_bgr (int w, int h, int wstep, unsigned char *bgr888, char *bgr) |
| Convert BGR888 to BGR888.
|
void | cvt_bgr8888_bgr (int w, int h, unsigned char *bgr8888, unsigned char *bgr) |
| Convert BGR8888 to BGR888.
|
void | cvt_bgr8888_bgr (int w, int h, int wstep, unsigned char *bgr8888, char *bgr) |
| Convert BGR8888 to BGR888.
|
void | cvt_yuv444_bgr (int w, int h, unsigned char *yuv444, unsigned char *bgr) |
| Convert YUV444 to BGR888.
|
void | cvt_yuv444_bgr (int w, int h, int wstep, unsigned char *yuv444, char *bgr) |
| Convert YUV444 to BGR888.
|
void | cvt_yuv422_bgr (int w, int h, unsigned char *yuv422, unsigned char *bgr) |
| Convert YUV422 to BGR888.
|
void | cvt_yuv422_bgr (int w, int h, int wstep, unsigned char *yuv422, char *bgr) |
| Convert YUV422 to BGR888.
|
void | cvt_yuv411_bgr (int w, int h, unsigned char *yuv411, unsigned char *bgr) |
| Convert YUV411 to BGR888.
|
void | cvt_yuv411_bgr (int w, int h, int wstep, unsigned char *yuv411, char *bgr) |
| Convert YUV411 to BGR888.
|
void | cvt_yuv420p_bgr (int w, int h, unsigned char *yuv420p, unsigned char *bgr) |
| Convert YUV420P to BGR888.
|
void | cvt_yuv420p_bgr (int w, int h, int wstep, unsigned char *yuv420p, char *bgr) |
| Convert YUV420P to BGR888.
|
void | cvt_yuv410p_bgr (int w, int h, unsigned char *yuv410p, unsigned char *bgr) |
| Convert YUV410P to BGR888.
|
void | cvt_yuv410p_bgr (int w, int h, int wstep, unsigned char *yuv410p, char *bgr) |
| Convert YUV410P to BGR888.
|
void | cvt_yvu420p_bgr (int w, int h, unsigned char *yvu420p, unsigned char *bgr) |
| Convert YVU420P to BGR888.
|
void | cvt_yvu420p_bgr (int w, int h, int wstep, unsigned char *yvu420p, char *bgr) |
| Convert YVU420P to BGR888.
|
void | cvt_yvu410p_bgr (int w, int h, unsigned char *yvu410p, unsigned char *bgr) |
| Convert YVU410P to BGR888.
|
void | cvt_yvu410p_bgr (int w, int h, int wstep, unsigned char *yvu410p, char *bgr) |
| Convert YVU410P to BGR888.
|
void | cvt_gray8_bgr (int w, int h, unsigned char *gray8, unsigned char *bgr) |
| Convert GRAY8 to BGR888.
|
void | cvt_gray8_bgr (int w, int h, int wstep, unsigned char *gray8, char *bgr) |
| Convert GRAY8 to BGR888.
|
void | cvt_gray16_bgr (int w, int h, unsigned char *gray16, unsigned char *bgr) |
| Convert GRAY16 to BGR888.
|
void | cvt_gray16_bgr (int w, int h, int wstep, unsigned char *gray16, char *bgr) |
| Convert GRAY16 to BGR888.
|
void | cvt_rgb555_gray (int w, int h, unsigned char *rgb555, unsigned char *gray) |
| Convert RGB555 to GRAY8.
|
void | cvt_rgb555_gray (int w, int h, int wstep, unsigned char *rgb555, char *gray) |
| Convert RGB555 to GRAY8.
|
void | cvt_rgb565_gray (int w, int h, unsigned char *rgb565, unsigned char *gray) |
| Convert RGB565 to GRAY8.
|
void | cvt_rgb565_gray (int w, int h, int wstep, unsigned char *rgb565, char *gray) |
| Convert RGB565 to GRAY8.
|
void | cvt_rgb888_gray (int w, int h, unsigned char *rgb888, unsigned char *gray) |
| Convert RGB888 to GRAY8.
|
void | cvt_rgb888_gray (int w, int h, int wstep, unsigned char *rgb888, char *gray) |
| Convert RGB888 to GRAY8.
|
void | cvt_rgb8888_gray (int w, int h, unsigned char *rgb8888, unsigned char *gray) |
| Convert RGB8888 to GRAY8.
|
void | cvt_rgb8888_gray (int w, int h, int wstep, unsigned char *rgb8888, char *gray) |
| Convert RGB8888 to GRAY8.
|
void | cvt_bgr888_gray (int w, int h, unsigned char *bgr888, unsigned char *gray) |
| Convert BGR888 to GRAY8.
|
void | cvt_bgr888_gray (int w, int h, int wstep, unsigned char *bgr888, char *gray) |
| Convert BGR888 to GRAY8.
|
void | cvt_bgr8888_gray (int w, int h, unsigned char *bgr8888, unsigned char *gray) |
| Convert BGR8888 to GRAY8.
|
void | cvt_bgr8888_gray (int w, int h, int wstep, unsigned char *bgr8888, char *gray) |
| Convert BGR8888 to GRAY8.
|
void | cvt_yuv444_gray (int w, int h, unsigned char *yuv444, unsigned char *gray) |
| Convert YUV444 to GRAY8.
|
void | cvt_yuv444_gray (int w, int h, int wstep, unsigned char *yuv444, char *gray) |
| Convert YUV444 to GRAY8.
|
void | cvt_yuv422_gray (int w, int h, unsigned char *yuv422, unsigned char *gray) |
| Convert YUV422 to GRAY8.
|
void | cvt_yuv422_gray (int w, int h, int wstep, unsigned char *yuv422, char *gray) |
| Convert YUV422 to GRAY8.
|
void | cvt_yuv411_gray (int w, int h, unsigned char *yuv411, unsigned char *gray) |
| Convert YUV411 to GRAY8.
|
void | cvt_yuv411_gray (int w, int h, int wstep, unsigned char *yuv411, char *gray) |
| Convert YUV411 to GRAY8.
|
void | cvt_yuvp_gray (int w, int h, unsigned char *yuvp, unsigned char *gray) |
| Convert any YUV Planar to GRAY8.
|
void | cvt_yuvp_gray (int w, int h, int wstep, unsigned char *yuvp, char *gray) |
| Convert any YUV Planar to GRAY8.
|
void | cvt_gray8_gray (int w, int h, unsigned char *gray8, unsigned char *gray) |
| Convert GRAY8 to GRAY8.
|
void | cvt_gray8_gray (int w, int h, int wstep, unsigned char *gray8, char *gray) |
| Convert GRAY8 to GRAY8.
|
void | cvt_gray16_gray (int w, int h, unsigned char *gray16, unsigned char *gray) |
| Convert GRAY16 to GRAY8.
|
void | cvt_gray16_gray (int w, int h, int wstep, unsigned char *gray16, char *gray) |
| Convert GRAY16 to GRAY8.
|
Variables |
const double | DistConvFactor [] |
| Conversion factors: from a platform-dependent unit to meters.
|
const double | AngleConvFactor [] |
| Conversion factors: from a platform-dependent unit to radians.
|
const double | VelConvFactor [] |
| Conversion factors: from a platform-dependent unit to meters.
|
const double | RangeConvFactor [] |
| Conversion factors: from a platform-dependent unit to meters.
|
const int | NumSonars [] |
| Robot property: number of sonar transducers.
|
const double | SonarPoses [][P_MAX_SONARS][3] |
| Robot property: number of sonar transducers.
|
const double | MaxLinearVelocity [] |
| Robot property: maximum linear velocity in meters.
|
const double | MaxAngularVelocity [] |
| Robot property: maximum angular velocity in meters.
|
const unsigned short | CMD_NONE = 0 |
| Don't care.
|
const unsigned short | CMD_SET_MAX_VEL = 10 |
| Set maximum velocity scale factor.
|
const unsigned short | CMD_SET_MAX_ACCEL = 11 |
| Set the maximum acceleration scale factor.
|
const unsigned short | CMD_SET_MAX_TURN = 12 |
| Set the maximum turn rate scale factor.
|
const unsigned short | CMD_SET_GAIN = 13 |
| Set gain schedule.
|
const unsigned short | CMD_SET_LIMIT = 14 |
| Set the current limit scale factor.
|
const unsigned short | CMD_RESET = 50 |
| Reset integrators.
|
const unsigned short | RESET_ODOM_LEFT = 0x0001 |
| Reset the odometer of the left wheel.
|
const unsigned short | RESET_ODOM_RIGHT = 0x0002 |
| Reset the odometer of the right wheel.
|
const unsigned short | RESET_POS_ANGULAR = 0x0004 |
| Reset the angular position.
|
const unsigned short | RESET_POS_LINEAR = 0x0008 |
| Reset the linear position.
|
Detailed Description
Boyoon Jung's Library.
Enumeration Type Documentation
|
Bayer tiling format.
- Enumeration values:
-
BAYER_BGGR |
for a BGGR format. |
BAYER_GRBG |
for a GRBG format. |
BAYER_GBRG |
for a GBRG format. |
BAYER_RGGB |
for a RGGB format. |
BAYER_NONE |
for no tiling. |
|
|
- Enumeration values:
-
P2DX |
ActivMedia Pioneer2 DX. |
P2DXe |
ActivMedia Pioneer2 DXe. |
P2AT |
ActivMedia Pioneer2 AT. |
UNKNOWN_PIONEER |
Unknown. |
|
|
- Enumeration values:
-
NoTransform |
|
Linear |
|
BiLinear |
|
PseudoPerspective |
|
|
Function Documentation
void cvt_bgr8888_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
bgr8888, |
|
|
char * |
bgr |
|
) |
|
|
|
Convert BGR8888 to BGR888.
|
void cvt_bgr8888_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
bgr8888, |
|
|
unsigned char * |
bgr |
|
) |
|
|
|
Convert BGR8888 to BGR888.
|
void cvt_bgr8888_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
bgr8888, |
|
|
char * |
gray |
|
) |
|
|
|
Convert BGR8888 to GRAY8.
|
void cvt_bgr8888_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
bgr8888, |
|
|
unsigned char * |
gray |
|
) |
|
|
|
Convert BGR8888 to GRAY8.
|
void cvt_bgr8888_rgb |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
bgr8888, |
|
|
unsigned char * |
rgb |
|
) |
|
|
|
Convert BGR8888 to RGB888.
|
void cvt_bgr888_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
bgr888, |
|
|
char * |
bgr |
|
) |
[inline] |
|
|
Convert BGR888 to BGR888.
|
void cvt_bgr888_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
bgr888, |
|
|
unsigned char * |
bgr |
|
) |
[inline] |
|
|
Convert BGR888 to BGR888.
|
void cvt_bgr888_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
bgr888, |
|
|
char * |
gray |
|
) |
|
|
void cvt_bgr888_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
bgr888, |
|
|
unsigned char * |
gray |
|
) |
|
|
void cvt_bgr888_rgb |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
bgr888, |
|
|
unsigned char * |
rgb |
|
) |
|
|
|
Convert BGR888 to RGB888.
|
void cvt_gray16_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
gray16, |
|
|
char * |
bgr |
|
) |
|
|
|
Convert GRAY16 to BGR888.
|
void cvt_gray16_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
gray16, |
|
|
unsigned char * |
bgr |
|
) |
|
|
|
Convert GRAY16 to BGR888.
|
void cvt_gray16_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
gray16, |
|
|
char * |
gray |
|
) |
|
|
void cvt_gray16_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
gray16, |
|
|
unsigned char * |
gray |
|
) |
|
|
void cvt_gray16_rgb |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
gray16, |
|
|
unsigned char * |
rgb |
|
) |
|
|
|
Convert GRAY16 to RGB888.
|
void cvt_gray8_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
gray8, |
|
|
char * |
bgr |
|
) |
|
|
void cvt_gray8_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
gray8, |
|
|
unsigned char * |
bgr |
|
) |
|
|
void cvt_gray8_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
gray8, |
|
|
char * |
gray |
|
) |
[inline] |
|
void cvt_gray8_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
gray8, |
|
|
unsigned char * |
gray |
|
) |
[inline] |
|
void cvt_gray8_rgb |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
gray8, |
|
|
unsigned char * |
rgb |
|
) |
|
|
void cvt_rgb555_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
rgb555, |
|
|
char * |
bgr |
|
) |
|
|
|
Convert RGB555 to BGR888.
|
void cvt_rgb555_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
rgb555, |
|
|
unsigned char * |
bgr |
|
) |
|
|
|
Convert RGB555 to BGR888.
|
void cvt_rgb555_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
rgb555, |
|
|
char * |
gray |
|
) |
|
|
void cvt_rgb555_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
rgb555, |
|
|
unsigned char * |
gray |
|
) |
|
|
void cvt_rgb555_rgb |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
rgb555, |
|
|
unsigned char * |
rgb |
|
) |
|
|
|
Convert RGB555 to RGB888.
|
void cvt_rgb565_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
rgb565, |
|
|
char * |
bgr |
|
) |
|
|
|
Convert RGB565 to BGR888.
|
void cvt_rgb565_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
rgb565, |
|
|
unsigned char * |
bgr |
|
) |
|
|
|
Convert RGB565 to BGR888.
|
void cvt_rgb565_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
rgb565, |
|
|
char * |
gray |
|
) |
|
|
void cvt_rgb565_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
rgb565, |
|
|
unsigned char * |
gray |
|
) |
|
|
void cvt_rgb565_rgb |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
rgb565, |
|
|
unsigned char * |
rgb |
|
) |
|
|
|
Convert RGB565 to RGB888.
|
void cvt_rgb8888_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
rgb8888, |
|
|
char * |
bgr |
|
) |
|
|
|
Convert RGB8888 to BGR888.
|
void cvt_rgb8888_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
rgb8888, |
|
|
unsigned char * |
bgr |
|
) |
|
|
|
Convert RGB8888 to BGR888.
|
void cvt_rgb8888_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
rgb8888, |
|
|
char * |
gray |
|
) |
|
|
|
Convert RGB8888 to GRAY8.
|
void cvt_rgb8888_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
rgb8888, |
|
|
unsigned char * |
gray |
|
) |
|
|
|
Convert RGB8888 to GRAY8.
|
void cvt_rgb8888_rgb |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
rgb8888, |
|
|
unsigned char * |
rgb |
|
) |
|
|
|
Convert RGB8888 to RGB888.
|
void cvt_rgb888_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
rgb888, |
|
|
char * |
bgr |
|
) |
|
|
|
Convert RGB888 to BGR888.
|
void cvt_rgb888_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
rgb888, |
|
|
unsigned char * |
bgr |
|
) |
|
|
|
Convert RGB888 to BGR888.
|
void cvt_rgb888_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
rgb888, |
|
|
char * |
gray |
|
) |
|
|
void cvt_rgb888_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
rgb888, |
|
|
unsigned char * |
gray |
|
) |
|
|
void cvt_rgb888_rgb |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
rgb888, |
|
|
unsigned char * |
rgb |
|
) |
[inline] |
|
|
Convert RGB888 to RGB888.
|
void cvt_yuv410p_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
yuv410p, |
|
|
char * |
bgr |
|
) |
|
|
|
Convert YUV410P to BGR888.
|
void cvt_yuv410p_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yuv410p, |
|
|
unsigned char * |
bgr |
|
) |
|
|
|
Convert YUV410P to BGR888.
|
void cvt_yuv410p_rgb |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yuv410p, |
|
|
unsigned char * |
rgb |
|
) |
|
|
|
Convert YUV410P to RGB888.
|
void cvt_yuv411_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
yuv411, |
|
|
char * |
bgr |
|
) |
|
|
|
Convert YUV411 to BGR888.
|
void cvt_yuv411_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yuv411, |
|
|
unsigned char * |
bgr |
|
) |
|
|
|
Convert YUV411 to BGR888.
|
void cvt_yuv411_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
yuv411, |
|
|
char * |
gray |
|
) |
|
|
void cvt_yuv411_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yuv411, |
|
|
unsigned char * |
gray |
|
) |
|
|
void cvt_yuv411_rgb |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yuv411, |
|
|
unsigned char * |
rgb |
|
) |
|
|
|
Convert YUV411 to RGB888.
|
void cvt_yuv420p_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
yuv420p, |
|
|
char * |
bgr |
|
) |
|
|
|
Convert YUV420P to BGR888.
|
void cvt_yuv420p_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yuv420p, |
|
|
unsigned char * |
bgr |
|
) |
|
|
|
Convert YUV420P to BGR888.
|
void cvt_yuv420p_rgb |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yuv420p, |
|
|
unsigned char * |
rgb |
|
) |
|
|
|
Convert YUV420P to RGB888.
|
void cvt_yuv422_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
yuv422, |
|
|
char * |
bgr |
|
) |
|
|
|
Convert YUV422 to BGR888.
|
void cvt_yuv422_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yuv422, |
|
|
unsigned char * |
bgr |
|
) |
|
|
|
Convert YUV422 to BGR888.
|
void cvt_yuv422_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
yuv422, |
|
|
char * |
gray |
|
) |
|
|
void cvt_yuv422_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yuv422, |
|
|
unsigned char * |
gray |
|
) |
|
|
void cvt_yuv422_rgb |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yuv422, |
|
|
unsigned char * |
rgb |
|
) |
|
|
|
Convert YUV422 to RGB888.
|
void cvt_yuv444_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
yuv444, |
|
|
char * |
bgr |
|
) |
|
|
|
Convert YUV444 to BGR888.
|
void cvt_yuv444_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yuv444, |
|
|
unsigned char * |
bgr |
|
) |
|
|
|
Convert YUV444 to BGR888.
|
void cvt_yuv444_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
yuv444, |
|
|
char * |
gray |
|
) |
|
|
void cvt_yuv444_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yuv444, |
|
|
unsigned char * |
gray |
|
) |
|
|
void cvt_yuv444_rgb |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yuv444, |
|
|
unsigned char * |
rgb |
|
) |
|
|
|
Convert YUV444 to RGB888.
|
void cvt_yuvp_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
yuvp, |
|
|
char * |
gray |
|
) |
[inline] |
|
|
Convert any YUV Planar to GRAY8.
|
void cvt_yuvp_gray |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yuvp, |
|
|
unsigned char * |
gray |
|
) |
[inline] |
|
|
Convert any YUV Planar to GRAY8.
|
void cvt_yvu410p_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
yvu410p, |
|
|
char * |
bgr |
|
) |
|
|
|
Convert YVU410P to BGR888.
|
void cvt_yvu410p_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yvu410p, |
|
|
unsigned char * |
bgr |
|
) |
|
|
|
Convert YVU410P to BGR888.
|
void cvt_yvu410p_rgb |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yvu410p, |
|
|
unsigned char * |
rgb |
|
) |
|
|
|
Convert YVU410P to RGB888.
|
void cvt_yvu420p_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
int |
wstep, |
|
|
unsigned char * |
yvu420p, |
|
|
char * |
bgr |
|
) |
|
|
|
Convert YVU420P to BGR888.
|
void cvt_yvu420p_bgr |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yvu420p, |
|
|
unsigned char * |
bgr |
|
) |
|
|
|
Convert YVU420P to BGR888.
|
void cvt_yvu420p_rgb |
( |
int |
w, |
|
|
int |
h, |
|
|
unsigned char * |
yvu420p, |
|
|
unsigned char * |
rgb |
|
) |
|
|
|
Convert YVU420P to RGB888.
|
Variable Documentation
|
Initial value:
{
0.001534 * M_PI/180,
0.001534 * M_PI/180,
0.001534 * M_PI/180,
0.001534 * M_PI/180
}
Conversion factors: from a platform-dependent unit to radians.
|
|
Set the current limit scale factor.
|
|
Set the maximum acceleration scale factor.
|
|
Set the maximum turn rate scale factor.
|
|
Set maximum velocity scale factor.
|
|
Initial value:
{
0.84 / 1000.0,
0.485 / 1000.0,
1.32 / 1000.0,
1.0 / 1000.0
}
Conversion factors: from a platform-dependent unit to meters.
|
|
Initial value:
{
300 * M_PI/180,
360 * M_PI/180,
140 * M_PI/180,
180 * M_PI/180
}
Robot property: maximum angular velocity in meters.
|
|
Initial value:
{
1600 / 1000.0,
1800 / 1000.0,
700 / 1000.0,
1000 / 1000.0
}
Robot property: maximum linear velocity in meters.
|
|
Initial value: Robot property: number of sonar transducers.
|
|
Initial value:
{
0.268 / 1000.0,
1.000 / 1000.0,
0.268 / 1000.0,
0.268 / 1000.0
}
Conversion factors: from a platform-dependent unit to meters.
|
|
Reset the odometer of the left wheel.
|
|
Reset the odometer of the right wheel.
|
|
Reset the angular position.
|
|
Reset the linear position.
|
|
Robot property: number of sonar transducers.
|
|
Initial value:
{
1.0 / 1000.0,
1.0 / 1000.0,
1.0 / 1000.0,
1.0 / 1000.0
}
Conversion factors: from a platform-dependent unit to meters.
|
|
|
|
|
|
|