#include <FindObjectROS.h>
Public Slots | |
void | publish (const find_object::DetectionInfo &info, const find_object::Header &header, const cv::Mat &depth, float depthConstant) |
void | publish (const find_object::DetectionInfo &info, const find_object::Header &header, const cv::Mat &depth, float depthConstant) |
Public Slots inherited from find_object::FindObject | |
void | addObjectAndUpdate (const cv::Mat &image, int id=0, const QString &filePath=QString()) |
void | detect (const cv::Mat &image) |
void | detect (const cv::Mat &image, const find_object::Header &header, const cv::Mat &depth, float depthConstant) |
void | removeObjectAndUpdate (int id) |
Public Member Functions | |
FindObjectROS (QObject *parent=0) | |
FindObjectROS (rclcpp::Node *node) | |
virtual | ~FindObjectROS () |
virtual | ~FindObjectROS () |
Public Member Functions inherited from find_object::FindObject | |
const ObjSignature * | addObject (const QString &filePath) |
const ObjSignature * | addObject (const cv::Mat &image, int id=0, const QString &filePath=QString()) |
bool | addObject (ObjSignature *obj) |
bool | detect (const cv::Mat &image, find_object::DetectionInfo &info) const |
FindObject (bool keepImagesInRAM_=true, QObject *parent=0) | |
bool | isSessionModified () const |
int | loadObjects (const QString &dirPath, bool recursive=false) |
bool | loadSession (const QString &path, const ParametersMap &customParameters=ParametersMap()) |
bool | loadVocabulary (const QString &filePath) |
const QMap< int, ObjSignature * > & | objects () const |
void | removeAllObjects () |
void | removeObject (int id) |
bool | saveSession (const QString &path) |
bool | saveVocabulary (const QString &filePath) const |
void | updateDetectorExtractor () |
void | updateObjects (const QList< int > &ids=QList< int >()) |
void | updateVocabulary (const QList< int > &ids=QList< int >()) |
const Vocabulary * | vocabulary () const |
virtual | ~FindObject () |
Private Member Functions | |
cv::Vec3f | getDepth (const cv::Mat &depthImage, int x, int y, float cx, float cy, float fx, float fy) |
cv::Vec3f | getDepth (const cv::Mat &depthImage, int x, int y, float cx, float cy, float fx, float fy) |
Private Attributes | |
rclcpp::Node * | node_ |
std::string | objFramePrefix_ |
ros::Publisher | pub_ |
rclcpp::Publisher< std_msgs::msg::Float32MultiArray >::SharedPtr | pub_ |
ros::Publisher | pubInfo_ |
rclcpp::Publisher< find_object_2d::msg::DetectionInfo >::SharedPtr | pubInfo_ |
ros::Publisher | pubStamped_ |
rclcpp::Publisher< find_object_2d::msg::ObjectsStamped >::SharedPtr | pubStamped_ |
tf::TransformBroadcaster | tfBroadcaster_ |
std::shared_ptr< tf2_ros::TransformBroadcaster > | tfBroadcaster_ |
bool | usePnP_ |
Additional Inherited Members | |
Signals inherited from find_object::FindObject | |
void | objectsFound (const find_object::DetectionInfo &, const find_object::Header &, const cv::Mat &, float) |
Static Public Member Functions inherited from find_object::FindObject | |
static void | affineSkew (float tilt, float phi, const cv::Mat &image, cv::Mat &skewImage, cv::Mat &skewMask, cv::Mat &Ai) |
Definition at line 42 of file ros1/FindObjectROS.h.
FindObjectROS::FindObjectROS | ( | QObject * | parent = 0 | ) |
Definition at line 37 of file ros1/FindObjectROS.cpp.
|
inlinevirtual |
Definition at line 48 of file ros1/FindObjectROS.h.
FindObjectROS::FindObjectROS | ( | rclcpp::Node * | node | ) |
Definition at line 44 of file ros2/FindObjectROS.cpp.
|
inlinevirtual |
Definition at line 52 of file ros2/FindObjectROS.h.
|
private |
Definition at line 293 of file ros1/FindObjectROS.cpp.
|
private |
|
slot |
Definition at line 57 of file ros1/FindObjectROS.cpp.
|
slot |
|
private |
Definition at line 64 of file ros2/FindObjectROS.h.
|
private |
Definition at line 65 of file ros1/FindObjectROS.h.
|
private |
Definition at line 61 of file ros1/FindObjectROS.h.
|
private |
Definition at line 65 of file ros2/FindObjectROS.h.
|
private |
Definition at line 63 of file ros1/FindObjectROS.h.
|
private |
Definition at line 67 of file ros2/FindObjectROS.h.
|
private |
Definition at line 62 of file ros1/FindObjectROS.h.
|
private |
Definition at line 66 of file ros2/FindObjectROS.h.
|
private |
Definition at line 67 of file ros1/FindObjectROS.h.
|
private |
Definition at line 71 of file ros2/FindObjectROS.h.
|
private |
Definition at line 66 of file ros1/FindObjectROS.h.