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 #include <locomotor/locomotor.h>
00035 #include <locomotor/locomotor_action_server.h>
00036 #include <nav_2d_utils/conversions.h>
00037 #include <string>
00038
00039 namespace locomotor
00040 {
00041 using nav_core2::getResultCode;
00042
00055 class DoubleThreadLocomotor
00056 {
00057 public:
00058 explicit DoubleThreadLocomotor(const ros::NodeHandle& private_nh)
00059 : private_nh_(private_nh), locomotor_(private_nh_),
00060 local_planning_ex_(private_nh_, false), global_planning_ex_(private_nh_),
00061 as_(private_nh_, std::bind(&DoubleThreadLocomotor::setGoal, this, std::placeholders::_1))
00062 {
00063 private_nh_.param("planner_frequency", planner_frequency_, planner_frequency_);
00064 desired_plan_duration_ = ros::Duration(1.0 / planner_frequency_);
00065 plan_loop_timer_ = private_nh_.createTimer(desired_plan_duration_, &DoubleThreadLocomotor::planLoopCallback,
00066 this, false, false);
00067 private_nh_.param("controller_frequency", controller_frequency_, controller_frequency_);
00068 desired_control_duration_ = ros::Duration(1.0 / controller_frequency_);
00069 control_loop_timer_ = private_nh_.createTimer(desired_control_duration_,
00070 &DoubleThreadLocomotor::controlLoopCallback,
00071 this, false, false);
00072 locomotor_.initializeGlobalCostmap(global_planning_ex_);
00073 locomotor_.initializeGlobalPlanners(global_planning_ex_);
00074 locomotor_.initializeLocalCostmap(local_planning_ex_);
00075 locomotor_.initializeLocalPlanners(local_planning_ex_);
00076 }
00077
00078 void setGoal(nav_2d_msgs::Pose2DStamped goal)
00079 {
00080 locomotor_.setGoal(goal);
00081 plan_loop_timer_.start();
00082 }
00083
00084 protected:
00085 void planLoopCallback(const ros::TimerEvent& event)
00086 {
00087 requestGlobalCostmapUpdate();
00088 }
00089
00090 void requestGlobalCostmapUpdate()
00091 {
00092 locomotor_.requestGlobalCostmapUpdate(global_planning_ex_, global_planning_ex_,
00093 std::bind(&DoubleThreadLocomotor::onGlobalCostmapUpdate, this, std::placeholders::_1),
00094 std::bind(&DoubleThreadLocomotor::onGlobalCostmapException, this, std::placeholders::_1, std::placeholders::_2));
00095 }
00096
00097 void requestNavigationFailure(const locomotor_msgs::ResultCode& result)
00098 {
00099 locomotor_.requestNavigationFailure(local_planning_ex_, result,
00100 std::bind(&DoubleThreadLocomotor::onNavigationFailure, this, std::placeholders::_1));
00101 }
00102
00103
00104 void onGlobalCostmapUpdate(const ros::Duration& planning_time)
00105 {
00106
00107 locomotor_.requestGlobalPlan(global_planning_ex_, local_planning_ex_,
00108 std::bind(&DoubleThreadLocomotor::onNewGlobalPlan, this, std::placeholders::_1, std::placeholders::_2),
00109 std::bind(&DoubleThreadLocomotor::onGlobalPlanningException, this, std::placeholders::_1, std::placeholders::_2));
00110 }
00111
00112 void onGlobalCostmapException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration& planning_time)
00113 {
00114 requestNavigationFailure(makeResultCode(locomotor_msgs::ResultCode::GLOBAL_COSTMAP, getResultCode(e_ptr),
00115 "Global Costmap failure."));
00116 }
00117
00118 void onNewGlobalPlan(nav_2d_msgs::Path2D new_global_plan, const ros::Duration& planning_time)
00119 {
00120 locomotor_.publishPath(new_global_plan);
00121 locomotor_.getCurrentLocalPlanner().setPlan(new_global_plan);
00122
00123 if (planning_time > desired_plan_duration_)
00124 {
00125 ROS_WARN_NAMED("locomotor", "Global planning missed its desired rate of %.4fHz... "
00126 "the loop actually took %.4f seconds (>%.4f).",
00127 planner_frequency_, planning_time.toSec(), desired_plan_duration_.toSec());
00128 }
00129 control_loop_timer_.start();
00130 as_.publishFeedback(locomotor_.getNavigationState());
00131 }
00132
00133 void onGlobalPlanningException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration& planning_time)
00134 {
00135 ROS_ERROR_NAMED("Locomotor", "Global planning error. Giving up.");
00136 requestNavigationFailure(makeResultCode(locomotor_msgs::ResultCode::GLOBAL_PLANNER, getResultCode(e_ptr),
00137 "Global Planning Failure."));
00138 }
00139
00140 void controlLoopCallback(const ros::TimerEvent& event)
00141 {
00142 locomotor_.requestLocalCostmapUpdate(local_planning_ex_, local_planning_ex_,
00143 std::bind(&DoubleThreadLocomotor::onLocalCostmapUpdate, this, std::placeholders::_1),
00144 std::bind(&DoubleThreadLocomotor::onLocalCostmapException, this, std::placeholders::_1, std::placeholders::_2));
00145 }
00146
00147 void onLocalCostmapUpdate(const ros::Duration& planning_time)
00148 {
00149 locomotor_.requestLocalPlan(local_planning_ex_, local_planning_ex_,
00150 std::bind(&DoubleThreadLocomotor::onNewLocalPlan, this, std::placeholders::_1, std::placeholders::_2),
00151 std::bind(&DoubleThreadLocomotor::onLocalPlanningException, this, std::placeholders::_1, std::placeholders::_2),
00152 std::bind(&DoubleThreadLocomotor::onNavigationCompleted, this));
00153 }
00154
00155 void onLocalCostmapException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration& planning_time)
00156 {
00157 requestNavigationFailure(makeResultCode(locomotor_msgs::ResultCode::LOCAL_COSTMAP, getResultCode(e_ptr),
00158 "Local Costmap failure."));
00159 }
00160
00161 void onNewLocalPlan(nav_2d_msgs::Twist2DStamped new_command, const ros::Duration& planning_time)
00162 {
00163 locomotor_.publishTwist(new_command);
00164 if (planning_time > desired_control_duration_)
00165 {
00166 ROS_WARN_NAMED("locomotor", "Control loop missed its desired rate of %.4fHz... "
00167 "the loop actually took %.4f seconds (>%.4f).",
00168 controller_frequency_, planning_time.toSec(), desired_control_duration_.toSec());
00169 }
00170 as_.publishFeedback(locomotor_.getNavigationState());
00171 }
00172
00173 void onLocalPlanningException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration& planning_time)
00174 {
00175 ROS_WARN_NAMED("Locomotor", "Local planning error. Creating new global plan.");
00176 control_loop_timer_.stop();
00177 requestGlobalCostmapUpdate();
00178 }
00179
00180 void onNavigationCompleted()
00181 {
00182 ROS_INFO_NAMED("Locomotor", "Plan completed! Stopping.");
00183 plan_loop_timer_.stop();
00184 control_loop_timer_.stop();
00185 as_.completeNavigation();
00186 }
00187
00188 void onNavigationFailure(const locomotor_msgs::ResultCode result)
00189 {
00190 plan_loop_timer_.stop();
00191 control_loop_timer_.stop();
00192 as_.failNavigation(result);
00193 }
00194
00195 ros::NodeHandle private_nh_;
00196
00197 Locomotor locomotor_;
00198
00199
00200 double planner_frequency_ { 10.0 }, controller_frequency_ { 20.0 };
00201 ros::Duration desired_plan_duration_, desired_control_duration_;
00202 ros::Timer plan_loop_timer_, control_loop_timer_;
00203
00204
00205 Executor local_planning_ex_, global_planning_ex_;
00206
00207
00208 LocomotorActionServer as_;
00209 };
00210 };
00211
00212 int main(int argc, char** argv)
00213 {
00214 ros::init(argc, argv, "locomotor_node");
00215 ros::NodeHandle nh("~");
00216 locomotor::DoubleThreadLocomotor sm(nh);
00217 ros::spin();
00218 return 0;
00219 }