ASCO Aerial Autonomy
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
Public Member Functions | Static Public Member Functions | List of all members
RoiToPositionConverter Class Reference

Converts a ROI in image to vector in camera frame. More...

#include <roi_to_position_converter.h>

Inheritance diagram for RoiToPositionConverter:
Inheritance graph
[legend]
Collaboration diagram for RoiToPositionConverter:
Collaboration graph
[legend]

Public Member Functions

 RoiToPositionConverter (ros::NodeHandle &nh)
 Constructor. More...
 
bool getTrackingVectors (std::unordered_map< uint32_t, Position > &pos)
 Get the stored tracking vector. More...
 
bool trackingIsValid ()
 Check whether tracking is valid. More...
 
bool isConnected ()
 Check whether topics are connected. More...
 
- Public Member Functions inherited from BaseTracker
 BaseTracker (TrackingStrategy *tracking_strategy)
 
virtual bool initialize ()
 Initialze the tracker. Can simply return true if the subclass requires no additional initialization. More...
 
virtual bool getTrackingVector (Position &pos)
 Get the tracking vector. More...
 
virtual bool getTrackingVector (std::tuple< uint32_t, Position > &pos)
 Get the tracking vector. More...
 

Static Public Member Functions

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...
 

Detailed Description

Converts a ROI in image to vector in camera frame.

Constructor & Destructor Documentation

RoiToPositionConverter::RoiToPositionConverter ( ros::NodeHandle &  nh)
inline

Constructor.

Parameters
nhNodehandle for subscribers, publishers

Member Function Documentation

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
roiRegion of interest to consider
depthPixel depths
cam_infoCamera calibration parameters
max_distanceIgnore pixels farther away than this
foreground_percentAverage over closest foreground_percent of pixels
posReturned 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
posReturned 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: