Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00036
00037 #include <ros/ros.h>
00038 #include <laser_joint_projector/laser_joint_projector.h>
00039 #include <kdl_parser/kdl_parser.hpp>
00040 #include <calibration_msgs/JointStateCalibrationPattern.h>
00041 #include <std_msgs/Float64.h>
00042 #include <boost/thread/mutex.hpp>
00043
00044 using namespace laser_joint_projector;
00045 using namespace std;
00046
00047 class TimeAlignmentNode
00048 {
00049 public:
00050 TimeAlignmentNode()
00051 {
00052 cloud_num_ = 0;
00053
00054 std::string robot_desc_string;
00055 nh_.param("robot_description", robot_desc_string, string());
00056 if (!kdl_parser::treeFromString(robot_desc_string, tree_))
00057 ROS_FATAL("Failed to construct kdl tree");
00058
00059 pub0_ = nh_.advertise<sensor_msgs::PointCloud>("cb_cloud_0", 1);
00060 pub1_ = nh_.advertise<sensor_msgs::PointCloud>("cb_cloud_1", 1);
00061 sub_features_ = nh_.subscribe("joint_state_features", 1, &TimeAlignmentNode::featuresCallback, this);
00062 sub_offset_ = nh_.subscribe("keyboard_float", 1, &TimeAlignmentNode::offsetCallback, this);
00063
00064 ros::NodeHandle private_nh_("~");
00065
00066 private_nh_.param("root", root_, std::string("root_link"));
00067 private_nh_.param("tip", tip_, std::string("tip_link"));
00068
00069 projector_.configure(tree_, root_, tip_);
00070 }
00071
00072 private:
00073 ros::NodeHandle nh_;
00074 unsigned int cloud_num_;
00075 KDL::Tree tree_;
00076 ros::Publisher pub0_;
00077 ros::Publisher pub1_;
00078 ros::Subscriber sub_features_;
00079 ros::Subscriber sub_offset_;
00080 LaserJointProjector projector_;
00081
00082 double offset_;
00083 std::string root_;
00084 std::string tip_;
00085
00086 boost::mutex mutex_;
00087
00088 calibration_msgs::JointStateCalibrationPatternConstPtr features_0_;
00089 calibration_msgs::JointStateCalibrationPatternConstPtr features_1_;
00090
00091 void featuresCallback(const calibration_msgs::JointStateCalibrationPatternConstPtr& msg)
00092 {
00093 boost::mutex::scoped_lock lock(mutex_);
00094
00095 if (cloud_num_ == 0)
00096 features_0_ = msg;
00097 else if (cloud_num_ == 1)
00098 features_1_ = msg;
00099 else
00100 ROS_FATAL("Cloud num is [%u]", cloud_num_);
00101
00102
00103 cloud_num_ = 1 - cloud_num_;
00104
00105 publish();
00106 }
00107
00108 void offsetCallback(const std_msgs::Float64ConstPtr& offset)
00109 {
00110 boost::mutex::scoped_lock lock(mutex_);
00111 offset_ = offset->data;
00112 publish();
00113 }
00114
00115 void publish()
00116 {
00117 ros::Duration offset(offset_);
00118
00119 sensor_msgs::PointCloud cloud_0;
00120 sensor_msgs::PointCloud cloud_1;
00121
00122 if (features_0_)
00123 {
00124 cloud_0 = projector_.project(features_0_->joint_points, offset);
00125 cloud_0.header.stamp = features_0_->header.stamp;
00126 }
00127
00128 if (features_1_)
00129 {
00130 cloud_1 = projector_.project(features_1_->joint_points, offset);
00131 cloud_1.header.stamp = features_1_->header.stamp;
00132 }
00133
00134 cloud_0.header.frame_id = root_;
00135 cloud_1.header.frame_id = root_;
00136
00137 pub0_.publish(cloud_0);
00138 pub1_.publish(cloud_1);
00139 }
00140
00141 };
00142
00143
00144 int main(int argc, char** argv)
00145 {
00146 ros::init(argc, argv, "time_alignment");
00147
00148 TimeAlignmentNode alignment_node;
00149
00150 ros::spin();
00151
00152 return 0;
00153 }