Go to the documentation of this file.00001 #include "trajectory_broadcaster_alg_node.h"
00002
00003 TrajectoryBroadcasterAlgNode::TrajectoryBroadcasterAlgNode(void) :
00004 algorithm_base::IriBaseAlgorithm<TrajectoryBroadcasterAlgorithm>()
00005 {
00006
00007
00008 this->loop_rate_ = 10;
00009
00010
00011
00012
00013 this->trajectory_subscriber_ = this->public_node_handle_.subscribe("trajectory", 100, &TrajectoryBroadcasterAlgNode::trajectory_callback, this);
00014
00015
00016
00017
00018
00019
00020
00021
00022 }
00023
00024 TrajectoryBroadcasterAlgNode::~TrajectoryBroadcasterAlgNode(void)
00025 {
00026
00027 }
00028
00029 void TrajectoryBroadcasterAlgNode::mainNodeThread(void)
00030 {
00031
00032
00033
00034
00035
00036
00037
00038 this->recompute_tf_mutex_.enter();
00039
00040 tfb_.sendTransform(tf::StampedTransform(T_map_odom_, ros::Time::now(), map_frame_id_, odom_frame_id_));
00041
00042 this->recompute_tf_mutex_.exit();
00043 }
00044
00045
00046 void TrajectoryBroadcasterAlgNode::trajectory_callback(const iri_poseslam::Trajectory::ConstPtr& msg)
00047 {
00048
00049
00050 this->recompute_tf_mutex_.enter();
00051
00052 geometry_msgs::PoseWithCovarianceStamped new_pose = msg->poses.back();
00053
00054
00055 tf::StampedTransform T_base_odom_stamped;
00056 try{
00057 tfl_.waitForTransform(base_frame_id_, odom_frame_id_,
00058 ros::Time::now(), ros::Duration(3.0));
00059
00060 tfl_.lookupTransform(base_frame_id_, odom_frame_id_,
00061 ros::Time(0), T_base_odom_stamped);
00062
00063 T_base_odom_ = T_base_odom_stamped;
00064 }
00065 catch (tf::TransformException ex){
00066 ROS_ERROR("%s",ex.what());
00067 }
00068
00069
00070 tf::poseMsgToTF(new_pose.pose.pose, T_map_base_);
00071
00072
00073 T_map_odom_ = T_map_base_ * T_base_odom_;
00074
00075 this->recompute_tf_mutex_.exit();
00076 }
00077
00078
00079
00080
00081
00082
00083
00084 void TrajectoryBroadcasterAlgNode::node_config_update(Config &config, uint32_t level)
00085 {
00086 this->alg_.lock();
00087
00088 map_frame_id_ = config.map_frame_id;
00089 odom_frame_id_ = config.odom_frame_id;
00090 base_frame_id_ = config.base_frame_id;
00091
00092 ROS_WARN("TRAJ BROADCASTER: Config updated");
00093
00094 this->alg_.unlock();
00095 }
00096
00097 void TrajectoryBroadcasterAlgNode::addNodeDiagnostics(void)
00098 {
00099 }
00100
00101
00102 int main(int argc,char *argv[])
00103 {
00104 return algorithm_base::main<TrajectoryBroadcasterAlgNode>(argc, argv, "trajectory_broadcaster_alg_node");
00105 }