Converts a ROI in image to vector in camera frame.
More...
#include <roi_to_position_converter.h>
|
| static void | computeTrackingVector (const sensor_msgs::RegionOfInterest &roi, const cv::Mat &depth, const sensor_msgs::CameraInfo &cam_info, double max_distance, double foreground_percent, Position &pos) |
| | Get the 3D position of the ROI (in the frame of the camera) More...
|
| |
Converts a ROI in image to vector in camera frame.
| RoiToPositionConverter::RoiToPositionConverter |
( |
ros::NodeHandle & |
nh | ) |
|
|
inline |
Constructor.
- Parameters
-
| nh | Nodehandle for subscribers, publishers |
| void RoiToPositionConverter::computeTrackingVector |
( |
const sensor_msgs::RegionOfInterest & |
roi, |
|
|
const cv::Mat & |
depth, |
|
|
const sensor_msgs::CameraInfo & |
cam_info, |
|
|
double |
max_distance, |
|
|
double |
foreground_percent, |
|
|
Position & |
pos |
|
) |
| |
|
static |
Get the 3D position of the ROI (in the frame of the camera)
- Parameters
-
| roi | Region of interest to consider |
| depth | Pixel depths |
| cam_info | Camera calibration parameters |
| max_distance | Ignore pixels farther away than this |
| foreground_percent | Average over closest foreground_percent of pixels |
| pos | Returned position |
- Todo:
- (Matt) make perc configurable
- Todo:
- Matt Perform foreground/background clustering with k-means
| bool RoiToPositionConverter::getTrackingVectors |
( |
std::unordered_map< uint32_t, Position > & |
pos | ) |
|
|
virtual |
Get the stored tracking vector.
- Parameters
-
| pos | Returned tracking vectors |
- Returns
- True if successful, false otherwise
Implements BaseTracker.
| bool RoiToPositionConverter::isConnected |
( |
| ) |
|
Check whether topics are connected.
- Returns
- True if connected and false otherwise
| bool RoiToPositionConverter::trackingIsValid |
( |
| ) |
|
|
virtual |
Check whether tracking is valid.
- Returns
- True if the tracking is valid, false otherwise
Implements BaseTracker.
The documentation for this class was generated from the following files: