hector_trajectory_server.cpp
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2011, Stefan Kohlbrecher, TU Darmstadt
00003 // All rights reserved.
00004 
00005 // Redistribution and use in source and binary forms, with or without
00006 // modification, are permitted provided that the following conditions are met:
00007 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of the Simulation, Systems Optimization and Robotics
00013 //       group, TU Darmstadt nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //=================================================================================================
00028 
00029 #include <cstdio>
00030 #include "ros/ros.h"
00031 #include "ros/console.h"
00032 
00033 #include "nav_msgs/Path.h"
00034 #include "std_msgs/String.h"
00035 
00036 #include <geometry_msgs/Quaternion.h>
00037 #include <geometry_msgs/PoseStamped.h>
00038 
00039 #include "tf/transform_listener.h"
00040 
00041 #include <hector_nav_msgs/GetRobotTrajectory.h>
00042 #include <hector_nav_msgs/GetRecoveryInfo.h>
00043 
00044 #include <tf/tf.h>
00045 
00046 #include <algorithm>
00047 
00048 using namespace std;
00049 
00050 bool comparePoseStampedStamps (const geometry_msgs::PoseStamped& t1, const geometry_msgs::PoseStamped& t2) { return (t1.header.stamp < t2.header.stamp); }
00051 
00052 
00056 class PathContainer
00057 {
00058 public:
00059   PathContainer()
00060   {
00061     ros::NodeHandle private_nh("~");
00062 
00063     private_nh.param("target_frame_name", p_target_frame_name_, std::string("map"));
00064     private_nh.param("source_frame_name", p_source_frame_name_, std::string("base_link"));
00065     private_nh.param("trajectory_update_rate", p_trajectory_update_rate_, 4.0);
00066     private_nh.param("trajectory_publish_rate", p_trajectory_publish_rate_, 0.25);
00067 
00068     waitForTf();
00069 
00070     ros::NodeHandle nh;
00071     sys_cmd_sub_ = nh.subscribe("syscommand", 1, &PathContainer::sysCmdCallback, this);
00072     trajectory_pub_ = nh.advertise<nav_msgs::Path>("trajectory",1, true);
00073 
00074     trajectory_provider_service_ = nh.advertiseService("trajectory", &PathContainer::trajectoryProviderCallBack, this);
00075     recovery_info_provider_service_ = nh.advertiseService("trajectory_recovery_info", &PathContainer::recoveryInfoProviderCallBack, this);
00076 
00077     last_reset_time_ = ros::Time::now();
00078 
00079     update_trajectory_timer_ = private_nh.createTimer(ros::Duration(1.0 / p_trajectory_update_rate_), &PathContainer::trajectoryUpdateTimerCallback, this, false);
00080     publish_trajectory_timer_ = private_nh.createTimer(ros::Duration(1.0 / p_trajectory_publish_rate_), &PathContainer::publishTrajectoryTimerCallback, this, false);
00081 
00082     pose_source_.pose.orientation.w = 1.0;
00083     pose_source_.header.frame_id = p_source_frame_name_;
00084 
00085     trajectory_.trajectory.header.frame_id = p_target_frame_name_;
00086   }
00087 
00088   void waitForTf()
00089   {
00090     ros::WallTime start = ros::WallTime::now();
00091     ROS_INFO("Waiting for tf transform data between frames %s and %s to become available", p_target_frame_name_.c_str(), p_source_frame_name_.c_str() );
00092 
00093     bool transform_successful = false;
00094 
00095     while (!transform_successful){
00096       transform_successful = tf_.canTransform(p_target_frame_name_, p_source_frame_name_, ros::Time());
00097       if (transform_successful) break;
00098 
00099       ros::WallTime now = ros::WallTime::now();
00100 
00101       if ((now-start).toSec() > 20.0){
00102         ROS_WARN_ONCE("No transform between frames %s and %s available after %f seconds of waiting. This warning only prints once.", p_target_frame_name_.c_str(), p_source_frame_name_.c_str(), (now-start).toSec());
00103       }
00104       
00105       if (!ros::ok()) return;
00106       ros::WallDuration(1.0).sleep();
00107     }
00108 
00109     ros::WallTime end = ros::WallTime::now();
00110     ROS_INFO("Finished waiting for tf, waited %f seconds", (end-start).toSec());
00111   }
00112 
00113 
00114   void sysCmdCallback(const std_msgs::String& sys_cmd)
00115   {
00116     if (sys_cmd.data == "reset"){
00117       last_reset_time_ = ros::Time::now();
00118       trajectory_.trajectory.poses.clear();
00119       trajectory_.trajectory.header.stamp = ros::Time::now();
00120     }
00121   }
00122 
00123   void addCurrentTfPoseToTrajectory()
00124   {
00125     pose_source_.header.stamp = ros::Time(0);
00126 
00127     geometry_msgs::PoseStamped pose_out;
00128 
00129     tf_.transformPose(p_target_frame_name_, pose_source_, pose_out);
00130 
00131     if (trajectory_.trajectory.poses.size() != 0){
00132       //Only add pose to trajectory if it's not already stored
00133       if (pose_out.header.stamp != trajectory_.trajectory.poses.back().header.stamp){
00134         trajectory_.trajectory.poses.push_back(pose_out);
00135       }
00136     }else{
00137       trajectory_.trajectory.poses.push_back(pose_out);
00138     }
00139 
00140     trajectory_.trajectory.header.stamp = pose_out.header.stamp;
00141   }
00142 
00143   void trajectoryUpdateTimerCallback(const ros::TimerEvent& event)
00144   {
00145 
00146     try{
00147       addCurrentTfPoseToTrajectory();
00148     }catch(tf::TransformException e)
00149     {
00150       ROS_WARN("Trajectory Server: Transform from %s to %s failed: %s \n", p_target_frame_name_.c_str(), pose_source_.header.frame_id.c_str(), e.what() );
00151     }
00152   }
00153 
00154   void publishTrajectoryTimerCallback(const ros::TimerEvent& event)
00155   {
00156     trajectory_pub_.publish(trajectory_.trajectory);
00157   }
00158 
00159   bool trajectoryProviderCallBack(hector_nav_msgs::GetRobotTrajectory::Request  &req,
00160                                   hector_nav_msgs::GetRobotTrajectory::Response &res )
00161   {
00162     res = trajectory_;
00163 
00164     return true;
00165   };
00166 
00167   bool recoveryInfoProviderCallBack(hector_nav_msgs::GetRecoveryInfo::Request  &req,
00168                                   hector_nav_msgs::GetRecoveryInfo::Response &res )
00169   {
00170     const ros::Time req_time = req.request_time;
00171 
00172     geometry_msgs::PoseStamped tmp;
00173     tmp.header.stamp = req_time;
00174 
00175     std::vector<geometry_msgs::PoseStamped>& poses = trajectory_.trajectory.poses;
00176 
00177     //Find the robot pose in the saved trajectory
00178     std::vector<geometry_msgs::PoseStamped>::iterator it = std::lower_bound(poses.begin(), poses.end(), tmp, comparePoseStampedStamps);
00179 
00180     //If we didn't find the robot pose for the desired time, add the current robot pose to trajectory
00181     if (it == poses.end()){
00182       addCurrentTfPoseToTrajectory();
00183       it = poses.end();
00184       --it;
00185     }
00186 
00187     std::vector<geometry_msgs::PoseStamped>::iterator it_start = it;
00188 
00189     const geometry_msgs::Point& req_coords ((*it).pose.position);
00190 
00191     double dist_sqr_threshold = req.request_radius * req.request_radius;
00192 
00193     double dist_sqr = 0.0;
00194 
00195     //Iterate backwards till the start of the trajectory is reached or we find a pose that's outside the specified radius
00196     while (it != poses.begin() && dist_sqr < dist_sqr_threshold){
00197       const geometry_msgs::Point& curr_coords ((*it).pose.position);
00198 
00199       dist_sqr = (req_coords.x - curr_coords.x) * (req_coords.x - curr_coords.x) +
00200                  (req_coords.y - curr_coords.y) * (req_coords.y - curr_coords.y);
00201 
00202       --it;
00203     }
00204 
00205     if (dist_sqr < dist_sqr_threshold){
00206       ROS_INFO("Failed to find trajectory leading out of radius %f", req.request_radius);
00207       return false;
00208     }
00209 
00210     std::vector<geometry_msgs::PoseStamped>::iterator it_end = it;
00211 
00212     res.req_pose = *it_start;
00213     res.radius_entry_pose = *it_end;
00214 
00215     std::vector<geometry_msgs::PoseStamped>& traj_out_poses = res.trajectory_radius_entry_pose_to_req_pose.poses;
00216 
00217     res.trajectory_radius_entry_pose_to_req_pose.poses.clear();
00218     res.trajectory_radius_entry_pose_to_req_pose.header = res.req_pose.header;
00219 
00220     for (std::vector<geometry_msgs::PoseStamped>::iterator it_tmp = it_start; it_tmp != it_end; --it_tmp){
00221       traj_out_poses.push_back(*it_tmp);
00222     }
00223 
00224     return true;
00225   };
00226 
00227   //parameters
00228   std::string p_target_frame_name_;
00229   std::string p_source_frame_name_;
00230   double p_trajectory_update_rate_;
00231   double p_trajectory_publish_rate_;
00232 
00233   // Zero pose used for transformation to target_frame.
00234   geometry_msgs::PoseStamped pose_source_;
00235 
00236   ros::ServiceServer trajectory_provider_service_;
00237   ros::ServiceServer recovery_info_provider_service_;
00238 
00239   ros::Timer update_trajectory_timer_;
00240   ros::Timer publish_trajectory_timer_;
00241 
00242 
00243   //ros::Subscriber pose_update_sub_;
00244   ros::Subscriber sys_cmd_sub_;
00245   ros::Publisher  trajectory_pub_;
00246 
00247   hector_nav_msgs::GetRobotTrajectory::Response trajectory_;
00248 
00249   tf::TransformListener tf_;
00250 
00251   ros::Time last_reset_time_;
00252   ros::Time last_pose_save_time_;
00253 };
00254 
00255 int main(int argc, char** argv)
00256 {
00257   ros::init(argc, argv, "hector_trajectory_server");
00258 
00259   PathContainer pc;
00260 
00261   ros::spin();
00262 
00263   return 0;
00264 }


hector_trajectory_server
Author(s): Stefan Kohlbrecher
autogenerated on Wed Aug 26 2015 11:45:12