Skip to content

Commit

Permalink
Address comments
Browse files Browse the repository at this point in the history
  • Loading branch information
nhatao committed Nov 2, 2023
1 parent 8db995a commit 40375d1
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 8 deletions.
13 changes: 6 additions & 7 deletions planner_cspace/src/planner_3d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -723,7 +723,7 @@ class Planner3dNode
previous_path_ = path;
}

void applyCostmapUpdate(const costmap_cspace_msgs::CSpace3DUpdate::ConstPtr msg)
void applyCostmapUpdate(const costmap_cspace_msgs::CSpace3DUpdate::ConstPtr& msg)
{
const auto ts_cm_init_start = boost::chrono::high_resolution_clock::now();
const ros::Time now = ros::Time::now();
Expand Down Expand Up @@ -914,7 +914,7 @@ class Planner3dNode
no_map_update_timer_ =
nh_.createTimer(costmap_watchdog_, &Planner3dNode::cbNoMapUpdateTimer, this, true);
}
void cbMapUpdate(const costmap_cspace_msgs::CSpace3DUpdate::ConstPtr msg)
void cbMapUpdate(const costmap_cspace_msgs::CSpace3DUpdate::ConstPtr& msg)
{
if (!has_map_)
return;
Expand All @@ -923,11 +923,6 @@ class Planner3dNode
{
no_map_update_timer_.stop();
updateStart();
if (jump_.detectJump())
{
bbf_costmap_.clear();
// Robot pose jumped.
}
applyCostmapUpdate(msg);
planPath(last_costmap_);
if (costmap_watchdog_ > ros::Duration(0))
Expand Down Expand Up @@ -1648,6 +1643,10 @@ class Planner3dNode
{
if (trigger_plan_by_costmap_update_)
{
if (jump_.detectJump())
{
bbf_costmap_.clear();
}
ros::spinOnce();
r.sleep();
}
Expand Down
2 changes: 1 addition & 1 deletion planner_cspace/test/src/test_dynamic_parameter_change.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -193,7 +193,7 @@ class DynamicParameterChangeTest
pub_map_overlay_.publish(map_overlay_);
}

double getAveragePathInterval(const ros::Duration costmap_publishing_interval)
double getAveragePathInterval(const ros::Duration& costmap_publishing_interval)
{
publishMapAndRobot(2.55, 0.45, M_PI);
ros::Duration(0.3).sleep();
Expand Down

0 comments on commit 40375d1

Please sign in to comment.