feat: amend topics

master
邱棚 2024-07-16 10:39:06 +08:00
parent ff7117c075
commit dee3c6856b
2 changed files with 13 additions and 5 deletions

7
.gitignore vendored
View File

@ -16,3 +16,10 @@ build
# Version control
.svn
.vscode/
.idea/
# Compiled files
mpc_local_planner/cmake-build-debug/

View File

@ -143,13 +143,14 @@ void MpcLocalPlannerROS::initialize(std::string name, tf2_ros::Buffer* tf, costm
nh.param("footprint_model/is_footprint_dynamic", _params.is_footprint_dynamic, _params.is_footprint_dynamic);
nh.param("collision_avoidance/include_costmap_obstacles", _params.include_costmap_obstacles, _params.include_costmap_obstacles);
nh.param("collision_avoidance/costmap_obstacles_behind_robot_dist", _params.costmap_obstacles_behind_robot_dist,
nh.param("collision/include_costmap_obstacles", _params.include_costmap_obstacles, _params.include_costmap_obstacles);
nh.param("collision/costmap_obstacles_behind_robot_dist", _params.costmap_obstacles_behind_robot_dist,
_params.costmap_obstacles_behind_robot_dist);
nh.param("collision_avoidance/collision_check_no_poses", _params.collision_check_no_poses, _params.collision_check_no_poses);
nh.param("collision_avoidance/collision_check_min_resolution_angular", _params.collision_check_min_resolution_angular,
nh.param("collision/collision_check_no_poses", _params.collision_check_no_poses, _params.collision_check_no_poses);
nh.param("collision/collision_check_min_resolution_angular", _params.collision_check_min_resolution_angular,
_params.collision_check_min_resolution_angular);
ROS_INFO("collision/collision_check_no_poses:%d",_params.collision_check_no_poses);
// 代价地图转换器插件相关参数
nh.param("costmap_converter_plugin", _costmap_conv_params.costmap_converter_plugin, _costmap_conv_params.costmap_converter_plugin);
@ -353,7 +354,7 @@ uint32_t MpcLocalPlannerROS::computeVelocityCommands(const geometry_msgs::PoseSt
// 修剪全局计划,剪掉机器人之前的部分
pruneGlobalPlan(*_tf, robot_pose, _global_plan, _params.global_plan_prune_distance);
// 修剪全局计划,剪掉机器人之前的部分
// Convert To Local frame
std::vector<geometry_msgs::PoseStamped> transformed_plan;
int goal_idx;
geometry_msgs::TransformStamped tf_plan_to_global;