Public Member Functions | |
virtual void | onInit () |
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method. | |
Private Types | |
typedef people_detect::PeopleDetectConfig | Config |
typedef dynamic_reconfigure::Server < Config > | ReconfigureServer |
Private Member Functions | |
void | do_work (const sensor_msgs::ImageConstPtr &msg, const std::string input_frame_from_msg) |
const std::string & | frameWithDefault (const std::string &frame, const std::string &image_frame) |
void | imageCallback (const sensor_msgs::ImageConstPtr &msg) |
void | imageCallbackWithInfo (const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info) |
void | reconfigureCallback (Config &new_config, uint32_t level) |
void | subscribe () |
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method. | |
void | unsubscribe () |
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this method. | |
Static Private Member Functions | |
static void | trackbarCallback (int, void *) |
Private Attributes | |
image_transport::CameraSubscriber | cam_sub_ |
Config | config_ |
bool | debug_view_ |
int | group_threshold_ |
double | hit_threshold_ |
cv::HOGDescriptor | hog_ |
image_transport::Publisher | img_pub_ |
image_transport::Subscriber | img_sub_ |
boost::shared_ptr < image_transport::ImageTransport > | it_ |
ros::Publisher | msg_pub_ |
int | padding_ |
ros::Time | prev_stamp_ |
boost::shared_ptr < ReconfigureServer > | reconfigure_server_ |
double | scale0_ |
int | win_stride_ |
std::string | window_name_ |
Static Private Attributes | |
static bool | need_config_update_ = false |
Definition at line 57 of file people_detect_nodelet.cpp.
typedef people_detect::PeopleDetectConfig people_detect::PeopleDetectNodelet::Config [private] |
Definition at line 66 of file people_detect_nodelet.cpp.
typedef dynamic_reconfigure::Server<Config> people_detect::PeopleDetectNodelet::ReconfigureServer [private] |
Definition at line 67 of file people_detect_nodelet.cpp.
void people_detect::PeopleDetectNodelet::do_work | ( | const sensor_msgs::ImageConstPtr & | msg, |
const std::string | input_frame_from_msg | ||
) | [inline, private] |
Definition at line 117 of file people_detect_nodelet.cpp.
const std::string& people_detect::PeopleDetectNodelet::frameWithDefault | ( | const std::string & | frame, |
const std::string & | image_frame | ||
) | [inline, private] |
Definition at line 95 of file people_detect_nodelet.cpp.
void people_detect::PeopleDetectNodelet::imageCallback | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [inline, private] |
Definition at line 107 of file people_detect_nodelet.cpp.
void people_detect::PeopleDetectNodelet::imageCallbackWithInfo | ( | const sensor_msgs::ImageConstPtr & | msg, |
const sensor_msgs::CameraInfoConstPtr & | cam_info | ||
) | [inline, private] |
Definition at line 102 of file people_detect_nodelet.cpp.
virtual void people_detect::PeopleDetectNodelet::onInit | ( | ) | [inline, virtual] |
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
Reimplemented from opencv_apps::Nodelet.
Definition at line 207 of file people_detect_nodelet.cpp.
void people_detect::PeopleDetectNodelet::reconfigureCallback | ( | Config & | new_config, |
uint32_t | level | ||
) | [inline, private] |
Definition at line 85 of file people_detect_nodelet.cpp.
void people_detect::PeopleDetectNodelet::subscribe | ( | ) | [inline, private, virtual] |
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
Implements opencv_apps::Nodelet.
Definition at line 190 of file people_detect_nodelet.cpp.
static void people_detect::PeopleDetectNodelet::trackbarCallback | ( | int | , |
void * | |||
) | [inline, static, private] |
Definition at line 112 of file people_detect_nodelet.cpp.
void people_detect::PeopleDetectNodelet::unsubscribe | ( | ) | [inline, private, virtual] |
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this method.
Implements opencv_apps::Nodelet.
Definition at line 199 of file people_detect_nodelet.cpp.
Definition at line 61 of file people_detect_nodelet.cpp.
Definition at line 68 of file people_detect_nodelet.cpp.
bool people_detect::PeopleDetectNodelet::debug_view_ [private] |
Definition at line 71 of file people_detect_nodelet.cpp.
int people_detect::PeopleDetectNodelet::group_threshold_ [private] |
Definition at line 83 of file people_detect_nodelet.cpp.
double people_detect::PeopleDetectNodelet::hit_threshold_ [private] |
Definition at line 79 of file people_detect_nodelet.cpp.
cv::HOGDescriptor people_detect::PeopleDetectNodelet::hog_ [private] |
Definition at line 77 of file people_detect_nodelet.cpp.
Definition at line 59 of file people_detect_nodelet.cpp.
Definition at line 60 of file people_detect_nodelet.cpp.
boost::shared_ptr<image_transport::ImageTransport> people_detect::PeopleDetectNodelet::it_ [private] |
Definition at line 64 of file people_detect_nodelet.cpp.
Definition at line 62 of file people_detect_nodelet.cpp.
bool people_detect::PeopleDetectNodelet::need_config_update_ = false [static, private] |
Definition at line 75 of file people_detect_nodelet.cpp.
int people_detect::PeopleDetectNodelet::padding_ [private] |
Definition at line 81 of file people_detect_nodelet.cpp.
Definition at line 72 of file people_detect_nodelet.cpp.
boost::shared_ptr<ReconfigureServer> people_detect::PeopleDetectNodelet::reconfigure_server_ [private] |
Definition at line 69 of file people_detect_nodelet.cpp.
double people_detect::PeopleDetectNodelet::scale0_ [private] |
Definition at line 82 of file people_detect_nodelet.cpp.
int people_detect::PeopleDetectNodelet::win_stride_ [private] |
Definition at line 80 of file people_detect_nodelet.cpp.
std::string people_detect::PeopleDetectNodelet::window_name_ [private] |
Definition at line 74 of file people_detect_nodelet.cpp.