3 #include <boost/filesystem/fstream.hpp> 4 #include <boost/format.hpp> 5 #include <boost/scope_exit.hpp> 6 #include <boost/version.hpp> 8 #include <dynamic_reconfigure/server.h> 9 #include <geometry_msgs/PoseWithCovarianceStamped.h> 15 #include <sensor_msgs/Image.h> 16 #include <std_msgs/String.h> 19 #include <boost/bind.hpp> 20 #include <visp3/core/vpExponentialMap.h> 21 #include <visp3/core/vpImage.h> 22 #include <visp3/core/vpImageConvert.h> 23 #include <visp3/core/vpCameraParameters.h> 40 visp_tracker::Init::Response& res)
42 ROS_INFO(
"Initialization request received.");
44 res.initialization_succeed =
false;
50 if(!res.initialization_succeed)
57 } BOOST_SCOPE_EXIT_END;
59 std::string fullModelPath;
60 boost::filesystem::ofstream modelStream;
80 visp_tracker::ModelBasedSettingsConfig config;
81 convertVpMbTrackerToModelBasedSettingsConfig<visp_tracker::ModelBasedSettingsConfig>(
tracker_, config);
83 convertVpMeToModelBasedSettingsConfig<visp_tracker::ModelBasedSettingsConfig>(
movingEdge_,
tracker_, config);
85 convertVpKltOpencvToModelBasedSettingsConfig<visp_tracker::ModelBasedSettingsConfig>(
kltTracker_,
tracker_, config);
89 visp_tracker::ModelBasedSettingsEdgeConfig config;
90 convertVpMbTrackerToModelBasedSettingsConfig<visp_tracker::ModelBasedSettingsEdgeConfig>(
tracker_, config);
92 convertVpMeToModelBasedSettingsConfig<visp_tracker::ModelBasedSettingsEdgeConfig>(
movingEdge_,
tracker_, config);
96 visp_tracker::ModelBasedSettingsKltConfig config;
97 convertVpMbTrackerToModelBasedSettingsConfig<visp_tracker::ModelBasedSettingsKltConfig>(
tracker_, config);
99 convertVpKltOpencvToModelBasedSettingsConfig<visp_tracker::ModelBasedSettingsKltConfig>(
kltTracker_,
tracker_, config);
110 tracker_.loadModel(fullModelPath.c_str());
118 ROS_DEBUG(
"Model has been successfully loaded.");
124 tracker_.setCovarianceComputation(
true);
132 ROS_INFO(
"Tracker successfully initialized.");
143 catch(
const std::string& str)
149 res.initialization_succeed =
true;
160 std::list<vpMbtDistanceLine*> linesList;
165 std::list<vpMbtDistanceLine*>::iterator linesIterator = linesList.begin();
167 bool noVisibleLine =
true;
168 for (; linesIterator != linesList.end(); ++linesIterator)
170 vpMbtDistanceLine* line = *linesIterator;
172 #if VISP_VERSION_INT >= VP_VERSION_INT(3,0,0) // ViSP >= 3.0.0 173 if (line && line->isVisible() && ! line->meline.empty())
175 if (line && line->isVisible() && line->meline)
178 #if VISP_VERSION_INT >= VP_VERSION_INT(3,0,0) // ViSP >= 3.0.0 179 for(
unsigned int a = 0 ; a < line->meline.size() ; a++)
181 if(line->meline[a] != NULL) {
182 std::list<vpMeSite>::const_iterator sitesIterator = line->meline[a]->getMeList().begin();
183 if (line->meline[a]->getMeList().empty())
185 for (; sitesIterator != line->meline[a]->getMeList().end(); ++sitesIterator)
187 #elif VISP_VERSION_INT >= VP_VERSION_INT(2,10,0) // ViSP >= 2.10.0 188 std::list<vpMeSite>::const_iterator sitesIterator = line->meline->getMeList().begin();
189 if (line->meline->getMeList().empty())
191 for (; sitesIterator != line->meline->getMeList().end(); ++sitesIterator)
194 std::list<vpMeSite>::const_iterator sitesIterator = line->meline->list.begin();
195 if (line->meline->list.empty())
197 for (; sitesIterator != line->meline->list.end(); ++sitesIterator)
200 visp_tracker::MovingEdgeSite movingEdgeSite;
201 movingEdgeSite.x = sitesIterator->ifloat;
202 movingEdgeSite.y = sitesIterator->jfloat;
203 #if VISP_VERSION_INT < VP_VERSION_INT(2,10,0) // ViSP < 2.10.0 204 movingEdgeSite.suppress = sitesIterator->suppress;
206 sites->moving_edge_sites.push_back (movingEdgeSite);
208 noVisibleLine =
false;
210 #if VISP_VERSION_INT >= VP_VERSION_INT(3,0,0) // ViSP >= 3.0.0 226 #if VISP_VERSION_INT < VP_VERSION_INT(2,10,0) // ViSP < 2.10.0 227 vpMbHiddenFaces<vpMbtKltPolygon> *poly_lst;
228 std::map<int, vpImagePoint> *map_klt;
231 poly_lst = &
dynamic_cast<vpMbKltTracker*
>(
tracker_)->getFaces();
233 for(
unsigned int i = 0 ; i < poly_lst->size() ; i++)
237 map_klt = &((*poly_lst)[i]->getCurrentPoints());
239 if(map_klt->size() > 3)
241 for (std::map<int, vpImagePoint>::iterator it=map_klt->begin(); it!=map_klt->end(); ++it)
243 visp_tracker::KltPoint kltPoint;
244 kltPoint.id = it->first;
245 kltPoint.i = it->second.get_i();
246 kltPoint.j = it->second.get_j();
247 klt->klt_points_positions.push_back (kltPoint);
253 #else // ViSP >= 2.10.0 254 std::list<vpMbtDistanceKltPoints*> poly_lst;
255 std::map<int, vpImagePoint> *map_klt;
258 poly_lst =
tracker_.getFeaturesKlt();
260 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=poly_lst.begin(); it!=poly_lst.end(); ++it){
261 map_klt = &((*it)->getCurrentPoints());
263 if((*it)->polygon->isVisible()){
264 if(map_klt->size() > 3)
266 for (std::map<int, vpImagePoint>::iterator it=map_klt->begin(); it!=map_klt->end(); ++it)
268 visp_tracker::KltPoint kltPoint;
269 kltPoint.id = it->first;
270 kltPoint.i = it->second.get_i();
271 kltPoint.j = it->second.get_j();
272 klt->klt_points_positions.push_back (kltPoint);
336 if(trackerType_==
"mbt")
337 tracker_.setTrackerType(vpMbGenericTracker::EDGE_TRACKER);
338 else if(trackerType_==
"klt")
339 tracker_.setTrackerType(vpMbGenericTracker::KLT_TRACKER);
341 tracker_.setTrackerType(vpMbGenericTracker::EDGE_TRACKER | vpMbGenericTracker::KLT_TRACKER);
343 if (cameraPrefix_.empty ())
346 (
"The camera_prefix parameter not set.\n" 347 "Please relaunch the tracker while setting this parameter, i.e.\n" 348 "$ rosrun visp_tracker tracker _camera_prefix:=/my/camera");
395 typedef boost::function<
396 void (
const geometry_msgs::TransformStampedConstPtr&)>
397 objectPositionHintCallback_t;
398 objectPositionHintCallback_t
callback =
402 (
"object_position_hint",
queueSize_, callback);
405 if(trackerType_==
"mbt+klt"){
411 boost::ref(
mutex_), _1, _2);
414 else if(trackerType_==
"mbt"){
420 boost::ref(
mutex_), _1, _2);
429 boost::ref(
mutex_), _1, _2);
438 throw std::runtime_error(
"failed to retrieve image");
452 ROS_WARN (
"Dubious camera parameters detected.\n" 454 "It seems that the matrix P from your camera\n" 455 "calibration topics is wrong.\n" 456 "The tracker will continue anyway, but you\n" 457 "should double check your calibration data,\n" 458 "especially if the model re-projection fails.\n" 460 "This warning is triggered is px, py, u0 or v0\n" 461 "is set to 0. or 1. (exactly).");
492 std_msgs::Header lastHeader;
499 if (
header_.seq < lastHeader.seq)
520 vpHomogeneousMatrix newMold;
570 geometry_msgs::Transform transformMsg;
576 geometry_msgs::TransformStampedPtr objectPosition
577 (
new geometry_msgs::TransformStamped);
578 objectPosition->header =
header_;
580 objectPosition->transform = transformMsg;
587 geometry_msgs::PoseWithCovarianceStampedPtr result
588 (
new geometry_msgs::PoseWithCovarianceStamped);
590 result->pose.pose.position.x =
591 transformMsg.translation.x;
592 result->pose.pose.position.y =
593 transformMsg.translation.y;
594 result->pose.pose.position.z =
595 transformMsg.translation.z;
597 result->pose.pose.orientation.x =
598 transformMsg.rotation.x;
599 result->pose.pose.orientation.y =
600 transformMsg.rotation.y;
601 result->pose.pose.orientation.z =
602 transformMsg.rotation.z;
603 result->pose.pose.orientation.w =
604 transformMsg.rotation.w;
605 const vpMatrix& covariance =
607 for (
unsigned i = 0; i < covariance.getRows(); ++i)
608 for (
unsigned j = 0; j < covariance.getCols(); ++j)
610 unsigned idx = i * covariance.getCols() + j;
613 result->pose.covariance[idx] = covariance[i][j];
621 visp_tracker::MovingEdgeSitesPtr sites
622 (
new visp_tracker::MovingEdgeSites);
630 visp_tracker::KltPointsPtr klt
631 (
new visp_tracker::KltPoints);
640 transformMsg.translation.y,
641 transformMsg.translation.z));
644 (transformMsg.rotation.x,
645 transformMsg.rotation.y,
646 transformMsg.rotation.z,
647 transformMsg.rotation.w));
659 loopRateTracking.
sleep();
682 (
const geometry_msgs::TransformStampedConstPtr& transform)
std::string rectifiedImageTopic_
void convertInitRequestToVpMe(const visp_tracker::Init::Request &req, vpMbGenericTracker &tracker, vpMe &moving_edge)
void transformToVpHomogeneousMatrix(vpHomogeneousMatrix &dst, const geometry_msgs::Transform &src)
#define ROS_WARN_THROTTLE(rate,...)
void publish(const boost::shared_ptr< M > &message) const
image_transport::CameraSubscriber::Callback bindImageCallback(vpImage< unsigned char > &image)
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsEdgeConfig >::reconfigureSrv_t * reconfigureEdgeSrv_
#define ROS_DEBUG_THROTTLE(rate,...)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, const CameraSubscriber::Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
void start(const ros::V_string &topics, double duration)
std::string moving_edge_sites_topic
void updateKltPoints(visp_tracker::KltPointsPtr klt)
void objectPositionHintCallback(const geometry_msgs::TransformStampedConstPtr &)
std::string getName(void *handle)
image_proc::AdvertisementChecker checkInputs_
Helper used to check that subscribed topics exist.
std::string cameraInfoTopic_
std::string worldFrameId_
ros::Publisher resultPublisher_
void reconfigureEdgeCallbackAndInitViewer(ros::NodeHandle &nh, vpMbGenericTracker &tracker, vpImage< unsigned char > &I, vpMe &moving_edge, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsEdgeConfig &config, uint32_t level)
vpMbGenericTracker tracker_
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
ros::Publisher movingEdgeSitesPublisher_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
std::string childFrameId_
std::string convertVpKltOpencvToRosMessage(const vpMbGenericTracker &tracker, const vpKltOpencv &klt)
void convertInitRequestToVpKltOpencv(const visp_tracker::Init::Request &req, vpMbGenericTracker &tracker, vpKltOpencv &klt)
Tracker(ros::NodeHandle &nh, ros::NodeHandle &privateNh, volatile bool &exiting, unsigned queueSize=5u)
boost::recursive_mutex mutex_
image_transport::ImageTransport imageTransport_
ros::Subscriber objectPositionHintSubscriber_
std::string convertVpMeToRosMessage(const vpMbGenericTracker &tracker, const vpMe &moving_edge)
boost::filesystem::path modelPath_
void callback(const sensor_msgs::ImageConstPtr &msg)
ros::NodeHandle & nodeHandle_
bool initCallback(visp_tracker::Init::Request &req, visp_tracker::Init::Response &res)
std::vector< std::string > V_string
void reconfigureCallbackAndInitViewer(ros::NodeHandle &nh, vpMbGenericTracker &tracker, vpImage< unsigned char > &I, vpMe &moving_edge, vpKltOpencv &kltTracker, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsConfig &config, uint32_t level)
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsKltConfig >::reconfigureSrv_t * reconfigureKltSrv_
void reconfigureKltCallbackAndInitViewer(ros::NodeHandle &nh, vpMbGenericTracker &tracker, vpImage< unsigned char > &I, vpKltOpencv &kltTracker, boost::recursive_mutex &mutex, visp_tracker::ModelBasedSettingsKltConfig &config, uint32_t level)
geometry_msgs::TransformStamped objectPositionHint_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::string cameraPrefix_
image_transport::CameraSubscriber cameraSubscriber_
tf::TransformListener listener_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool compensateRobotMotion_
sensor_msgs::CameraInfoConstPtr info_
#define ROS_DEBUG_STREAM(args)
unsigned lastTrackedImage_
uint32_t getNumSubscribers() const
void updateMovingEdgeSites(visp_tracker::MovingEdgeSitesPtr sites)
#define ROS_INFO_STREAM(args)
std::string convertVpMbTrackerToRosMessage(const vpMbGenericTracker &tracker)
reconfigureSrvStruct< visp_tracker::ModelBasedSettingsConfig >::reconfigureSrv_t * reconfigureSrv_
tf::TransformBroadcaster transformBroadcaster_
void initializeVpCameraFromCameraInfo(vpCameraParameters &cam, sensor_msgs::CameraInfoConstPtr info)
std::string object_position_covariance_topic
boost::function< bool(visp_tracker::Init::Request &, visp_tracker::Init::Response &res)> initCallback_t
ros::ServiceServer initService_
ROSCPP_DECL void shutdown()
std::string object_position_topic
void convertInitRequestToVpMbTracker(const visp_tracker::Init::Request &req, vpMbGenericTracker &tracker)
vpCameraParameters cameraParameters_
#define ROS_ERROR_STREAM(args)
void vpHomogeneousMatrixToTransform(geometry_msgs::Transform &dst, const vpHomogeneousMatrix &src)
std::string klt_points_topic
ros::NodeHandle & nodeHandlePrivate_
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
ros::Publisher kltPointsPublisher_
bool makeModelFile(boost::filesystem::ofstream &modelStream, std::string &fullModelPath)
ros::Publisher transformationPublisher_