1 #ifndef VISP_TRACKER_TRACKER_HH 2 # define VISP_TRACKER_TRACKER_HH 3 # include <boost/filesystem/path.hpp> 4 # include <boost/thread/recursive_mutex.hpp> 6 # include <dynamic_reconfigure/server.h> 12 # include <geometry_msgs/TwistStamped.h> 14 # include <sensor_msgs/Image.h> 15 # include <sensor_msgs/CameraInfo.h> 20 # include <visp_tracker/Init.h> 21 # include <visp_tracker/ModelBasedSettingsConfig.h> 22 # include <visp_tracker/ModelBasedSettingsKltConfig.h> 23 # include <visp_tracker/ModelBasedSettingsEdgeConfig.h> 24 # include <visp_tracker/MovingEdgeSites.h> 25 # include <visp_tracker/KltPoints.h> 27 # include <visp/vpCameraParameters.h> 28 # include <visp/vpHomogeneousMatrix.h> 29 # include <visp/vpImage.h> 31 # include <visp/vpMbTracker.h> 32 # include <visp/vpMbEdgeKltTracker.h> 34 # include <visp/vpMe.h> 44 typedef boost::function<bool (visp_tracker::Init::Request&,
45 visp_tracker::Init::Response& res)>
48 template<
class ConfigType>
64 unsigned queueSize = 5u);
71 visp_tracker::Init::Response& res);
80 (
const geometry_msgs::TransformStampedConstPtr&);
129 sensor_msgs::CameraInfoConstPtr
info_;
std::string rectifiedImageTopic_
tf::TransformBroadcaster tfBroadcaster_
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsEdgeConfig >::reconfigureSrv_t * reconfigureEdgeSrv_
void updateKltPoints(visp_tracker::KltPointsPtr klt)
void objectPositionHintCallback(const geometry_msgs::TransformStampedConstPtr &)
image_proc::AdvertisementChecker checkInputs_
Helper used to check that subscribed topics exist.
std::string cameraInfoTopic_
std::string worldFrameId_
ros::Publisher resultPublisher_
ros::Publisher movingEdgeSitesPublisher_
std::string childFrameId_
Tracker(ros::NodeHandle &nh, ros::NodeHandle &privateNh, volatile bool &exiting, unsigned queueSize=5u)
boost::recursive_mutex mutex_
image_transport::ImageTransport imageTransport_
ros::Subscriber objectPositionHintSubscriber_
boost::filesystem::path modelPath_
ros::NodeHandle & nodeHandle_
bool initCallback(visp_tracker::Init::Request &req, visp_tracker::Init::Response &res)
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsKltConfig >::reconfigureSrv_t * reconfigureKltSrv_
geometry_msgs::TransformStamped objectPositionHint_
std::string cameraPrefix_
image_transport::CameraSubscriber cameraSubscriber_
tf::TransformListener listener_
bool compensateRobotMotion_
sensor_msgs::CameraInfoConstPtr info_
unsigned lastTrackedImage_
void updateMovingEdgeSites(visp_tracker::MovingEdgeSitesPtr sites)
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsConfig >::reconfigureSrv_t * reconfigureSrv_
tf::TransformBroadcaster transformBroadcaster_
boost::function< bool(visp_tracker::Init::Request &, visp_tracker::Init::Response &res)> initCallback_t
ros::ServiceServer initService_
vpCameraParameters cameraParameters_
ROSCPP_DECL void spinOnce()
ros::NodeHandle & nodeHandlePrivate_
vpImage< unsigned char > image_t
ros::Publisher kltPointsPublisher_
ros::Publisher transformationPublisher_