#include <FindObjectROS.h>
|
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) |
|
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) |
|
|
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) |
|
Definition at line 42 of file ros1/FindObjectROS.h.
◆ FindObjectROS() [1/2]
FindObjectROS::FindObjectROS |
( |
QObject * |
parent = 0 | ) |
|
◆ ~FindObjectROS() [1/2]
virtual FindObjectROS::~FindObjectROS |
( |
| ) |
|
|
inlinevirtual |
◆ FindObjectROS() [2/2]
FindObjectROS::FindObjectROS |
( |
rclcpp::Node * |
node | ) |
|
◆ ~FindObjectROS() [2/2]
virtual FindObjectROS::~FindObjectROS |
( |
| ) |
|
|
inlinevirtual |
◆ getDepth() [1/2]
cv::Vec3f FindObjectROS::getDepth |
( |
const cv::Mat & |
depthImage, |
|
|
int |
x, |
|
|
int |
y, |
|
|
float |
cx, |
|
|
float |
cy, |
|
|
float |
fx, |
|
|
float |
fy |
|
) |
| |
|
private |
◆ getDepth() [2/2]
cv::Vec3f FindObjectROS::getDepth |
( |
const cv::Mat & |
depthImage, |
|
|
int |
x, |
|
|
int |
y, |
|
|
float |
cx, |
|
|
float |
cy, |
|
|
float |
fx, |
|
|
float |
fy |
|
) |
| |
|
private |
◆ publish [1/2]
◆ publish [2/2]
◆ node_
rclcpp::Node* FindObjectROS::node_ |
|
private |
◆ objFramePrefix_
std::string FindObjectROS::objFramePrefix_ |
|
private |
◆ pub_ [1/2]
◆ pub_ [2/2]
rclcpp::Publisher<std_msgs::msg::Float32MultiArray>::SharedPtr FindObjectROS::pub_ |
|
private |
◆ pubInfo_ [1/2]
◆ pubInfo_ [2/2]
rclcpp::Publisher<find_object_2d::msg::DetectionInfo>::SharedPtr FindObjectROS::pubInfo_ |
|
private |
◆ pubStamped_ [1/2]
◆ pubStamped_ [2/2]
rclcpp::Publisher<find_object_2d::msg::ObjectsStamped>::SharedPtr FindObjectROS::pubStamped_ |
|
private |
◆ tfBroadcaster_ [1/2]
◆ tfBroadcaster_ [2/2]
◆ usePnP_
bool FindObjectROS::usePnP_ |
|
private |
The documentation for this class was generated from the following files: