$search
Classes | |
class | CartesianControl |
class | DisparityRenderer |
Fills the Z Buffer based on a disparity image. More... | |
class | Gripper |
class | ImageOverlay |
class | Line |
class | MeshObject |
class | MeshObjectSwitcher |
class | PointCloud |
A visual representation of a set of points. More... | |
class | PointCloudRenderable |
class | UniqueStringManager |
Typedefs | |
typedef boost::shared_ptr < PointCloudRenderable > | PointCloudRenderablePtr |
typedef std::vector < PointCloudRenderablePtr > | V_PointCloudRenderable |
Functions | |
int | getNextInt () |
void | getPoint (const stereo_msgs::DisparityImage &disparity_image, const sensor_msgs::CameraInfo &camera_info, unsigned int h, unsigned int w, float &x, float &y, float &z) |
Get the 3D coordinates of a point given its image coordinates and the disparity image. | |
void | getPoint (const sensor_msgs::PointCloud2 &cloud, unsigned int h, unsigned int w, float &x, float &y, float &z) |
Get a point as three floats from a dense point cloud using image coordinates. | |
void | getValue (const sensor_msgs::Image &image, unsigned int h, unsigned int w, float &val) |
Get the value from an image at given image coordinates as a float. | |
bool | hasDisparityValue (const stereo_msgs::DisparityImage &disparity_image, unsigned int h, unsigned int w) |
Check if a disparity image as a valid value at given image coordinates. | |
bool | hasPoint (const sensor_msgs::Image &image, unsigned int h, unsigned int w) |
Check if an image has a value at given image coordinates that is not inf or nan. | |
bool | hasPoint (const sensor_msgs::PointCloud2 &cloud, unsigned int h, unsigned int w) |
Check if a dense point cloud has a point at given image coordinates. | |
void | projectTo3d (float u, float v, float disparity, const stereo_msgs::DisparityImage &disparity_image, const sensor_msgs::CameraInfo &camera_info, float &x, float &y, float &z) |
void | setValue (sensor_msgs::Image &image, unsigned int h, unsigned int w, float val) |
Set the value from an image at given image coordinates as a float. | |
void | updateCamera (Ogre::Camera *camera, const sensor_msgs::CameraInfo &camera_info) |
Variables | |
static float | g_point_vertices [3] |
A few tools for retrieving points and info from point clouds, images or disparity images, and converting from 2D to 3D coordinates.
typedef boost::shared_ptr<PointCloudRenderable> rviz_interaction_tools::PointCloudRenderablePtr |
Definition at line 85 of file point_cloud.h.
typedef std::vector<PointCloudRenderablePtr> rviz_interaction_tools::V_PointCloudRenderable |
Definition at line 86 of file point_cloud.h.
int rviz_interaction_tools::getNextInt | ( | ) | [inline] |
Definition at line 38 of file unique_string_manager.h.
void rviz_interaction_tools::getPoint | ( | const stereo_msgs::DisparityImage & | disparity_image, | |
const sensor_msgs::CameraInfo & | camera_info, | |||
unsigned int | h, | |||
unsigned int | w, | |||
float & | x, | |||
float & | y, | |||
float & | z | |||
) | [inline] |
Get the 3D coordinates of a point given its image coordinates and the disparity image.
Definition at line 122 of file image_tools.h.
void rviz_interaction_tools::getPoint | ( | const sensor_msgs::PointCloud2 & | cloud, | |
unsigned int | h, | |||
unsigned int | w, | |||
float & | x, | |||
float & | y, | |||
float & | z | |||
) | [inline] |
Get a point as three floats from a dense point cloud using image coordinates.
Definition at line 49 of file image_tools.h.
void rviz_interaction_tools::getValue | ( | const sensor_msgs::Image & | image, | |
unsigned int | h, | |||
unsigned int | w, | |||
float & | val | |||
) | [inline] |
Get the value from an image at given image coordinates as a float.
Definition at line 69 of file image_tools.h.
bool rviz_interaction_tools::hasDisparityValue | ( | const stereo_msgs::DisparityImage & | disparity_image, | |
unsigned int | h, | |||
unsigned int | w | |||
) | [inline] |
Check if a disparity image as a valid value at given image coordinates.
Definition at line 94 of file image_tools.h.
bool rviz_interaction_tools::hasPoint | ( | const sensor_msgs::Image & | image, | |
unsigned int | h, | |||
unsigned int | w | |||
) | [inline] |
Check if an image has a value at given image coordinates that is not inf or nan.
Definition at line 84 of file image_tools.h.
bool rviz_interaction_tools::hasPoint | ( | const sensor_msgs::PointCloud2 & | cloud, | |
unsigned int | h, | |||
unsigned int | w | |||
) | [inline] |
Check if a dense point cloud has a point at given image coordinates.
Definition at line 59 of file image_tools.h.
void rviz_interaction_tools::projectTo3d | ( | float | u, | |
float | v, | |||
float | disparity, | |||
const stereo_msgs::DisparityImage & | disparity_image, | |||
const sensor_msgs::CameraInfo & | camera_info, | |||
float & | x, | |||
float & | y, | |||
float & | z | |||
) | [inline] |
Get the 3d coordinates of a point, given its image coordinates, its disparity value, as well as the images themselves which contain additional calibration information
Definition at line 106 of file image_tools.h.
void rviz_interaction_tools::setValue | ( | sensor_msgs::Image & | image, | |
unsigned int | h, | |||
unsigned int | w, | |||
float | val | |||
) | [inline] |
Set the value from an image at given image coordinates as a float.
Definition at line 76 of file image_tools.h.
void rviz_interaction_tools::updateCamera | ( | Ogre::Camera * | camera, | |
const sensor_msgs::CameraInfo & | camera_info | |||
) |
Definition at line 35 of file camera_tools.cpp.
float rviz_interaction_tools::g_point_vertices[3] [static] |
{ 0.0f, 0.0f, 0.0f }
Definition at line 51 of file point_cloud.cpp.