main.cpp
Go to the documentation of this file.
00001 /*
00002  * ar_marker_processor
00003  *   main.cpp
00004  *
00005  *  LICENSE : BSD - https://raw.github.com/yujinrobot/yujin_ocs/license/LICENSE
00006  *
00007  *  Created on: Apr 6, 2013
00008  *      Author: jorge
00009  *  Modified on: Dec, 2013 
00010  *      Jihoon Lee
00011  */
00012 
00013 #include "yocs_ar_pair_tracking/tracking.hpp"
00014 
00015 int main(int argc, char** argv)
00016 {
00017   ros::init(argc, argv, "ar_marker_processor");
00018   yocs::ARPairTracking tracking;
00019 
00020   ros::NodeHandle pnh("~");
00021 
00022   int left_id, right_id;
00023   double baseline, target_offset;
00024   yocs_msgs::ARPair p;
00025   
00026   // Parameters
00027   pnh.param("ar_pair_left_id",  left_id,  yocs::ARPairTrackingDefaultParams::AR_PAIR_LEFT_ID);
00028   pnh.param("ar_pair_right_id", right_id, yocs::ARPairTrackingDefaultParams::AR_PAIR_RIGHT_ID);
00029   pnh.param("ar_pair_baseline", baseline, yocs::ARPairTrackingDefaultParams::AR_PAIR_BASELINE);
00030   pnh.param("ar_pair_target_pose_offset", target_offset, yocs::ARPairTrackingDefaultParams::AR_PAIR_TARGET_POSE_OFFSET);
00031 
00032   p.left_id = left_id;
00033   p.right_id = right_id;
00034   p.baseline = baseline;
00035   p.target_offset = target_offset;
00036   p.target_frame = "global_marker_3_target";
00037 
00038   tracking.addPair(p);
00039   
00040   ROS_INFO("AR Pair Tracking : initialised");
00041   tracking.spin();
00042 
00043   return 0;
00044 }


yocs_ar_pair_tracking
Author(s): Daniel Stonier, Jihoon Lee, Jorge Santos Simon
autogenerated on Thu Jun 6 2019 21:47:30