Skip to content

Commit

Permalink
rename
Browse files Browse the repository at this point in the history
  • Loading branch information
siferati committed Dec 12, 2023
1 parent d2312fb commit 5acae8c
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 12 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -234,12 +234,12 @@ class CostmapNavigationServer : public mbf_abstract_nav::AbstractNavigationServe
bool callServiceFindValidPose(mbf_msgs::FindValidPose::Request& request, mbf_msgs::FindValidPose::Response& response);

/**
* @brief Callback method for the force_update_costmaps service
* @brief Callback method for the update_costmaps service
* @param request Empty request object.
* @param response Empty response object.
* @return true, if the service completed successfully, false otherwise
*/
bool callForceUpdateCostmaps(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);
bool callServiceUpdateCostmaps(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);

/**
* @brief Reconfiguration method called by dynamic reconfigure.
Expand Down Expand Up @@ -294,8 +294,8 @@ class CostmapNavigationServer : public mbf_abstract_nav::AbstractNavigationServe
//! Service Server for the find_valid_pose service
ros::ServiceServer find_valid_pose_srv_;

//! Service Server for the force_update_costmap service
ros::ServiceServer force_update_costmaps_srv_;
//! Service Server for the update_costmap service
ros::ServiceServer update_costmaps_srv_;

static constexpr double ANGLE_INCREMENT = 5.0 * M_PI / 180.0; // 5 degrees
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -175,13 +175,12 @@ CostmapNavigationServer::CostmapNavigationServer(const TFPtr& tf_listener_ptr)
private_nh_.advertiseService("check_pose_cost", &CostmapNavigationServer::callServiceCheckPoseCost, this);
check_path_cost_srv_ =
private_nh_.advertiseService("check_path_cost", &CostmapNavigationServer::callServiceCheckPathCost, this);
clear_costmaps_srv_ =
private_nh_.advertiseService("clear_costmaps", &CostmapNavigationServer::callServiceClearCostmaps, this);
find_valid_pose_srv_ =
private_nh_.advertiseService("find_valid_pose", &CostmapNavigationServer::callServiceFindValidPose, this);

force_update_costmaps_srv_ =
private_nh_.advertiseService("force_update_costmaps", &CostmapNavigationServer::callForceUpdateCostmaps, this);
update_costmaps_srv_ =
private_nh_.advertiseService("update_costmaps", &CostmapNavigationServer::callServiceUpdateCostmaps, this);
clear_costmaps_srv_ =
private_nh_.advertiseService("clear_costmaps", &CostmapNavigationServer::callServiceClearCostmaps, this);

// dynamic reconfigure server for mbf_costmap_nav configuration; also include abstract server parameters
dsrv_costmap_ = boost::make_shared<dynamic_reconfigure::Server<mbf_costmap_nav::MoveBaseFlexConfig> >(private_nh_);
Expand Down Expand Up @@ -821,10 +820,10 @@ bool CostmapNavigationServer::callServiceClearCostmaps(std_srvs::Empty::Request&
return true;
}

bool CostmapNavigationServer::callForceUpdateCostmaps(std_srvs::Empty::Request& request,
std_srvs::Empty::Response& response)
bool CostmapNavigationServer::callServiceUpdateCostmaps(std_srvs::Empty::Request& request,
std_srvs::Empty::Response& response)
{
// force update both costmaps
// update both costmaps
for (auto costmap : { local_costmap_ptr_, global_costmap_ptr_ })
{
costmap->checkActivate();
Expand Down

0 comments on commit 5acae8c

Please sign in to comment.