Skip to content

Commit

Permalink
Create 2 topics for current goal: controller and planner
Browse files Browse the repository at this point in the history
  • Loading branch information
corot committed Nov 21, 2023
1 parent c02460e commit bab973b
Show file tree
Hide file tree
Showing 11 changed files with 16 additions and 26 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -85,15 +85,13 @@ namespace mbf_abstract_nav
* @param controller_ptr Pointer to the controller plugin
* @param robot_info Current robot state
* @param vel_pub Velocity publisher
* @param goal_pub Current goal publisher
* @param config Initial configuration for this execution
*/
AbstractControllerExecution(
const std::string &name,
const mbf_abstract_core::AbstractController::Ptr &controller_ptr,
const mbf_utility::RobotInformation &robot_info,
const ros::Publisher &vel_pub,
const ros::Publisher &goal_pub,
const MoveBaseFlexConfig &config);

/**
Expand Down Expand Up @@ -330,9 +328,6 @@ namespace mbf_abstract_nav
//! publisher for the current velocity command
ros::Publisher vel_pub_;

//! publisher for the current goal
ros::Publisher current_goal_pub_;

//! the current controller state
AbstractControllerExecution::ControllerState state_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -342,9 +342,6 @@ typedef boost::shared_ptr<dynamic_reconfigure::Server<mbf_abstract_nav::MoveBase
//! cmd_vel publisher for all controller execution objects
ros::Publisher vel_pub_;

//! current_goal publisher for all controller execution objects
ros::Publisher goal_pub_;

//! current robot state
mbf_utility::RobotInformation robot_info_;

Expand Down
2 changes: 2 additions & 0 deletions mbf_abstract_nav/include/mbf_abstract_nav/controller_action.h
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,8 @@ class ControllerAction :
geometry_msgs::PoseStamped robot_pose_; ///< Current robot pose
geometry_msgs::PoseStamped goal_pose_; ///< Current goal pose

//! Publish the current goal pose (the last pose of the path we are following)
ros::Publisher goal_pub_;
};
}

Expand Down
2 changes: 1 addition & 1 deletion mbf_abstract_nav/include/mbf_abstract_nav/planner_action.h
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ class PlannerAction : public AbstractActionBase<mbf_msgs::GetPathAction, Abstrac
private:

//! Publisher to publish the current goal pose, which is used for path planning
ros::Publisher current_goal_pub_;
ros::Publisher goal_pub_;

//! Path sequence counter
unsigned int path_seq_count_;
Expand Down
4 changes: 1 addition & 3 deletions mbf_abstract_nav/src/abstract_controller_execution.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,11 +52,10 @@ AbstractControllerExecution::AbstractControllerExecution(
const mbf_abstract_core::AbstractController::Ptr &controller_ptr,
const mbf_utility::RobotInformation &robot_info,
const ros::Publisher &vel_pub,
const ros::Publisher &goal_pub,
const MoveBaseFlexConfig &config) :
AbstractExecutionBase(name, robot_info),
controller_(controller_ptr),
state_(INITIALIZED), moving_(false), max_retries_(0), patience_(0), vel_pub_(vel_pub), current_goal_pub_(goal_pub),
state_(INITIALIZED), moving_(false), max_retries_(0), patience_(0), vel_pub_(vel_pub),
loop_rate_(DEFAULT_CONTROLLER_FREQUENCY)
{
ros::NodeHandle nh;
Expand Down Expand Up @@ -375,7 +374,6 @@ void AbstractControllerExecution::run()
condition_.notify_all();
return;
}
current_goal_pub_.publish(plan.back());
}

// compute robot pose and store it in robot_pose_
Expand Down
8 changes: 2 additions & 6 deletions mbf_abstract_nav/src/abstract_navigation_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,12 +66,8 @@ AbstractNavigationServer::AbstractNavigationServer(const TFPtr &tf_listener_ptr)
recovery_action_(name_action_recovery, robot_info_),
move_base_action_(name_action_move_base, robot_info_, recovery_plugin_manager_.getLoadedNames())
{
ros::NodeHandle nh;

goal_pub_ = nh.advertise<geometry_msgs::PoseStamped>("current_goal", 1);

// init cmd_vel publisher for the robot velocity
vel_pub_ = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1);
vel_pub_ = ros::NodeHandle().advertise<geometry_msgs::Twist>("cmd_vel", 1);

action_server_get_path_ptr_ = ActionServerGetPathPtr(
new ActionServerGetPath(
Expand Down Expand Up @@ -323,7 +319,7 @@ mbf_abstract_nav::AbstractControllerExecution::Ptr AbstractNavigationServer::new
const mbf_abstract_core::AbstractController::Ptr &plugin_ptr)
{
return boost::make_shared<mbf_abstract_nav::AbstractControllerExecution>(plugin_name, plugin_ptr, robot_info_,
vel_pub_, goal_pub_, last_config_);
vel_pub_, last_config_);
}

mbf_abstract_nav::AbstractRecoveryExecution::Ptr AbstractNavigationServer::newRecoveryExecution(
Expand Down
5 changes: 5 additions & 0 deletions mbf_abstract_nav/src/controller_action.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,9 @@ ControllerAction::ControllerAction(
const mbf_utility::RobotInformation &robot_info)
: AbstractActionBase(action_name, robot_info)
{
// informative topics: current navigation goal
ros::NodeHandle private_nh("~");
goal_pub_ = private_nh.advertise<geometry_msgs::PoseStamped>("controller_goal", 1);
}

void ControllerAction::start(
Expand Down Expand Up @@ -85,6 +88,7 @@ void ControllerAction::start(
goal_handle.getGoal()->angle_tolerance);
// Update also goal pose, so the feedback remains consistent
goal_pose_ = goal_handle.getGoal()->path.poses.back();
goal_pub_.publish(goal_pose_);
mbf_msgs::ExePathResult result;
fillExePathResult(mbf_msgs::ExePathResult::CANCELED, "Goal preempted by a new plan", result);
concurrency_slots_[slot].goal_handle.setCanceled(result, result.message);
Expand Down Expand Up @@ -146,6 +150,7 @@ void ControllerAction::runImpl(GoalHandle &goal_handle, AbstractControllerExecut
}

goal_pose_ = plan.back();
goal_pub_.publish(goal_pose_);
ROS_DEBUG_STREAM_NAMED(name_, "Called action \""
<< name_ << "\" with plan:" << std::endl
<< "frame: \"" << goal.path.header.frame_id << "\" " << std::endl
Expand Down
6 changes: 3 additions & 3 deletions mbf_abstract_nav/src/planner_action.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,9 +50,9 @@ PlannerAction::PlannerAction(
const mbf_utility::RobotInformation &robot_info)
: AbstractActionBase(name, robot_info), path_seq_count_(0)
{
ros::NodeHandle private_nh("~");
// informative topics: current navigation goal
current_goal_pub_ = private_nh.advertise<geometry_msgs::PoseStamped>("current_goal", 1);
ros::NodeHandle private_nh("~");
goal_pub_ = private_nh.advertise<geometry_msgs::PoseStamped>("planner_goal", 1);
}

void PlannerAction::runImpl(GoalHandle &goal_handle, AbstractPlannerExecution &execution)
Expand All @@ -67,7 +67,7 @@ void PlannerAction::runImpl(GoalHandle &goal_handle, AbstractPlannerExecution &e

double tolerance = goal.tolerance;
bool use_start_pose = goal.use_start_pose;
current_goal_pub_.publish(goal.target_pose);
goal_pub_.publish(goal.target_pose);

bool planner_active = true;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,6 @@ class CostmapControllerExecution : public mbf_abstract_nav::AbstractControllerEx
* @param controller_ptr Shared pointer to the plugin to use.
* @param robot_info Current robot state
* @param vel_pub Velocity commands publisher.
* @param goal_pub Goal pose publisher (just vor visualization).
* @param costmap_ptr Shared pointer to the local costmap.
* @param config Current server configuration (dynamic).
*/
Expand All @@ -76,7 +75,6 @@ class CostmapControllerExecution : public mbf_abstract_nav::AbstractControllerEx
const mbf_costmap_core::CostmapController::Ptr &controller_ptr,
const mbf_utility::RobotInformation &robot_info,
const ros::Publisher &vel_pub,
const ros::Publisher &goal_pub,
const CostmapWrapper::Ptr &costmap_ptr,
const MoveBaseFlexConfig &config);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,10 +47,9 @@ CostmapControllerExecution::CostmapControllerExecution(
const mbf_costmap_core::CostmapController::Ptr &controller_ptr,
const mbf_utility::RobotInformation &robot_info,
const ros::Publisher &vel_pub,
const ros::Publisher &goal_pub,
const CostmapWrapper::Ptr &costmap_ptr,
const MoveBaseFlexConfig &config)
: AbstractControllerExecution(controller_name, controller_ptr, robot_info, vel_pub, goal_pub, toAbstract(config)),
: AbstractControllerExecution(controller_name, controller_ptr, robot_info, vel_pub, toAbstract(config)),
costmap_ptr_(costmap_ptr)
{
ros::NodeHandle private_nh("~");
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -236,7 +236,7 @@ mbf_abstract_nav::AbstractControllerExecution::Ptr CostmapNavigationServer::newC
findWithDefault(controller_name_to_costmap_ptr_, plugin_name, local_costmap_ptr_);
return boost::make_shared<mbf_costmap_nav::CostmapControllerExecution>(
plugin_name, boost::static_pointer_cast<mbf_costmap_core::CostmapController>(plugin_ptr), robot_info_, vel_pub_,
goal_pub_, costmap_ptr, last_config_);
costmap_ptr, last_config_);
}

mbf_abstract_nav::AbstractRecoveryExecution::Ptr CostmapNavigationServer::newRecoveryExecution(
Expand Down

0 comments on commit bab973b

Please sign in to comment.