Classes | |
class | MapBuilder |
Functions | |
double | angleFromQuaternion (const tf::Quaternion &q) |
std::string | getWorldFrame (const tf::Transformer &tf_transformer, const std::string &child) |
template<typename T > | |
void | moveAndCopyImage (int fill, int dx, int dy, unsigned int ncol, vector< T > &map) |
template<typename T > | |
void | moveAndCopyImage (int fill, int dx, int dy, unsigned int ncol, std::vector< T > &map) |
int | offsetFromRowColNoRangeCheck (int row, int col, size_t ncol) |
Variables | |
const double | g_default_large_log_odds = 100 |
const double | g_default_max_log_odds_for_belief = 20 |
const double | g_default_p_occupied_when_laser = 0.9 |
const double | g_default_p_occupied_when_no_laser = 0.3 |
Defines a class with a local occupancy grid
double local_map::angleFromQuaternion | ( | const tf::Quaternion & | q | ) |
Return the angle from a quaternion representing a rotation around the z-axis
The quaternion in ROS is q = (x, y, z, w), so that q = (ux * sin(a/2), uy * sin(a/2), uz * sin(a/2), cos(a/2)), where a is the rotation angle and (ux, uy, uz) is the unit vector of the rotation axis. For a rotation around z, we have q = (cos(a/2), 0, 0, sin(a/2)). Thus a = 2 * atan2(z, w).
Definition at line 42 of file map_builder.cpp.
std::string local_map::getWorldFrame | ( | const tf::Transformer & | tf_transformer, |
const std::string & | child | ||
) |
Return the name of the tf frame that has no parent.
Definition at line 20 of file map_builder.cpp.
void local_map::moveAndCopyImage | ( | int | fill, |
int | dx, | ||
int | dy, | ||
unsigned int | ncol, | ||
vector< T > & | map | ||
) |
In-place move an image represented as a 1D array
The origin of the image moves relativelty to a frame F. All pixels must be moved in the opposite direction, so that what is represented by the pixels is fixed in the frame F.
[in] | fill | Default fill value |
[in] | dx | pixel displacement in x (rows) |
[in] | dy | pixel displacement in y (columns) |
[in] | ncol | number of column |
[in,out] | map | image to be moved |
Definition at line 66 of file map_builder.cpp.
void local_map::moveAndCopyImage | ( | int | fill, |
int | dx, | ||
int | dy, | ||
unsigned int | ncol, | ||
std::vector< T > & | map | ||
) |
int local_map::offsetFromRowColNoRangeCheck | ( | int | row, |
int | col, | ||
size_t | ncol | ||
) | [inline] |
Definition at line 95 of file map_builder.h.
const double local_map::g_default_large_log_odds = 100 |
Definition at line 15 of file map_builder.cpp.
const double local_map::g_default_max_log_odds_for_belief = 20 |
Definition at line 16 of file map_builder.cpp.
const double local_map::g_default_p_occupied_when_laser = 0.9 |
Definition at line 13 of file map_builder.cpp.
const double local_map::g_default_p_occupied_when_no_laser = 0.3 |
Definition at line 14 of file map_builder.cpp.