Added collision avoidance to MoveGlobal routine
This commit is contained in:
@ -106,10 +106,13 @@ namespace mg {
|
||||
pos_query();
|
||||
target_init();
|
||||
|
||||
rclcpp::Time elapsed = baseNode.get_clock()->now();
|
||||
rclcpp::Rate rate(UPDATE_RATE);
|
||||
|
||||
while (target_check() && rclcpp::ok()) {
|
||||
target_update();
|
||||
baseNode.obstacle_manager()->update_dynamic();
|
||||
baseNode.obstacle_manager()->update_static();
|
||||
if (hgoal->is_canceling()) {
|
||||
cancel();
|
||||
return;
|
||||
@ -138,7 +141,6 @@ namespace mg {
|
||||
cvl = spacevl[b_ind];
|
||||
cvr = spacevr[b_ind];
|
||||
send_speed(step * cvl, step * cvr);
|
||||
|
||||
rate.sleep();
|
||||
}
|
||||
succeed();
|
||||
|
||||
Reference in New Issue
Block a user