$search
Public Member Functions | |
void | cameraCallback (const sensor_msgs::CameraInfoConstPtr &camera_info) |
void | imageCallback (const sensor_msgs::ImageConstPtr &image) |
virtual void | reconf_callback (blort_ros::TrackerConfig &config, uint32_t level) |
virtual blort_ros::RecoveryCall | recovery (const sensor_msgs::ImageConstPtr &msg) |
SingleShotMode (TrackerNode *parent) | |
bool | singleShotService (blort_ros::EstimatePose::Request &req, blort_ros::EstimatePose::Response &resp) |
Private Attributes | |
ros::Subscriber | cam_info_sub |
ros::ServiceClient | detector_set_caminfo_service |
image_transport::Subscriber | image_sub |
bool | inServiceCall |
sensor_msgs::CameraInfoConstPtr | lastCameraInfo |
sensor_msgs::ImageConstPtr | lastImage |
TrackerNode * | parent_ |
std::list< geometry_msgs::Pose > | results |
ros::ServiceServer | singleshot_service |
double | time_to_run_singleshot |
Definition at line 251 of file tracker_node.cpp.
TrackerNode::SingleShotMode::SingleShotMode | ( | TrackerNode * | parent | ) | [inline] |
Definition at line 266 of file tracker_node.cpp.
void TrackerNode::SingleShotMode::cameraCallback | ( | const sensor_msgs::CameraInfoConstPtr & | camera_info | ) | [inline] |
Definition at line 294 of file tracker_node.cpp.
void TrackerNode::SingleShotMode::imageCallback | ( | const sensor_msgs::ImageConstPtr & | image | ) | [inline] |
Definition at line 284 of file tracker_node.cpp.
virtual void TrackerNode::SingleShotMode::reconf_callback | ( | blort_ros::TrackerConfig & | config, | |
uint32_t | level | |||
) | [inline, virtual] |
Implements TrackerNode::Mode.
Definition at line 304 of file tracker_node.cpp.
virtual blort_ros::RecoveryCall TrackerNode::SingleShotMode::recovery | ( | const sensor_msgs::ImageConstPtr & | msg | ) | [inline, virtual] |
Implements TrackerNode::Mode.
Definition at line 309 of file tracker_node.cpp.
bool TrackerNode::SingleShotMode::singleShotService | ( | blort_ros::EstimatePose::Request & | req, | |
blort_ros::EstimatePose::Response & | resp | |||
) | [inline] |
Definition at line 322 of file tracker_node.cpp.
Definition at line 261 of file tracker_node.cpp.
Definition at line 256 of file tracker_node.cpp.
Definition at line 262 of file tracker_node.cpp.
bool TrackerNode::SingleShotMode::inServiceCall [private] |
Definition at line 257 of file tracker_node.cpp.
Definition at line 264 of file tracker_node.cpp.
Definition at line 263 of file tracker_node.cpp.
TrackerNode* TrackerNode::SingleShotMode::parent_ [private] |
Definition at line 258 of file tracker_node.cpp.
std::list<geometry_msgs::Pose> TrackerNode::SingleShotMode::results [private] |
Definition at line 259 of file tracker_node.cpp.
Definition at line 254 of file tracker_node.cpp.
double TrackerNode::SingleShotMode::time_to_run_singleshot [private] |
Definition at line 255 of file tracker_node.cpp.