1 #ifndef VISP_TRACKER_TRACKER_CLIENT_HH 2 # define VISP_TRACKER_TRACKER_CLIENT_HH 3 # include <boost/filesystem/fstream.hpp> 4 # include <boost/filesystem/path.hpp> 5 # include <boost/thread/recursive_mutex.hpp> 7 # include <dynamic_reconfigure/server.h> 18 # include <sensor_msgs/Image.h> 19 # include <sensor_msgs/CameraInfo.h> 23 # include <visp_tracker/ModelBasedSettingsConfig.h> 24 # include <visp_tracker/ModelBasedSettingsKltConfig.h> 25 # include <visp_tracker/ModelBasedSettingsEdgeConfig.h> 26 # include <visp_tracker/MovingEdgeSites.h> 28 # include <visp3/core/vpCameraParameters.h> 29 # include <visp3/core/vpHomogeneousMatrix.h> 30 # include <visp3/core/vpImage.h> 31 # include <visp3/mbt/vpMbGenericTracker.h> 32 # include <visp3/me/vpMe.h> 33 # include <visp3/klt/vpKltOpencv.h> 34 # include <visp3/vision/vpPose.h> 46 template<
class ConfigType>
54 unsigned queueSize = 5u);
73 imagePoints_t& imagePoints,
80 void sendcMo(
const vpHomogeneousMatrix& cMo);
84 const std::string& resourcePath,
85 std::string& fullModelPath);
125 sensor_msgs::CameraInfoConstPtr
info_;
boost::filesystem::path bInitPath_
TrackerClient(ros::NodeHandle &nh, ros::NodeHandle &privateNh, volatile bool &exiting, unsigned queueSize=5u)
std::string cameraInfoTopic_
void checkInputs()
Make sure the topics we subscribe already exist.
void saveInitialPose(const vpHomogeneousMatrix &cMo)
ros::NodeHandle & nodeHandle_
image_transport::ImageTransport imageTransport_
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsEdgeConfig >::reconfigureSrv_t * reconfigureEdgeSrv_
ros::NodeHandle & nodeHandlePrivate_
points_t loadInitializationPoints()
std::vector< vpPoint > points_t
resource_retriever::Retriever resourceRetriever_
bool validatePose(const vpHomogeneousMatrix &cMo)
vpHomogeneousMatrix loadInitialPose()
vpImage< unsigned char > image_t
image_proc::AdvertisementChecker checkInputs_
Helper used to check that subscribed topics exist.
void initPoint(unsigned &i, points_t &points, imagePoints_t &imagePoints, ros::Rate &rate, vpPose &pose)
std::string modelPathAndExt_
image_transport::CameraSubscriber cameraSubscriber_
std::string cameraPrefix_
void sendcMo(const vpHomogeneousMatrix &cMo)
vpMbGenericTracker tracker_
sensor_msgs::CameraInfoConstPtr info_
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsConfig >::reconfigureSrv_t * reconfigureSrv_
std::string rectifiedImageTopic_
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsKltConfig >::reconfigureSrv_t * reconfigureKltSrv_
boost::filesystem::path bModelPath_
vpCameraParameters cameraParameters_
std::vector< vpImagePoint > imagePoints_t
bool makeModelFile(boost::filesystem::ofstream &modelStream, const std::string &resourcePath, std::string &fullModelPath)
boost::recursive_mutex mutex_
std::string fetchResource(const std::string &)