diff --git a/nav2_costmap_filters_demo/launch/costmap_filter_info.launch.py b/nav2_costmap_filters_demo/launch/costmap_filter_info.launch.py
index 4a24082..0578879 100644
--- a/nav2_costmap_filters_demo/launch/costmap_filter_info.launch.py
+++ b/nav2_costmap_filters_demo/launch/costmap_filter_info.launch.py
@@ -22,7 +22,7 @@
from launch.actions import DeclareLaunchArgument, GroupAction
from launch.conditions import IfCondition
from launch.substitutions import LaunchConfiguration, PythonExpression
-from launch.substitutions import NotEqualsSubstitution
+# from launch.substitutions import NotEqualsSubstitution
from launch_ros.actions import Node, LoadComposableNodes
from launch_ros.actions import PushRosNamespace
from launch_ros.descriptions import ComposableNode
@@ -123,7 +123,10 @@ def generate_launch_description():
condition=IfCondition(use_composition),
actions=[
PushRosNamespace(
- condition=IfCondition(NotEqualsSubstitution(LaunchConfiguration('namespace'), '')),
+ # condition=IfCondition(NotEqualsSubstitution(LaunchConfiguration('namespace'), '')),
+ condition=IfCondition(PythonExpression(["'",
+ LaunchConfiguration('namespace'),
+ "' != ''",])),
namespace=namespace),
LoadComposableNodes(
target_container=container_name_full,
diff --git a/nav2_gps_waypoint_follower_demo/config/demo_waypoints.yaml b/nav2_gps_waypoint_follower_demo/config/demo_waypoints.yaml
deleted file mode 100644
index 367eb37..0000000
--- a/nav2_gps_waypoint_follower_demo/config/demo_waypoints.yaml
+++ /dev/null
@@ -1,13 +0,0 @@
-waypoints:
-- latitude: 38.161491054181276
- longitude: -122.45464431092836
- yaw: 0.0
-- latitude: 38.161587576524845
- longitude: -122.4547994038464
- yaw: 1.57
-- latitude: 38.161708040316405
- longitude: -122.45499603070951
- yaw: 3.14
-- latitude: 38.16180165780551
- longitude: -122.45515645020123
- yaw: 4.71
diff --git a/nav2_gps_waypoint_follower_demo/config/dual_ekf_navsat_params.yaml b/nav2_gps_waypoint_follower_demo/config/dual_ekf_navsat_params.yaml
deleted file mode 100644
index 5358f15..0000000
--- a/nav2_gps_waypoint_follower_demo/config/dual_ekf_navsat_params.yaml
+++ /dev/null
@@ -1,127 +0,0 @@
-# For parameter descriptions, please refer to the template parameter files for each node.
-
-ekf_filter_node_odom:
- ros__parameters:
- frequency: 30.0
- two_d_mode: true # Recommended to use 2d mode for nav2 in mostly planar environments
- print_diagnostics: true
- debug: false
- publish_tf: true
-
- map_frame: map
- odom_frame: odom
- base_link_frame: base_footprint # the frame id used by the turtlebot's diff drive plugin
- world_frame: odom
-
- odom0: odom
- odom0_config: [false, false, false,
- false, false, false,
- true, true, true,
- false, false, true,
- false, false, false]
- odom0_queue_size: 10
- odom0_differential: false
- odom0_relative: false
-
- imu0: imu
- imu0_config: [false, false, false,
- false, false, true,
- false, false, false,
- false, false, false,
- false, false, false]
- imu0_differential: false # If using a real robot you might want to set this to true, since usually absolute measurements from real imu's are not very accurate
- imu0_relative: false
- imu0_queue_size: 10
- imu0_remove_gravitational_acceleration: true
-
- use_control: false
-
- process_noise_covariance: [1e-3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 1e-3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 1e-3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3]
-
-ekf_filter_node_map:
- ros__parameters:
- frequency: 30.0
- two_d_mode: true # Recommended to use 2d mode for nav2 in mostly planar environments
- print_diagnostics: true
- debug: false
- publish_tf: true
-
- map_frame: map
- odom_frame: odom
- base_link_frame: base_footprint # the frame id used by the turtlebot's diff drive plugin
- world_frame: map
-
- odom0: odom
- odom0_config: [false, false, false,
- false, false, false,
- true, true, true,
- false, false, true,
- false, false, false]
- odom0_queue_size: 10
- odom0_differential: false
- odom0_relative: false
-
- odom1: odometry/gps
- odom1_config: [true, true, false,
- false, false, false,
- false, false, false,
- false, false, false,
- false, false, false]
- odom1_queue_size: 10
- odom1_differential: false
- odom1_relative: false
-
- imu0: imu
- imu0_config: [false, false, false,
- false, false, true,
- false, false, false,
- false, false, false,
- false, false, false]
- imu0_differential: false # If using a real robot you might want to set this to true, since usually absolute measurements from real imu's are not very accurate
- imu0_relative: false
- imu0_queue_size: 10
- imu0_remove_gravitational_acceleration: true
-
- use_control: false
-
- process_noise_covariance: [1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 1e-3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.5, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3, 0.0,
- 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.3]
-
-navsat_transform:
- ros__parameters:
- frequency: 30.0
- delay: 3.0
- magnetic_declination_radians: 0.0
- yaw_offset: 0.0
- zero_altitude: true
- broadcast_utm_transform: true
- publish_filtered_gps: true
- use_odometry_yaw: true
- wait_for_datum: false
diff --git a/nav2_gps_waypoint_follower_demo/config/gps_wpf_demo.mvc b/nav2_gps_waypoint_follower_demo/config/gps_wpf_demo.mvc
deleted file mode 100644
index bb578c7..0000000
--- a/nav2_gps_waypoint_follower_demo/config/gps_wpf_demo.mvc
+++ /dev/null
@@ -1,56 +0,0 @@
-capture_directory: "~"
-fixed_frame: map
-target_frame: map
-fix_orientation: false
-rotate_90: false
-enable_antialiasing: true
-show_displays: true
-show_status_bar: true
-show_capture_tools: true
-window_width: 1920
-window_height: 1016
-view_scale: 0.564473748
-offset_x: -55.0469894
-offset_y: -4.65194941
-use_latest_transforms: true
-background: "#a0a0a4"
-image_transport: raw
-displays:
- - type: mapviz_plugins/tile_map
- name: new display
- config:
- visible: true
- collapsed: false
- custom_sources:
- []
- bing_api_key: ""
- source: Bing Maps (terrain)
- - type: mapviz_plugins/point_click_publisher
- name: new display
- config:
- visible: true
- collapsed: false
- topic: clicked_point
- output_frame: wgs84
- - type: mapviz_plugins/tf_frame
- name: new display
- config:
- visible: true
- collapsed: false
- frame: base_link
- color: "#00ff00"
- draw_style: arrows
- position_tolerance: 0
- buffer_size: 1
- static_arrow_sizes: true
- arrow_size: 53
- - type: mapviz_plugins/navsat
- name: new display
- config:
- visible: true
- collapsed: false
- topic: /gps/fix
- color: "#55aaff"
- draw_style: points
- position_tolerance: 0
- buffer_size: 1
\ No newline at end of file
diff --git a/nav2_gps_waypoint_follower_demo/config/nav2_no_map_params.yaml b/nav2_gps_waypoint_follower_demo/config/nav2_no_map_params.yaml
deleted file mode 100644
index 31fad8f..0000000
--- a/nav2_gps_waypoint_follower_demo/config/nav2_no_map_params.yaml
+++ /dev/null
@@ -1,315 +0,0 @@
-# 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
- publish_frequency: 2.0
- global_frame: odom
- robot_base_frame: base_link
- rolling_window: true
- width: 3
- height: 3
- resolution: 0.05
- robot_radius: 0.22
- plugins: ["voxel_layer", "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
- publish_frequency: 1.0
- global_frame: map
- robot_base_frame: base_link
- robot_radius: 0.22
- 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
- height: 50
- track_unknown_space: true
- # no static map
- plugins: ["obstacle_layer", "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_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
diff --git a/nav2_gps_waypoint_follower_demo/launch/dual_ekf_navsat.launch.py b/nav2_gps_waypoint_follower_demo/launch/dual_ekf_navsat.launch.py
deleted file mode 100644
index 553985c..0000000
--- a/nav2_gps_waypoint_follower_demo/launch/dual_ekf_navsat.launch.py
+++ /dev/null
@@ -1,68 +0,0 @@
-# Copyright 2018 Open Source Robotics Foundation, Inc.
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-# http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-from launch import LaunchDescription
-from ament_index_python.packages import get_package_share_directory
-from launch.actions import IncludeLaunchDescription
-from launch.launch_description_sources import PythonLaunchDescriptionSource
-import launch_ros.actions
-import os
-import launch.actions
-
-
-def generate_launch_description():
- gps_wpf_dir = get_package_share_directory(
- "nav2_gps_waypoint_follower_demo")
- rl_params_file = os.path.join(
- gps_wpf_dir, "config", "dual_ekf_navsat_params.yaml")
-
- return LaunchDescription(
- [
- launch.actions.DeclareLaunchArgument(
- "output_final_position", default_value="false"
- ),
- launch.actions.DeclareLaunchArgument(
- "output_location", default_value="~/dual_ekf_navsat_example_debug.txt"
- ),
- launch_ros.actions.Node(
- package="robot_localization",
- executable="ekf_node",
- name="ekf_filter_node_odom",
- output="screen",
- parameters=[rl_params_file, {"use_sim_time": True}],
- remappings=[("odometry/filtered", "odometry/local")],
- ),
- launch_ros.actions.Node(
- package="robot_localization",
- executable="ekf_node",
- name="ekf_filter_node_map",
- output="screen",
- parameters=[rl_params_file, {"use_sim_time": True}],
- remappings=[("odometry/filtered", "odometry/global")],
- ),
- launch_ros.actions.Node(
- package="robot_localization",
- executable="navsat_transform_node",
- name="navsat_transform",
- output="screen",
- parameters=[rl_params_file, {"use_sim_time": True}],
- remappings=[
- ("imu/data", "imu/data"),
- ("gps/fix", "gps/fix"),
- ("gps/filtered", "gps/filtered"),
- ("odometry/gps", "odometry/gps"),
- ("odometry/filtered", "odometry/global"),
- ],
- ),
- ]
- )
diff --git a/nav2_gps_waypoint_follower_demo/launch/gazebo_gps_world.launch.py b/nav2_gps_waypoint_follower_demo/launch/gazebo_gps_world.launch.py
deleted file mode 100644
index 4bf4449..0000000
--- a/nav2_gps_waypoint_follower_demo/launch/gazebo_gps_world.launch.py
+++ /dev/null
@@ -1,82 +0,0 @@
-# Copyright (c) 2018 Intel Corporation
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-# http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-import os
-
-from ament_index_python.packages import get_package_share_directory
-
-from launch import LaunchDescription
-from launch.actions import ExecuteProcess, SetEnvironmentVariable
-from launch_ros.actions import Node
-
-
-def generate_launch_description():
- # Get the launch directory
- gps_wpf_dir = get_package_share_directory(
- "nav2_gps_waypoint_follower_demo")
- launch_dir = os.path.join(gps_wpf_dir, 'launch')
- world = os.path.join(gps_wpf_dir, "worlds", "sonoma_raceway.world")
-
- urdf = os.path.join(gps_wpf_dir, 'urdf', 'turtlebot3_waffle_gps.urdf')
- with open(urdf, 'r') as infp:
- robot_description = infp.read()
-
- models_dir = os.path.join(gps_wpf_dir, "models")
- models_dir += os.pathsep + \
- f"/opt/ros/{os.getenv('ROS_DISTRO')}/share/turtlebot3_gazebo/models"
- set_gazebo_model_path_cmd = None
-
- if 'GAZEBO_MODEL_PATH' in os.environ:
- gazebo_model_path = os.environ['GAZEBO_MODEL_PATH'] + \
- os.pathsep + models_dir
- set_gazebo_model_path_cmd = SetEnvironmentVariable(
- "GAZEBO_MODEL_PATH", gazebo_model_path)
- else:
- set_gazebo_model_path_cmd = SetEnvironmentVariable(
- "GAZEBO_MODEL_PATH", models_dir)
-
- set_tb3_model_cmd = SetEnvironmentVariable("TURTLEBOT3_MODEL", "waffle")
-
- # Specify the actions
- start_gazebo_server_cmd = ExecuteProcess(
- cmd=['gzserver', '-s', 'libgazebo_ros_init.so',
- '-s', 'libgazebo_ros_factory.so', world],
- cwd=[launch_dir], output='both')
-
- start_gazebo_client_cmd = ExecuteProcess(
- cmd=['gzclient'],
- cwd=[launch_dir], output='both')
-
- start_robot_state_publisher_cmd = Node(
- package='robot_state_publisher',
- executable='robot_state_publisher',
- name='robot_state_publisher',
- output='both',
- parameters=[{'robot_description': robot_description}])
-
- # Create the launch description and populate
- ld = LaunchDescription()
-
- # Set gazebo up to find models properly
- ld.add_action(set_gazebo_model_path_cmd)
- ld.add_action(set_tb3_model_cmd)
-
- # simulator launch
- ld.add_action(start_gazebo_server_cmd)
- ld.add_action(start_gazebo_client_cmd)
-
- # robot state publisher launch
- ld.add_action(start_robot_state_publisher_cmd)
-
- return ld
diff --git a/nav2_gps_waypoint_follower_demo/launch/gps_waypoint_follower.launch.py b/nav2_gps_waypoint_follower_demo/launch/gps_waypoint_follower.launch.py
deleted file mode 100644
index 279fafd..0000000
--- a/nav2_gps_waypoint_follower_demo/launch/gps_waypoint_follower.launch.py
+++ /dev/null
@@ -1,103 +0,0 @@
-# Copyright (c) 2018 Intel Corporation
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-# http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-import os
-
-from ament_index_python.packages import get_package_share_directory
-
-from launch import LaunchDescription
-from launch.substitutions import LaunchConfiguration
-from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument
-from launch.launch_description_sources import PythonLaunchDescriptionSource
-from launch.conditions import IfCondition
-from nav2_common.launch import RewrittenYaml
-
-
-def generate_launch_description():
- # Get the launch directory
- bringup_dir = get_package_share_directory('nav2_bringup')
- gps_wpf_dir = get_package_share_directory(
- "nav2_gps_waypoint_follower_demo")
- launch_dir = os.path.join(gps_wpf_dir, 'launch')
- params_dir = os.path.join(gps_wpf_dir, "config")
- nav2_params = os.path.join(params_dir, "nav2_no_map_params.yaml")
- configured_params = RewrittenYaml(
- source_file=nav2_params, root_key="", param_rewrites="", convert_types=True
- )
-
- use_rviz = LaunchConfiguration('use_rviz')
- use_mapviz = LaunchConfiguration('use_mapviz')
-
- declare_use_rviz_cmd = DeclareLaunchArgument(
- 'use_rviz',
- default_value='False',
- description='Whether to start RVIZ')
-
- declare_use_mapviz_cmd = DeclareLaunchArgument(
- 'use_mapviz',
- default_value='False',
- description='Whether to start mapviz')
-
- gazebo_cmd = IncludeLaunchDescription(
- PythonLaunchDescriptionSource(
- os.path.join(launch_dir, 'gazebo_gps_world.launch.py'))
- )
-
- robot_localization_cmd = IncludeLaunchDescription(
- PythonLaunchDescriptionSource(
- os.path.join(launch_dir, 'dual_ekf_navsat.launch.py'))
- )
-
- navigation2_cmd = IncludeLaunchDescription(
- PythonLaunchDescriptionSource(
- os.path.join(bringup_dir, "launch", "navigation_launch.py")
- ),
- launch_arguments={
- "use_sim_time": "True",
- "params_file": configured_params,
- "autostart": "True",
- }.items(),
- )
-
- rviz_cmd = IncludeLaunchDescription(
- PythonLaunchDescriptionSource(
- os.path.join(bringup_dir, "launch", 'rviz_launch.py')),
- condition=IfCondition(use_rviz)
- )
-
- mapviz_cmd = IncludeLaunchDescription(
- PythonLaunchDescriptionSource(
- os.path.join(launch_dir, 'mapviz.launch.py')),
- condition=IfCondition(use_mapviz)
- )
-
- # Create the launch description and populate
- ld = LaunchDescription()
-
- # simulator launch
- ld.add_action(gazebo_cmd)
-
- # robot localization launch
- ld.add_action(robot_localization_cmd)
-
- # navigation2 launch
- ld.add_action(navigation2_cmd)
-
- # viz launch
- ld.add_action(declare_use_rviz_cmd)
- ld.add_action(rviz_cmd)
- ld.add_action(declare_use_mapviz_cmd)
- ld.add_action(mapviz_cmd)
-
- return ld
diff --git a/nav2_gps_waypoint_follower_demo/launch/mapviz.launch.py b/nav2_gps_waypoint_follower_demo/launch/mapviz.launch.py
deleted file mode 100644
index b8ef693..0000000
--- a/nav2_gps_waypoint_follower_demo/launch/mapviz.launch.py
+++ /dev/null
@@ -1,34 +0,0 @@
-import launch
-import launch.actions
-import launch.substitutions
-import launch_ros.actions
-import os
-from ament_index_python.packages import get_package_share_directory
-
-gps_wpf_dir = get_package_share_directory("nav2_gps_waypoint_follower_demo")
-mapviz_config_file = os.path.join(gps_wpf_dir, "config", "gps_wpf_demo.mvc")
-
-
-def generate_launch_description():
- return launch.LaunchDescription([
- launch_ros.actions.Node(
- package="mapviz",
- executable="mapviz",
- name="mapviz",
- parameters=[{"config": mapviz_config_file}]
- ),
- launch_ros.actions.Node(
- package="swri_transform_util",
- executable="initialize_origin.py",
- name="initialize_origin",
- remappings=[
- ("fix", "gps/fix"),
- ],
- ),
- launch_ros.actions.Node(
- package="tf2_ros",
- executable="static_transform_publisher",
- name="swri_transform",
- arguments=["0", "0", "0", "0", "0", "0", "map", "origin"]
- )
- ])
diff --git a/nav2_gps_waypoint_follower_demo/models/turtlebot_waffle_gps/model.config b/nav2_gps_waypoint_follower_demo/models/turtlebot_waffle_gps/model.config
deleted file mode 100755
index 6543f64..0000000
--- a/nav2_gps_waypoint_follower_demo/models/turtlebot_waffle_gps/model.config
+++ /dev/null
@@ -1,19 +0,0 @@
-
-
-
- turtlebot_waffle_gps
- 2.0
- model.sdf
-
-
- Taehun Lim(Darby)
- thlim@robotis.com
-
- Melih Erdogan(mlherd)
- h.meliherdogan@gmail.com
-
-
-
- TurtleBot3 Waffle with a gps sensor
-
-
diff --git a/nav2_gps_waypoint_follower_demo/models/turtlebot_waffle_gps/model.sdf b/nav2_gps_waypoint_follower_demo/models/turtlebot_waffle_gps/model.sdf
deleted file mode 100755
index 2479342..0000000
--- a/nav2_gps_waypoint_follower_demo/models/turtlebot_waffle_gps/model.sdf
+++ /dev/null
@@ -1,561 +0,0 @@
-
-
-
-
-
-
-
-
- 0.0 0.0 0.0 0.0 0.0 0.0
-
-
-
-
-
-
- -0.064 0 0.048 0 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 1.0
-
-
-
- -0.064 0 0.048 0 0 0
-
-
- 0.265 0.265 0.089
-
-
-
-
-
- -0.064 0 0 0 0 0
-
-
- model://turtlebot3_common/meshes/waffle_base.dae
- 0.001 0.001 0.001
-
-
-
-
-
-
-
- true
- 200
-
-
-
-
- 0.0
- 2e-4
-
-
-
-
- 0.0
- 2e-4
-
-
-
-
- 0.0
- 2e-4
-
-
-
-
-
-
- 0.0
- 1.7e-2
-
-
-
-
- 0.0
- 1.7e-2
-
-
-
-
- 0.0
- 1.7e-2
-
-
-
-
-
- false
-
-
- ~/out:=imu
-
-
-
-
-
-
-
-
- -0.052 0 0.111 0 0 0
-
- 0.001
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.125
-
-
- true
- 1
- 0 0 0 0 0 0
-
-
-
-
- 0.0
- 0.01
-
-
-
-
- 0.0
- 0.01
-
-
-
-
-
-
- ~/out:=/gps/fix
-
-
-
-
-
-
-
- -0.064 0 0.121 0 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.125
-
-
-
- -0.052 0 0.111 0 0 0
-
-
- 0.0508
- 0.055
-
-
-
-
-
- -0.064 0 0.121 0 0 0
-
-
- model://turtlebot3_common/meshes/lds.dae
- 0.001 0.001 0.001
-
-
-
-
-
- true
- false
- -0.064 0 0.15 0 0 0
- 5
-
-
-
- 360
- 1.000000
- 0.000000
- 6.280000
-
-
-
- 0.00000
- 20.0
- 0.015000
-
-
- gaussian
- 0.0
- 0.01
-
-
-
-
-
- ~/out:=scan
-
- sensor_msgs/LaserScan
- base_scan
-
-
-
-
-
-
-
- 0.0 0.144 0.023 -1.57 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.1
-
-
-
- 0.0 0.144 0.023 -1.57 0 0
-
-
- 0.033
- 0.018
-
-
-
-
-
-
- 100000.0
- 100000.0
- 0 0 0
- 0.0
- 0.0
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
- 0.0 0.144 0.023 0 0 0
-
-
- model://turtlebot3_common/meshes/tire.dae
- 0.001 0.001 0.001
-
-
-
-
-
-
-
-
- 0.0 -0.144 0.023 -1.57 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.1
-
-
-
- 0.0 -0.144 0.023 -1.57 0 0
-
-
- 0.033
- 0.018
-
-
-
-
-
-
- 100000.0
- 100000.0
- 0 0 0
- 0.0
- 0.0
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
- 0.0 -0.144 0.023 0 0 0
-
-
- model://turtlebot3_common/meshes/tire.dae
- 0.001 0.001 0.001
-
-
-
-
-
-
- -0.177 -0.064 -0.004 0 0 0
-
- 0.001
-
- 0.00001
- 0.000
- 0.000
- 0.00001
- 0.000
- 0.00001
-
-
-
-
-
- 0.005000
-
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
-
- -0.177 0.064 -0.004 0 0 0
-
- 0.001
-
- 0.00001
- 0.000
- 0.000
- 0.00001
- 0.000
- 0.00001
-
-
-
-
-
- 0.005000
-
-
-
-
-
- 0
- 0.2
- 1e+5
- 1
- 0.01
- 0.001
-
-
-
-
-
-
-
-
- 0.069 -0.047 0.107 0 0 0
-
- 0.001
- 0.000
- 0.000
- 0.001
- 0.000
- 0.001
-
- 0.035
-
-
- 0 0.047 -0.005 0 0 0
-
-
- 0.008 0.130 0.022
-
-
-
-
- 0.069 -0.047 0.107 0 0 0
-
-
- 1
- 5
- 0.064 -0.047 0.107 0 0 0
-
-
-
-
-
- intel_realsense_r200_depth
- camera_depth_frame
- 0.07
- 0.001
- 5.0
-
-
-
-
-
- base_footprint
- base_link
- 0.0 0.0 0.010 0 0 0
-
-
-
- base_link
- imu_link
- -0.032 0 0.068 0 0 0
-
- 0 0 1
-
-
-
-
- base_link
- gps_link
- -0.05 0 0.05 0 0 0
-
- 0 0 1
-
-
-
-
- base_link
- wheel_left_link
- 0.0 0.144 0.023 -1.57 0 0
-
- 0 0 1
-
-
-
-
- base_link
- wheel_right_link
- 0.0 -0.144 0.023 -1.57 0 0
-
- 0 0 1
-
-
-
-
- base_link
- caster_back_right_link
-
-
-
- base_link
- caster_back_left_link
-
-
-
- base_link
- base_scan
- -0.064 0 0.121 0 0 0
-
- 0 0 1
-
-
-
-
- base_link
- camera_link
- 0.064 -0.065 0.094 0 0 0
-
- 0 0 1
-
-
-
-
-
-
-
-
- /tf:=tf
-
-
- 30
-
-
- wheel_left_joint
- wheel_right_joint
-
-
- 0.287
- 0.066
-
-
- 20
- 1.0
-
- cmd_vel
-
-
-
- true
- false
- false
-
- odom
- odom
- base_footprint
-
-
-
-
-
-
- ~/out:=joint_states
-
- 30
- wheel_left_joint
- wheel_right_joint
-
-
-
-
\ No newline at end of file
diff --git a/nav2_gps_waypoint_follower_demo/nav2_gps_waypoint_follower_demo/__init__.py b/nav2_gps_waypoint_follower_demo/nav2_gps_waypoint_follower_demo/__init__.py
deleted file mode 100644
index e69de29..0000000
diff --git a/nav2_gps_waypoint_follower_demo/nav2_gps_waypoint_follower_demo/gps_waypoint_logger.py b/nav2_gps_waypoint_follower_demo/nav2_gps_waypoint_follower_demo/gps_waypoint_logger.py
deleted file mode 100644
index a80ec1a..0000000
--- a/nav2_gps_waypoint_follower_demo/nav2_gps_waypoint_follower_demo/gps_waypoint_logger.py
+++ /dev/null
@@ -1,128 +0,0 @@
-import rclpy
-from rclpy.node import Node
-from sensor_msgs.msg import NavSatFix, Imu
-import yaml
-import os
-import sys
-import tkinter as tk
-from tkinter import messagebox
-from nav2_gps_waypoint_follower_demo.utils.gps_utils import euler_from_quaternion
-
-
-class GpsGuiLogger(tk.Tk, Node):
- """
- ROS2 node to log GPS waypoints to a file
- """
-
- def __init__(self, logging_file_path):
- tk.Tk.__init__(self)
- Node.__init__(self, 'gps_waypoint_logger')
- self.title("GPS Waypoint Logger")
-
- self.logging_file_path = logging_file_path
-
- self.gps_pose_label = tk.Label(self, text="Current Coordinates:")
- self.gps_pose_label.pack()
- self.gps_pose_textbox = tk.Label(self, text="", width=45)
- self.gps_pose_textbox.pack()
-
- self.log_gps_wp_button = tk.Button(self, text="Log GPS Waypoint",
- command=self.log_waypoint)
- self.log_gps_wp_button.pack()
-
- self.gps_subscription = self.create_subscription(
- NavSatFix,
- '/gps/fix',
- self.gps_callback,
- 1
- )
- self.last_gps_position = NavSatFix()
-
- self.imu_subscription = self.create_subscription(
- Imu,
- '/imu',
- self.imu_callback,
- 1
- )
- self.last_heading = 0.0
-
- def gps_callback(self, msg: NavSatFix):
- """
- Callback to store the last GPS pose
- """
- self.last_gps_position = msg
- self.updateTextBox()
-
- def imu_callback(self, msg: Imu):
- """
- Callback to store the last heading
- """
- _, _, self.last_heading = euler_from_quaternion(msg.orientation)
- self.updateTextBox()
-
- def updateTextBox(self):
- """
- Function to update the GUI with the last coordinates
- """
- self.gps_pose_textbox.config(
- text=f"Lat: {self.last_gps_position.latitude:.6f}, Lon: {self.last_gps_position.longitude:.6f}, yaw: {self.last_heading:.2f} rad")
-
- def log_waypoint(self):
- """
- Function to save a new waypoint to a file
- """
- # read existing waypoints
- try:
- with open(self.logging_file_path, 'r') as yaml_file:
- existing_data = yaml.safe_load(yaml_file)
- # in case the file does not exist, create with the new wps
- except FileNotFoundError:
- existing_data = {"waypoints": []}
- # if other exception, raise the warining
- except Exception as ex:
- messagebox.showerror(
- "Error", f"Error logging position: {str(ex)}")
- return
-
- # build new waypoint object
- data = {
- "latitude": self.last_gps_position.latitude,
- "longitude": self.last_gps_position.longitude,
- "yaw": self.last_heading
- }
- existing_data["waypoints"].append(data)
-
- # write updated waypoints
- try:
- with open(self.logging_file_path, 'w') as yaml_file:
- yaml.dump(existing_data, yaml_file, default_flow_style=False)
- except Exception as ex:
- messagebox.showerror(
- "Error", f"Error logging position: {str(ex)}")
- return
-
- messagebox.showinfo("Info", "Waypoint logged succesfully")
-
-
-def main(args=None):
- rclpy.init(args=args)
-
- # allow to pass the logging path as an argument
- default_yaml_file_path = os.path.expanduser("~/gps_waypoints.yaml")
- if len(sys.argv) > 1:
- yaml_file_path = sys.argv[1]
- else:
- yaml_file_path = default_yaml_file_path
-
- gps_gui_logger = GpsGuiLogger(yaml_file_path)
-
- while rclpy.ok():
- # we spin both the ROS system and the interface
- rclpy.spin_once(gps_gui_logger, timeout_sec=0.1) # Run ros2 callbacks
- gps_gui_logger.update() # Update the tkinter interface
-
- rclpy.shutdown()
-
-
-if __name__ == '__main__':
- main()
diff --git a/nav2_gps_waypoint_follower_demo/nav2_gps_waypoint_follower_demo/interactive_waypoint_follower.py b/nav2_gps_waypoint_follower_demo/nav2_gps_waypoint_follower_demo/interactive_waypoint_follower.py
deleted file mode 100644
index 2783ddf..0000000
--- a/nav2_gps_waypoint_follower_demo/nav2_gps_waypoint_follower_demo/interactive_waypoint_follower.py
+++ /dev/null
@@ -1,43 +0,0 @@
-import rclpy
-from rclpy.node import Node
-from nav2_simple_commander.robot_navigator import BasicNavigator
-from geometry_msgs.msg import PointStamped
-from nav2_gps_waypoint_follower_demo.utils.gps_utils import latLonYaw2Geopose
-
-
-class InteractiveGpsWpCommander(Node):
- """
- ROS2 node to send gps waypoints to nav2 received from mapviz's point click publisher
- """
-
- def __init__(self):
- super().__init__(node_name="gps_wp_commander")
- self.navigator = BasicNavigator("basic_navigator")
-
- self.mapviz_wp_sub = self.create_subscription(
- PointStamped, "/clicked_point", self.mapviz_wp_cb, 1)
-
- def mapviz_wp_cb(self, msg: PointStamped):
- """
- clicked point callback, sends received point to nav2 gps waypoint follower if its a geographic point
- """
- if msg.header.frame_id != "wgs84":
- self.get_logger().warning(
- "Received point from mapviz that ist not in wgs84 frame. This is not a gps point and wont be followed")
- return
-
- self.navigator.waitUntilNav2Active(localizer='robot_localization')
- wp = [latLonYaw2Geopose(msg.point.y, msg.point.x)]
- self.navigator.followGpsWaypoints(wp)
- if (self.navigator.isTaskComplete()):
- self.get_logger().info("wps completed successfully")
-
-
-def main():
- rclpy.init()
- gps_wpf = InteractiveGpsWpCommander()
- rclpy.spin(gps_wpf)
-
-
-if __name__ == "__main__":
- main()
diff --git a/nav2_gps_waypoint_follower_demo/nav2_gps_waypoint_follower_demo/logged_waypoint_follower.py b/nav2_gps_waypoint_follower_demo/nav2_gps_waypoint_follower_demo/logged_waypoint_follower.py
deleted file mode 100644
index 101fbb7..0000000
--- a/nav2_gps_waypoint_follower_demo/nav2_gps_waypoint_follower_demo/logged_waypoint_follower.py
+++ /dev/null
@@ -1,69 +0,0 @@
-import rclpy
-from nav2_simple_commander.robot_navigator import BasicNavigator
-import yaml
-from ament_index_python.packages import get_package_share_directory
-import os
-import sys
-import time
-
-from nav2_gps_waypoint_follower_demo.utils.gps_utils import latLonYaw2Geopose
-
-
-class YamlWaypointParser:
- """
- Parse a set of gps waypoints from a yaml file
- """
-
- def __init__(self, wps_file_path: str) -> None:
- with open(wps_file_path, 'r') as wps_file:
- self.wps_dict = yaml.safe_load(wps_file)
-
- def get_wps(self):
- """
- Get an array of geographic_msgs/msg/GeoPose objects from the yaml file
- """
- gepose_wps = []
- for wp in self.wps_dict["waypoints"]:
- latitude, longitude, yaw = wp["latitude"], wp["longitude"], wp["yaw"]
- gepose_wps.append(latLonYaw2Geopose(latitude, longitude, yaw))
- return gepose_wps
-
-
-class GpsWpCommander():
- """
- Class to use nav2 gps waypoint follower to follow a set of waypoints logged in a yaml file
- """
-
- def __init__(self, wps_file_path):
- self.navigator = BasicNavigator("basic_navigator")
- self.wp_parser = YamlWaypointParser(wps_file_path)
-
- def start_wpf(self):
- """
- Function to start the waypoint following
- """
- self.navigator.waitUntilNav2Active(localizer='robot_localization')
- wps = self.wp_parser.get_wps()
- self.navigator.followGpsWaypoints(wps)
- while (not self.navigator.isTaskComplete()):
- time.sleep(0.1)
- print("wps completed successfully")
-
-
-def main():
- rclpy.init()
-
- # allow to pass the waypoints file as an argument
- default_yaml_file_path = os.path.join(get_package_share_directory(
- "nav2_gps_waypoint_follower_demo"), "config", "demo_waypoints.yaml")
- if len(sys.argv) > 1:
- yaml_file_path = sys.argv[1]
- else:
- yaml_file_path = default_yaml_file_path
-
- gps_wpf = GpsWpCommander(yaml_file_path)
- gps_wpf.start_wpf()
-
-
-if __name__ == "__main__":
- main()
diff --git a/nav2_gps_waypoint_follower_demo/nav2_gps_waypoint_follower_demo/utils/__init__.py b/nav2_gps_waypoint_follower_demo/nav2_gps_waypoint_follower_demo/utils/__init__.py
deleted file mode 100644
index e69de29..0000000
diff --git a/nav2_gps_waypoint_follower_demo/nav2_gps_waypoint_follower_demo/utils/gps_utils.py b/nav2_gps_waypoint_follower_demo/nav2_gps_waypoint_follower_demo/utils/gps_utils.py
deleted file mode 100644
index eb0cda7..0000000
--- a/nav2_gps_waypoint_follower_demo/nav2_gps_waypoint_follower_demo/utils/gps_utils.py
+++ /dev/null
@@ -1,54 +0,0 @@
-import math
-from geographic_msgs.msg import GeoPose
-from geometry_msgs.msg import Quaternion
-
-
-def quaternion_from_euler(roll, pitch, yaw):
- """
- Converts euler roll, pitch, yaw to quaternion
- """
- cy = math.cos(yaw * 0.5)
- sy = math.sin(yaw * 0.5)
- cp = math.cos(pitch * 0.5)
- sp = math.sin(pitch * 0.5)
- cr = math.cos(roll * 0.5)
- sr = math.sin(roll * 0.5)
-
- q = Quaternion()
- q.w = cy * cp * cr + sy * sp * sr
- q.x = cy * cp * sr - sy * sp * cr
- q.y = sy * cp * sr + cy * sp * cr
- q.z = sy * cp * cr - cy * sp * sr
- return q
-
-
-def euler_from_quaternion(q: Quaternion):
- """
- Convert a quaternion into euler angles
- taken from: https://automaticaddison.com/how-to-convert-a-quaternion-into-euler-angles-in-python/
- """
- t0 = +2.0 * (q.w * q.x + q.y * q.z)
- t1 = +1.0 - 2.0 * (q.x * q.x + q.y * q.y)
- roll_x = math.atan2(t0, t1)
-
- t2 = +2.0 * (q.w * q.y - q.z * q.x)
- t2 = +1.0 if t2 > +1.0 else t2
- t2 = -1.0 if t2 < -1.0 else t2
- pitch_y = math.asin(t2)
-
- t3 = +2.0 * (q.w * q.z + q.x * q.y)
- t4 = +1.0 - 2.0 * (q.y * q.y + q.z * q.z)
- yaw_z = math.atan2(t3, t4)
-
- return roll_x, pitch_y, yaw_z
-
-
-def latLonYaw2Geopose(latitude: float, longitude: float, yaw: float = 0.0) -> GeoPose:
- """
- Creates a geographic_msgs/msg/GeoPose object from latitude, longitude and yaw
- """
- geopose = GeoPose()
- geopose.position.latitude = latitude
- geopose.position.longitude = longitude
- geopose.orientation = quaternion_from_euler(0.0, 0.0, yaw)
- return geopose
diff --git a/nav2_gps_waypoint_follower_demo/package.xml b/nav2_gps_waypoint_follower_demo/package.xml
deleted file mode 100644
index 8bed9e4..0000000
--- a/nav2_gps_waypoint_follower_demo/package.xml
+++ /dev/null
@@ -1,20 +0,0 @@
-
-
-
- nav2_gps_waypoint_follower_demo
- 0.0.0
- Demo package for following GPS waypoints with nav2
- pepisg
- Steve Macenski
- MIT
-
- navigation2
- robot_localization
- mapviz
- mapviz_plugins
- tile_map
-
-
- ament_python
-
-
diff --git a/nav2_gps_waypoint_follower_demo/resource/nav2_gps_waypoint_follower_demo b/nav2_gps_waypoint_follower_demo/resource/nav2_gps_waypoint_follower_demo
deleted file mode 100644
index e69de29..0000000
diff --git a/nav2_gps_waypoint_follower_demo/setup.cfg b/nav2_gps_waypoint_follower_demo/setup.cfg
deleted file mode 100644
index b0f2147..0000000
--- a/nav2_gps_waypoint_follower_demo/setup.cfg
+++ /dev/null
@@ -1,4 +0,0 @@
-[develop]
-script_dir=$base/lib/nav2_gps_waypoint_follower_demo
-[install]
-install_scripts=$base/lib/nav2_gps_waypoint_follower_demo
diff --git a/nav2_gps_waypoint_follower_demo/setup.py b/nav2_gps_waypoint_follower_demo/setup.py
deleted file mode 100644
index 943a265..0000000
--- a/nav2_gps_waypoint_follower_demo/setup.py
+++ /dev/null
@@ -1,36 +0,0 @@
-from setuptools import find_packages, setup
-import os
-from glob import glob
-
-package_name = 'nav2_gps_waypoint_follower_demo'
-
-setup(
- name=package_name,
- version='0.0.1',
- packages=find_packages(exclude=['test']),
- data_files=[
- ('share/ament_index/resource_index/packages',
- ['resource/' + package_name]),
- ('share/' + package_name, ['package.xml']),
- (os.path.join('share', package_name, 'launch'), glob('launch/*.launch.py')),
- (os.path.join('share', package_name, 'config'), glob('config/*')),
- (os.path.join('share', package_name, 'urdf'), glob('urdf/*')),
- (os.path.join('share', package_name, 'worlds'), glob('worlds/*')),
- (os.path.join('share', package_name, 'models/turtlebot_waffle_gps'),
- glob('models/turtlebot_waffle_gps/*')),
- ],
- install_requires=['setuptools'],
- zip_safe=True,
- maintainer='root',
- maintainer_email='pedro.gonzalez@eia.edu.co',
- description='Demo package for following GPS waypoints with nav2',
- license='MIT',
- tests_require=['pytest'],
- entry_points={
- 'console_scripts': [
- 'logged_waypoint_follower = nav2_gps_waypoint_follower_demo.logged_waypoint_follower:main',
- 'interactive_waypoint_follower = nav2_gps_waypoint_follower_demo.interactive_waypoint_follower:main',
- 'gps_waypoint_logger = nav2_gps_waypoint_follower_demo.gps_waypoint_logger:main'
- ],
- },
-)
diff --git a/nav2_gps_waypoint_follower_demo/test/test_copyright.py b/nav2_gps_waypoint_follower_demo/test/test_copyright.py
deleted file mode 100644
index 97a3919..0000000
--- a/nav2_gps_waypoint_follower_demo/test/test_copyright.py
+++ /dev/null
@@ -1,25 +0,0 @@
-# Copyright 2015 Open Source Robotics Foundation, Inc.
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-# http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-from ament_copyright.main import main
-import pytest
-
-
-# Remove the `skip` decorator once the source file(s) have a copyright header
-@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
-@pytest.mark.copyright
-@pytest.mark.linter
-def test_copyright():
- rc = main(argv=['.', 'test'])
- assert rc == 0, 'Found errors'
diff --git a/nav2_gps_waypoint_follower_demo/test/test_flake8.py b/nav2_gps_waypoint_follower_demo/test/test_flake8.py
deleted file mode 100644
index 27ee107..0000000
--- a/nav2_gps_waypoint_follower_demo/test/test_flake8.py
+++ /dev/null
@@ -1,25 +0,0 @@
-# Copyright 2017 Open Source Robotics Foundation, Inc.
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-# http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-from ament_flake8.main import main_with_errors
-import pytest
-
-
-@pytest.mark.flake8
-@pytest.mark.linter
-def test_flake8():
- rc, errors = main_with_errors(argv=[])
- assert rc == 0, \
- 'Found %d code style errors / warnings:\n' % len(errors) + \
- '\n'.join(errors)
diff --git a/nav2_gps_waypoint_follower_demo/test/test_pep257.py b/nav2_gps_waypoint_follower_demo/test/test_pep257.py
deleted file mode 100644
index b234a38..0000000
--- a/nav2_gps_waypoint_follower_demo/test/test_pep257.py
+++ /dev/null
@@ -1,23 +0,0 @@
-# Copyright 2015 Open Source Robotics Foundation, Inc.
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-# http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-from ament_pep257.main import main
-import pytest
-
-
-@pytest.mark.linter
-@pytest.mark.pep257
-def test_pep257():
- rc = main(argv=['.', 'test'])
- assert rc == 0, 'Found code style errors / warnings'
diff --git a/nav2_gps_waypoint_follower_demo/urdf/turtlebot3_waffle_gps.urdf b/nav2_gps_waypoint_follower_demo/urdf/turtlebot3_waffle_gps.urdf
deleted file mode 100644
index 8fa7b2c..0000000
--- a/nav2_gps_waypoint_follower_demo/urdf/turtlebot3_waffle_gps.urdf
+++ /dev/null
@@ -1,305 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
\ No newline at end of file
diff --git a/nav2_gps_waypoint_follower_demo/worlds/sonoma_raceway.world b/nav2_gps_waypoint_follower_demo/worlds/sonoma_raceway.world
deleted file mode 100644
index 9a08cbd..0000000
--- a/nav2_gps_waypoint_follower_demo/worlds/sonoma_raceway.world
+++ /dev/null
@@ -1,61 +0,0 @@
-
-
-
-
-
- 0.95 0.95 0.95 1
- 0.3 0.3 0.3 1
- true
-
-
- 3
-
-
-
-
- model://sun
-
-
- model://sonoma_raceway
- -287.5 143.5 -7 0 0 0
-
-
-
- EARTH_WGS84
- 38.161479
- -122.454630
- 488.0
- 180
-
-
-
- 100.0
- 0.01
- 1
-
-
- quick
- 150
- 0
- 1.400000
- 1
-
-
- 0.00001
- 0.2
- 2000.000000
- 0.01000
-
-
-
-
-
- model://turtlebot_waffle_gps
- 2 -2.5 0.3 0 0 0
-
-
-
-
\ No newline at end of file
diff --git a/nav2_pure_pursuit_controller/src/pure_pursuit_controller.cpp b/nav2_pure_pursuit_controller/src/pure_pursuit_controller.cpp
index 071fd57..744bcb5 100644
--- a/nav2_pure_pursuit_controller/src/pure_pursuit_controller.cpp
+++ b/nav2_pure_pursuit_controller/src/pure_pursuit_controller.cpp
@@ -10,8 +10,7 @@
#include
#include
-#include "nav2_core/controller_exceptions.hpp"
-#include "nav2_core/planner_exceptions.hpp"
+#include "nav2_core/exceptions.hpp"
#include "nav2_util/node_utils.hpp"
#include "nav2_pure_pursuit_controller/pure_pursuit_controller.hpp"
#include "nav2_util/geometry_utils.hpp"
diff --git a/nav2_sms_behavior/include/nav2_sms_behavior/send_sms.hpp b/nav2_sms_behavior/include/nav2_sms_behavior/send_sms.hpp
index 35a6f59..f7c127f 100644
--- a/nav2_sms_behavior/include/nav2_sms_behavior/send_sms.hpp
+++ b/nav2_sms_behavior/include/nav2_sms_behavior/send_sms.hpp
@@ -24,18 +24,12 @@ class SendSms : public TimedBehavior
SendSms();
~SendSms();
- ResultStatus onRun(const std::shared_ptr command) override;
+ Status onRun(const std::shared_ptr command) override;
- ResultStatus onCycleUpdate() override;
+ Status onCycleUpdate() override;
void onConfigure() override;
- /**
- * @brief Method to determine the required costmap info
- * @return costmap resources needed
- */
- nav2_core::CostmapInfoType getResourceInfo() override {return nav2_core::CostmapInfoType::NONE;}
-
protected:
std::string _account_sid;
std::string _auth_token;
diff --git a/nav2_sms_behavior/src/send_sms.cpp b/nav2_sms_behavior/src/send_sms.cpp
index 06fe0e2..b672491 100644
--- a/nav2_sms_behavior/src/send_sms.cpp
+++ b/nav2_sms_behavior/src/send_sms.cpp
@@ -33,7 +33,7 @@ void SendSms::onConfigure()
_twilio = std::make_shared(_account_sid, _auth_token);
}
-ResultStatus SendSms::onRun(const std::shared_ptr command)
+Status SendSms::onRun(const std::shared_ptr command)
{
auto node = node_.lock();
std::string response;
@@ -46,16 +46,16 @@ ResultStatus SendSms::onRun(const std::shared_ptr command)
false);
if (!message_success) {
RCLCPP_INFO(node->get_logger(), "SMS send failed.");
- return ResultStatus{Status::FAILED};
+ return Status::FAILED;
}
RCLCPP_INFO(node->get_logger(), "SMS sent successfully!");
- return ResultStatus{Status::SUCCEEDED};
+ return Status::SUCCEEDED;
}
-ResultStatus SendSms::onCycleUpdate()
+Status SendSms::onCycleUpdate()
{
- return ResultStatus{Status::SUCCEEDED};
+ return Status::SUCCEEDED;
}
} // namespace nav2_sms_behavior
diff --git a/nav2_straightline_planner/include/nav2_straightline_planner/straight_line_planner.hpp b/nav2_straightline_planner/include/nav2_straightline_planner/straight_line_planner.hpp
index 3643763..1b6f839 100644
--- a/nav2_straightline_planner/include/nav2_straightline_planner/straight_line_planner.hpp
+++ b/nav2_straightline_planner/include/nav2_straightline_planner/straight_line_planner.hpp
@@ -81,8 +81,7 @@ class StraightLine : public nav2_core::GlobalPlanner
// This method creates path for given start and goal pose.
nav_msgs::msg::Path createPlan(
const geometry_msgs::msg::PoseStamped & start,
- const geometry_msgs::msg::PoseStamped & goal,
- std::function cancel_checker) override;
+ const geometry_msgs::msg::PoseStamped & goal) override;
private:
// TF buffer
diff --git a/nav2_straightline_planner/src/straight_line_planner.cpp b/nav2_straightline_planner/src/straight_line_planner.cpp
index a8b35ea..1a3b47d 100644
--- a/nav2_straightline_planner/src/straight_line_planner.cpp
+++ b/nav2_straightline_planner/src/straight_line_planner.cpp
@@ -89,8 +89,7 @@ void StraightLine::deactivate()
nav_msgs::msg::Path StraightLine::createPlan(
const geometry_msgs::msg::PoseStamped & start,
- const geometry_msgs::msg::PoseStamped & goal,
- std::function /*cancel_checker*/)
+ const geometry_msgs::msg::PoseStamped & goal)
{
nav_msgs::msg::Path global_path;
diff --git a/sam_bot_description/config/nav2_params.yaml b/sam_bot_description/config/nav2_params.yaml
index 1d3c6e4..8ed21c0 100644
--- a/sam_bot_description/config/nav2_params.yaml
+++ b/sam_bot_description/config/nav2_params.yaml
@@ -328,6 +328,7 @@ robot_state_publisher:
waypoint_follower:
ros__parameters:
+ use_sim_time: True
loop_rate: 20
stop_on_failure: false
waypoint_task_executor_plugin: "wait_at_waypoint"