49 costmap_loader_(
"nav_core2",
"nav_core2::Costmap"),
50 global_planner_mux_(
"nav_core2",
"nav_core2::GlobalPlanner",
51 "global_planner_namespaces",
"dlux_global_planner::DluxGlobalPlanner",
52 "current_global_planner",
"switch_global_planner"),
53 local_planner_mux_(
"nav_core2",
"nav_core2::LocalPlanner",
54 "local_planner_namespaces",
"dwb_local_planner::DWBLocalPlanner",
55 "current_local_planner",
"switch_local_planner"),
56 private_nh_(private_nh), path_pub_(private_nh_), twist_pub_(private_nh_)
66 std::placeholders::_2));
69 odom_sub_ = std::make_shared<nav_2d_utils::OdomSubscriber>(global_nh);
74 std::string costmap_class;
75 private_nh_.
param(
"global_costmap_class", costmap_class, std::string(
"nav_core_adapter::CostmapAdapter"));
76 ROS_INFO_NAMED(
"Locomotor",
"Loading Global Costmap %s", costmap_class.c_str());
84 std::string costmap_class;
85 private_nh_.
param(
"local_costmap_class", costmap_class, std::string(
"nav_core_adapter::CostmapAdapter"));
86 ROS_INFO_NAMED(
"Locomotor",
"Loading Local Costmap %s", costmap_class.c_str());
96 ROS_INFO_NAMED(
"Locomotor",
"Initializing global planner %s", planner_name.c_str());
105 ROS_INFO_NAMED(
"Locomotor",
"Initializing local planner %s", planner_name.c_str());
113 state_ = locomotor_msgs::NavigationState();
120 new_local_planner.setGoalPose(
state_.goal);
121 new_local_planner.setPlan(
state_.global_plan);
164 boost::unique_lock<boost::recursive_mutex> lock(*(costmap.
getMutex()));
184 boost::unique_lock<boost::recursive_mutex> lock(*(
global_costmap_->getMutex()));
205 if (local_planner.isGoalReached(
state_.local_pose,
state_.current_velocity.velocity))
207 if (complete_cb) result_ex.
addCallback(std::bind(complete_cb));
214 boost::unique_lock<boost::recursive_mutex> lock(*(
local_costmap_->getMutex()));
218 state_.command_velocity = local_planner.computeVelocityCommands(
state_.local_pose,
219 state_.current_velocity.velocity);
234 nav_2d_msgs::Pose2DStamped robot_pose, transformed_pose;
245 return transformed_pose;
nav_2d_utils::PluginMux< nav_core2::LocalPlanner > local_planner_mux_
nav_2d_msgs::Pose2DStamped getLocalRobotPose() const
nav_2d_msgs::Pose2DStamped getRobotPose(const std::string &target_frame) const
ros::Duration getTimeDiffFromNow(const ros::WallTime &start_time)
std::function< void(const nav_2d_msgs::Path2D &, const ros::Duration &)> GlobalPlanCallback
#define ROS_INFO_NAMED(name,...)
pluginlib::ClassLoader< nav_core2::Costmap > costmap_loader_
Collection of objects used in ROS CallbackQueue threading.
bool transformPose(const TFListenerPtr tf, const std::string frame, const geometry_msgs::PoseStamped &in_pose, geometry_msgs::PoseStamped &out_pose, const bool extrapolation_fallback=true)
nav_core2::Costmap::Ptr global_costmap_
std::function< void(const locomotor_msgs::ResultCode)> NavigationFailureCallback
void requestLocalCostmapUpdate(Executor &work_ex, Executor &result_ex, CostmapUpdateCallback cb=nullptr, CostmapUpdateExceptionCallback fail_cb=nullptr)
Request the local costmap get updated as a new callback.
std::function< void(nav_core2::NavCore2ExceptionPtr, const ros::Duration &)> CostmapUpdateExceptionCallback
void initializeGlobalPlanners(Executor &ex)
ros::NodeHandle private_nh_
virtual void setGoal(nav_2d_msgs::Pose2DStamped goal)
Starts a new navigation to the given goal.
std::function< void(nav_core2::NavCore2ExceptionPtr, const ros::Duration &)> PlannerExceptionCallback
T & getPlugin(const std::string &name)
locomotor_msgs::NavigationState state_
nav_2d_msgs::Pose2DStamped getGlobalRobotPose() const
std::function< void(const ros::Duration &)> CostmapUpdateCallback
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::string robot_base_frame_
void initializeLocalCostmap(Executor &ex)
nav_2d_utils::PluginMux< nav_core2::GlobalPlanner > global_planner_mux_
void initializeGlobalCostmap(Executor &ex)
virtual void switchLocalPlannerCallback(const std::string &old_planner, const std::string &new_planner)
Callback for when the local planner switches to ensure the new planner has up to date information...
void doCostmapUpdate(nav_core2::Costmap &costmap, Executor &result_ex, CostmapUpdateCallback cb, CostmapUpdateExceptionCallback fail_cb)
void initializeLocalPlanners(Executor &ex)
void requestNavigationFailure(Executor &result_ex, const locomotor_msgs::ResultCode &result, NavigationFailureCallback cb=nullptr)
Request that a onNavigationFailure event be added as a new callback.
Locomotor(const ros::NodeHandle &private_nh)
Base Constructor.
void setSwitchCallback(SwitchCallback switch_callback)
nav_core2::Costmap::Ptr local_costmap_
std::function< void()> NavigationCompleteCallback
void addCallback(LocomotorCallback::Function f)
Add a callback to this executor's CallbackQueue.
void makeLocalPlan(Executor &result_ex, LocalPlanCallback cb, PlannerExceptionCallback fail_cb, NavigationCompleteCallback complete_cb)
virtual const ros::NodeHandle & getNodeHandle() const
Gets NodeHandle coupled with this executor's CallbackQueue.
void makeGlobalPlan(Executor &result_ex, GlobalPlanCallback cb, PlannerExceptionCallback fail_cb)
void requestGlobalCostmapUpdate(Executor &work_ex, Executor &result_ex, CostmapUpdateCallback cb=nullptr, CostmapUpdateExceptionCallback fail_cb=nullptr)
Request the global costmap get updated as a new callback.
virtual mutex_t * getMutex()=0
std::function< void(const nav_2d_msgs::Twist2DStamped &, const ros::Duration &)> LocalPlanCallback
void requestGlobalPlan(Executor &work_ex, Executor &result_ex, GlobalPlanCallback cb=nullptr, PlannerExceptionCallback fail_cb=nullptr)
Request the global planner get run as a new callback.
std::vector< std::string > getPluginNames() const
std::shared_ptr< nav_2d_utils::OdomSubscriber > odom_sub_
void requestLocalPlan(Executor &work_ex, Executor &result_ex, LocalPlanCallback cb=nullptr, PlannerExceptionCallback fail_cb=nullptr, NavigationCompleteCallback complete_cb=nullptr)
Request the local planner get run as a new callback.