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
00035 #include <locomotor/locomotor.h>
00036 #include <nav_2d_utils/tf_help.h>
00037 #include <functional>
00038 #include <string>
00039
00040 namespace locomotor
00041 {
00042 ros::Duration getTimeDiffFromNow(const ros::WallTime& start_time)
00043 {
00044 ros::WallDuration duration = ros::WallTime::now() - start_time;
00045 return ros::Duration(duration.sec, duration.nsec);
00046 }
00047
00048 Locomotor::Locomotor(const ros::NodeHandle& private_nh) :
00049 costmap_loader_("nav_core2", "nav_core2::Costmap"),
00050 global_planner_mux_("nav_core2", "nav_core2::GlobalPlanner",
00051 "global_planner_namespaces", "dlux_global_planner::DluxGlobalPlanner",
00052 "current_global_planner", "switch_global_planner"),
00053 local_planner_mux_("nav_core2", "nav_core2::LocalPlanner",
00054 "local_planner_namespaces", "dwb_local_planner::DWBLocalPlanner",
00055 "current_local_planner", "switch_local_planner"),
00056 private_nh_(private_nh), path_pub_(private_nh_), twist_pub_(private_nh_)
00057 {
00058 tf_ = std::make_shared<tf::TransformListener>(ros::Duration(10));
00059
00060 private_nh_.param("robot_base_frame", robot_base_frame_, std::string("base_link"));
00061
00062
00063 private_nh_.param("use_latest_pose", use_latest_pose_, true);
00064
00065 local_planner_mux_.setSwitchCallback(std::bind(&Locomotor::switchLocalPlannerCallback, this, std::placeholders::_1,
00066 std::placeholders::_2));
00067
00068 ros::NodeHandle global_nh;
00069 odom_sub_ = std::make_shared<nav_2d_utils::OdomSubscriber>(global_nh);
00070 }
00071
00072 void Locomotor::initializeGlobalCostmap(Executor& ex)
00073 {
00074 std::string costmap_class;
00075 private_nh_.param("global_costmap_class", costmap_class, std::string("nav_core_adapter::CostmapAdapter"));
00076 ROS_INFO_NAMED("Locomotor", "Loading Global Costmap %s", costmap_class.c_str());
00077 global_costmap_ = costmap_loader_.createUniqueInstance(costmap_class);
00078 ROS_INFO_NAMED("Locomotor", "Initializing Global Costmap");
00079 global_costmap_->initialize(ex.getNodeHandle(), "global_costmap", tf_);
00080 }
00081
00082 void Locomotor::initializeLocalCostmap(Executor& ex)
00083 {
00084 std::string costmap_class;
00085 private_nh_.param("local_costmap_class", costmap_class, std::string("nav_core_adapter::CostmapAdapter"));
00086 ROS_INFO_NAMED("Locomotor", "Loading Local Costmap %s", costmap_class.c_str());
00087 local_costmap_ = costmap_loader_.createUniqueInstance(costmap_class);
00088 ROS_INFO_NAMED("Locomotor", "Initializing Local Costmap");
00089 local_costmap_->initialize(ex.getNodeHandle(), "local_costmap", tf_);
00090 }
00091
00092 void Locomotor::initializeGlobalPlanners(Executor& ex)
00093 {
00094 for (auto planner_name : global_planner_mux_.getPluginNames())
00095 {
00096 ROS_INFO_NAMED("Locomotor", "Initializing global planner %s", planner_name.c_str());
00097 global_planner_mux_.getPlugin(planner_name).initialize(ex.getNodeHandle(), planner_name, tf_, global_costmap_);
00098 }
00099 }
00100
00101 void Locomotor::initializeLocalPlanners(Executor& ex)
00102 {
00103 for (auto planner_name : local_planner_mux_.getPluginNames())
00104 {
00105 ROS_INFO_NAMED("Locomotor", "Initializing local planner %s", planner_name.c_str());
00106 local_planner_mux_.getPlugin(planner_name).initialize(ex.getNodeHandle(), planner_name, tf_, local_costmap_);
00107 }
00108 }
00109
00110 void Locomotor::setGoal(nav_2d_msgs::Pose2DStamped goal)
00111 {
00112 local_planner_mux_.getCurrentPlugin().setGoalPose(goal);
00113 state_ = locomotor_msgs::NavigationState();
00114 state_.goal = goal;
00115 }
00116
00117 void Locomotor::switchLocalPlannerCallback(const std::string&, const std::string& new_planner)
00118 {
00119 auto& new_local_planner = local_planner_mux_.getPlugin(new_planner);
00120 new_local_planner.setGoalPose(state_.goal);
00121 new_local_planner.setPlan(state_.global_plan);
00122 }
00123
00124 void Locomotor::requestGlobalCostmapUpdate(Executor& work_ex, Executor& result_ex,
00125 CostmapUpdateCallback cb, CostmapUpdateExceptionCallback fail_cb)
00126 {
00127 work_ex.addCallback(
00128 std::bind(&Locomotor::doCostmapUpdate, this, std::ref(*global_costmap_), std::ref(result_ex), cb, fail_cb));
00129 }
00130
00131 void Locomotor::requestLocalCostmapUpdate(Executor& work_ex, Executor& result_ex,
00132 CostmapUpdateCallback cb, CostmapUpdateExceptionCallback fail_cb)
00133 {
00134 work_ex.addCallback(
00135 std::bind(&Locomotor::doCostmapUpdate, this, std::ref(*local_costmap_), std::ref(result_ex), cb, fail_cb));
00136 }
00137
00138 void Locomotor::requestGlobalPlan(Executor& work_ex, Executor& result_ex,
00139 GlobalPlanCallback cb, PlannerExceptionCallback fail_cb)
00140 {
00141 work_ex.addCallback(std::bind(&Locomotor::makeGlobalPlan, this, std::ref(result_ex), cb, fail_cb));
00142 }
00143
00144 void Locomotor::requestLocalPlan(Executor& work_ex, Executor& result_ex,
00145 LocalPlanCallback cb, PlannerExceptionCallback fail_cb,
00146 NavigationCompleteCallback complete_cb)
00147 {
00148 work_ex.addCallback(std::bind(&Locomotor::makeLocalPlan, this, std::ref(result_ex), cb, fail_cb, complete_cb));
00149 }
00150
00151 void Locomotor::requestNavigationFailure(Executor& result_ex, const locomotor_msgs::ResultCode& result,
00152 NavigationFailureCallback cb)
00153 {
00154 result_ex.addCallback(std::bind(cb, result));
00155 }
00156
00157 void Locomotor::doCostmapUpdate(nav_core2::Costmap& costmap, Executor& result_ex,
00158 CostmapUpdateCallback cb, CostmapUpdateExceptionCallback fail_cb)
00159 {
00160 ros::WallTime start_t = ros::WallTime::now();
00161 try
00162 {
00163 {
00164 boost::unique_lock<boost::recursive_mutex> lock(*(costmap.getMutex()));
00165 costmap.update();
00166 }
00167 if (cb) result_ex.addCallback(std::bind(cb, getTimeDiffFromNow(start_t)));
00168 }
00169 catch (const nav_core2::CostmapException& e)
00170 {
00171 if (fail_cb)
00172 result_ex.addCallback(std::bind(fail_cb, std::current_exception(), getTimeDiffFromNow(start_t)));
00173 }
00174 }
00175
00176 void Locomotor::makeGlobalPlan(Executor& result_ex, GlobalPlanCallback cb, PlannerExceptionCallback fail_cb)
00177 {
00178 ros::WallTime start_t = ros::WallTime::now();
00179 try
00180 {
00181 state_.global_pose = getGlobalRobotPose();
00182
00183 {
00184 boost::unique_lock<boost::recursive_mutex> lock(*(global_costmap_->getMutex()));
00185 state_.global_plan = global_planner_mux_.getCurrentPlugin().makePlan(state_.global_pose, state_.goal);
00186 }
00187 if (cb) result_ex.addCallback(std::bind(cb, state_.global_plan, getTimeDiffFromNow(start_t)));
00188 }
00189
00190 catch (const nav_core2::PlannerException& e)
00191 {
00192 if (fail_cb)
00193 result_ex.addCallback(std::bind(fail_cb, std::current_exception(), getTimeDiffFromNow(start_t)));
00194 }
00195 }
00196
00197 void Locomotor::makeLocalPlan(Executor& result_ex, LocalPlanCallback cb, PlannerExceptionCallback fail_cb,
00198 NavigationCompleteCallback complete_cb)
00199 {
00200 state_.global_pose = getGlobalRobotPose();
00201 state_.local_pose = getLocalRobotPose();
00202 state_.current_velocity = odom_sub_->getTwistStamped();
00203 auto& local_planner = local_planner_mux_.getCurrentPlugin();
00204
00205 if (local_planner.isGoalReached(state_.local_pose, state_.current_velocity.velocity))
00206 {
00207 if (complete_cb) result_ex.addCallback(std::bind(complete_cb));
00208 return;
00209 }
00210
00211
00212
00213 {
00214 boost::unique_lock<boost::recursive_mutex> lock(*(local_costmap_->getMutex()));
00215 ros::WallTime start_t = ros::WallTime::now();
00216 try
00217 {
00218 state_.command_velocity = local_planner.computeVelocityCommands(state_.local_pose,
00219 state_.current_velocity.velocity);
00220 lock.unlock();
00221 if (cb) result_ex.addCallback(std::bind(cb, state_.command_velocity, getTimeDiffFromNow(start_t)));
00222 }
00223 catch (const nav_core2::PlannerException& e)
00224 {
00225 lock.unlock();
00226 if (fail_cb)
00227 result_ex.addCallback(std::bind(fail_cb, std::current_exception(), getTimeDiffFromNow(start_t)));
00228 }
00229 }
00230 }
00231
00232 nav_2d_msgs::Pose2DStamped Locomotor::getRobotPose(const std::string& target_frame) const
00233 {
00234 nav_2d_msgs::Pose2DStamped robot_pose, transformed_pose;
00235 robot_pose.header.frame_id = robot_base_frame_;
00236 if (!use_latest_pose_)
00237 {
00238 robot_pose.header.stamp = ros::Time::now();
00239 }
00240 bool ret = nav_2d_utils::transformPose(tf_, target_frame, robot_pose, transformed_pose);
00241 if (!ret)
00242 {
00243 throw nav_core2::PlannerTFException("Could not get pose into costmap frame!");
00244 }
00245 return transformed_pose;
00246 }
00247
00248 }