紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
小鱼 ROS 2 新书上线!点击链接查看, 新书配套视频点击链接查看。
提问前必看的发帖注意事项—— 提问前必看!不符合要求的问题拒绝回答!!
社区使用指南—如何添加标签修改密码
如何在不使用nav2_amcl节点的情况下实现单点导航?
-
我自己写了一个定位的节点可以发布map->odom的tf转换。
我的机器人上面有里程计节点提供odom->base_link的tf转换。
因为我是直接使用平面图作为map的,不需要LIDAR来进行建图和定位,但是我不知道如何配置navigation.yaml.我尝试调用nav2_bringup里的navigation.launch.py且使用了下面这个yaml文件:
# GPS WPF CHANGES: # - amcl params where removed. They are not needed because global localization is provided # by an ekf node on robot_localization fusing gps data with local odometry sources # - static layer is removed from both costmaps, in this tutorial we assume there is no map # of the environment # - global costmap is set to be rolling to allow the robot to traverse big environment by # following successive relatively close waypoints that fit in a smaller rolling costmap bt_navigator: ros__parameters: global_frame: map robot_base_frame: base_link odom_topic: /odom bt_loop_duration: 10 default_server_timeout: 20 navigators: ["navigate_to_pose", "navigate_through_poses"] navigate_to_pose: plugin: "nav2_bt_navigator/NavigateToPoseNavigator" navigate_through_poses: plugin: "nav2_bt_navigator/NavigateThroughPosesNavigator" # 'default_nav_through_poses_bt_xml' and 'default_nav_to_pose_bt_xml' are use defaults: # nav2_bt_navigator/navigate_to_pose_w_replanning_and_recovery.xml # nav2_bt_navigator/navigate_through_poses_w_replanning_and_recovery.xml # They can be set here or via a RewrittenYaml remap from a parent launch file to Nav2. plugin_lib_names: - nav2_compute_path_to_pose_action_bt_node - nav2_compute_path_through_poses_action_bt_node # - nav2_smooth_path_action_bt_node - nav2_follow_path_action_bt_node - nav2_spin_action_bt_node - nav2_wait_action_bt_node # - nav2_assisted_teleop_action_bt_node - nav2_back_up_action_bt_node # - nav2_drive_on_heading_bt_node - nav2_clear_costmap_service_bt_node - nav2_is_stuck_condition_bt_node - nav2_goal_reached_condition_bt_node - nav2_goal_updated_condition_bt_node # - nav2_globally_updated_goal_condition_bt_node # - nav2_is_path_valid_condition_bt_node # - nav2_are_error_codes_active_condition_bt_node # - nav2_would_a_controller_recovery_help_condition_bt_node # - nav2_would_a_planner_recovery_help_condition_bt_node # - nav2_would_a_smoother_recovery_help_condition_bt_node - nav2_initial_pose_received_condition_bt_node - nav2_reinitialize_global_localization_service_bt_node - nav2_rate_controller_bt_node - nav2_distance_controller_bt_node - nav2_speed_controller_bt_node - nav2_truncate_path_action_bt_node # - nav2_truncate_path_local_action_bt_node - nav2_goal_updater_node_bt_node - nav2_recovery_node_bt_node - nav2_pipeline_sequence_bt_node - nav2_round_robin_node_bt_node - nav2_transform_available_condition_bt_node - nav2_time_expired_condition_bt_node # - nav2_path_expiring_timer_condition - nav2_distance_traveled_condition_bt_node - nav2_single_trigger_bt_node - nav2_goal_updated_controller_bt_node - nav2_is_battery_low_condition_bt_node - nav2_navigate_through_poses_action_bt_node - nav2_navigate_to_pose_action_bt_node - nav2_remove_passed_goals_action_bt_node - nav2_planner_selector_bt_node - nav2_controller_selector_bt_node - nav2_goal_checker_selector_bt_node # - nav2_controller_cancel_bt_node # - nav2_path_longer_on_approach_bt_node # - nav2_wait_cancel_bt_node # - nav2_spin_cancel_bt_node # - nav2_back_up_cancel_bt_node # - nav2_assisted_teleop_cancel_bt_node # - nav2_drive_on_heading_cancel_bt_node # - nav2_is_battery_charging_condition_bt_node # error_code_names: # - compute_path_error_code # - follow_path_error_code controller_server: ros__parameters: controller_frequency: 20.0 min_x_velocity_threshold: 0.001 min_y_velocity_threshold: 0.5 min_theta_velocity_threshold: 0.001 failure_tolerance: 0.3 progress_checker_plugins: ["progress_checker"] goal_checker_plugins: ["general_goal_checker"] # "precise_goal_checker" controller_plugins: ["FollowPath"] # Progress checker parameters progress_checker: plugin: "nav2_controller::SimpleProgressChecker" required_movement_radius: 0.5 movement_time_allowance: 10.0 # Goal checker parameters #precise_goal_checker: # plugin: "nav2_controller::SimpleGoalChecker" # xy_goal_tolerance: 0.25 # yaw_goal_tolerance: 0.25 # stateful: True general_goal_checker: stateful: True plugin: "nav2_controller::SimpleGoalChecker" xy_goal_tolerance: 0.25 yaw_goal_tolerance: 0.25 # DWB parameters FollowPath: plugin: "dwb_core::DWBLocalPlanner" debug_trajectory_details: True min_vel_x: 0.0 min_vel_y: 0.0 max_vel_x: 0.26 max_vel_y: 0.0 max_vel_theta: 1.0 min_speed_xy: 0.0 max_speed_xy: 0.26 min_speed_theta: 0.0 # Add high threshold velocity for turtlebot 3 issue. # https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75 acc_lim_x: 2.5 acc_lim_y: 0.0 acc_lim_theta: 3.2 decel_lim_x: -2.5 decel_lim_y: 0.0 decel_lim_theta: -3.2 vx_samples: 20 vy_samples: 5 vtheta_samples: 20 sim_time: 1.7 linear_granularity: 0.05 angular_granularity: 0.025 transform_tolerance: 0.2 xy_goal_tolerance: 0.25 trans_stopped_velocity: 0.25 short_circuit_trajectory_evaluation: True stateful: True critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"] BaseObstacle.scale: 0.02 PathAlign.scale: 32.0 PathAlign.forward_point_distance: 0.1 GoalAlign.scale: 24.0 GoalAlign.forward_point_distance: 0.1 PathDist.scale: 32.0 GoalDist.scale: 24.0 RotateToGoal.scale: 32.0 RotateToGoal.slowing_factor: 5.0 RotateToGoal.lookahead_time: -1.0 # GPS WPF CHANGE: Remove static layer local_costmap: local_costmap: ros__parameters: # update_frequency: 5.0 update_frequency: 10.0 # publish_frequency: 2.0 publish_frequency: 5.0 global_frame: odom robot_base_frame: base_link rolling_window: true width: 3 height: 3 resolution: 0.05 # robot_radius: 0.22 robot_radius: 0.6 plugins: ["voxel_layer", "inflation_layer"] # plugins: ["inflation_layer"] inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" cost_scaling_factor: 3.0 inflation_radius: 0.55 voxel_layer: plugin: "nav2_costmap_2d::VoxelLayer" enabled: True publish_voxel_map: True origin_z: 0.0 z_resolution: 0.05 z_voxels: 16 max_obstacle_height: 2.0 mark_threshold: 0 observation_sources: scan scan: topic: /scan max_obstacle_height: 2.0 clearing: True marking: True data_type: "LaserScan" raytrace_max_range: 3.0 raytrace_min_range: 0.0 obstacle_max_range: 2.5 obstacle_min_range: 0.0 always_send_full_costmap: True # GPS WPF CHANGE: Remove static layer # GPS WPF CHANGE: Set rolling global costmap with 50x50 size. See note below global_costmap: global_costmap: ros__parameters: # update_frequency: 1.0 update_frequency: 20.0 # publish_frequency: 1.0 publish_frequency: 10.0 global_frame: map robot_base_frame: base_link # robot_radius: 0.22 robot_radius: 0.6 resolution: 0.1 # When using GPS navigation you will potentially traverse huge environments which are not practical to # fit on a big static costmap. Thus it is recommended to use a rolling global costmap large enough to # contain each pair of successive waypoints. See: https://github.com/ros-planning/navigation2/issues/2174 rolling_window: True # width: 50 width: 10 # height: 50 height: 10 track_unknown_space: true # no static map plugins: ["obstacle_layer", "inflation_layer"] # plugins: ["inflation_layer"] obstacle_layer: plugin: "nav2_costmap_2d::ObstacleLayer" enabled: True observation_sources: scan scan: topic: /scan max_obstacle_height: 2.0 clearing: True marking: True data_type: "LaserScan" raytrace_max_range: 3.0 raytrace_min_range: 0.0 obstacle_max_range: 2.5 obstacle_min_range: 0.0 # outdoors there will probably be more inf points inf_is_valid: true inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" cost_scaling_factor: 3.0 inflation_radius: 0.55 always_send_full_costmap: True # The yaml_filename does not need to be specified since it going to be set by defaults in launch. # If you'd rather set it in the yaml, remove the default "map" value in the tb3_simulation_launch.py # file & provide full path to map below. If CLI map configuration or launch default is provided, that will be used. # map_server: # ros__parameters: # yaml_filename: "" map_server: ros__parameters: # 这里是我的地图文件路径,路径没有问题,地图加载也没有,只是这里不方便暴露出来 yaml_filename: "turtlebot3_world.yaml" topic_name: "/map" frame_id: "map" map_saver: ros__parameters: save_map_timeout: 5.0 free_thresh_default: 0.25 occupied_thresh_default: 0.65 map_subscribe_transient_local: True planner_server: ros__parameters: expected_planner_frequency: 20.0 planner_plugins: ["GridBased"] GridBased: plugin: "nav2_navfn_planner/NavfnPlanner" tolerance: 0.5 use_astar: false allow_unknown: true smoother_server: ros__parameters: smoother_plugins: ["simple_smoother"] simple_smoother: plugin: "nav2_smoother::SimpleSmoother" tolerance: 1.0e-10 max_its: 1000 do_refinement: True behavior_server: ros__parameters: local_costmap_topic: local_costmap/costmap_raw global_costmap_topic: global_costmap/costmap_raw local_footprint_topic: local_costmap/published_footprint global_footprint_topic: global_costmap/published_footprint cycle_frequency: 10.0 behavior_plugins: ["spin", "backup", "drive_on_heading", "assisted_teleop", "wait"] spin: plugin: "nav2_behaviors/Spin" backup: plugin: "nav2_behaviors/BackUp" drive_on_heading: plugin: "nav2_behaviors/DriveOnHeading" wait: plugin: "nav2_behaviors/Wait" assisted_teleop: plugin: "nav2_behaviors/AssistedTeleop" local_frame: odom global_frame: map robot_base_frame: base_link transform_tolerance: 0.1 simulate_ahead_time: 2.0 max_rotational_vel: 1.0 min_rotational_vel: 0.4 rotational_acc_lim: 3.2 waypoint_follower: ros__parameters: loop_rate: 20 stop_on_failure: false waypoint_task_executor_plugin: "wait_at_waypoint" wait_at_waypoint: plugin: "nav2_waypoint_follower::WaitAtWaypoint" enabled: True waypoint_pause_duration: 200 velocity_smoother: ros__parameters: smoothing_frequency: 20.0 scale_velocities: False feedback: "OPEN_LOOP" max_velocity: [0.26, 0.0, 1.0] min_velocity: [-0.26, 0.0, -1.0] max_accel: [2.5, 0.0, 3.2] max_decel: [-2.5, 0.0, -3.2] odom_topic: "odom" odom_duration: 0.1 deadband_velocity: [0.0, 0.0, 0.0] velocity_timeout: 1.0
启动后没有报错,但是我不清楚如何给它机器人的初始位姿和目标点的位姿,如果使用rviz2里的插件在map上给的话会有报错:
[planner_server-7] [WARN] [1698376103.809749922] [planner_server]: The goal sent to the planner is off the global costmap. Planning will always fail to this goal. [planner_server-7] [WARN] [1698376103.810110705] [planner_server]: GridBased: failed to create plan with tolerance 0.50. [planner_server-7] [WARN] [1698376103.810187956] [planner_server]: Planning algorithm GridBased failed to generate a valid path to (6.39, -3.78) [planner_server-7] [WARN] [1698376103.810229686] [planner_server_rclcpp_node]: [compute_path_to_pose] [ActionServer] Aborting handle.
我一开始以为是我的global_costmap大小太小没有把目标点也包含在内,但是之后我将global_costmap改大之后还是报同样的错误。
会不会是我那个自己写的定位节点除了发布map->odomtf转换之外还需要别的?