Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 17 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -1 +1,18 @@
# Mirte navigation


## how to
- clone, rosdep and build
- ```ros2 launch mirte_navigation robot_navigation.launch.py```
- Creating map:
- remove map, run normal launch file
- ```ros2 launch slam_toolbox online_async_launch.py```
- drive around with ```ros2 launch mirte_teleop teleop_key.launch.py```
- after creating map: cd to maps/ and ```ros2 run nav2_map_server map_saver_cli -f map```


## Todos
- omni is not really working
- min speed is often too low
- initial pose is 'defaulted' to 0,0,0
- target pose might be too far
33 changes: 31 additions & 2 deletions launch/robot_navigation.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,33 @@ def generate_launch_description():
])],
output="screen"
)

relay_topic_cmd = Node(
package = "topic_tools",
executable = "relay",
arguments=["/cmd_vel", "/mirte_base_controller/cmd_vel"],
output="screen",
)
relay_topic_odom = Node(
package = "topic_tools",
executable = "relay",
arguments=["/mirte_base_controller/odom", "/odom"],
output="screen",
)
# tf_base_footprint =
tf_base_frame = TimerAction(
period=1.0, # Delay in seconds before starting the initial pose node
actions=[Node(
package = "tf2_ros",
executable = "static_transform_publisher",
arguments=["0", "0", "0", "0", "0", "0", "base_link", "base_frame"],
output="screen",
),Node(
package = "tf2_ros",
executable = "static_transform_publisher",
arguments=["0", "0", "0", "0", "0", "0", "base_link", "base_footprint"],
output="screen",
),
])
initial_pose_node = TimerAction(
period=1.0, # Delay in seconds before starting the initial pose node
actions=[
Expand All @@ -66,5 +92,8 @@ def generate_launch_description():
localization_launch,
initial_pose_node,
navigation_launch,
rviz_command
rviz_command,
relay_topic_cmd,
relay_topic_odom,
tf_base_frame,
])
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>python3-pytest</test_depend>

<depend>topic_tools</depend>
<export>
<build_type>ament_python</build_type>
</export>
Expand Down
24 changes: 13 additions & 11 deletions params/mirte_nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,9 @@ amcl:
recovery_alpha_fast: 0.0
recovery_alpha_slow: 0.0
resample_interval: 1
robot_model_type: "nav2_amcl::DifferentialMotionModel"
# robot_model_type: "nav2_amcl::DifferentialMotionModel"
robot_model_type: "nav2_amcl::OmniMotionModel"

save_pose_rate: 0.5
sigma_hit: 0.2
tf_broadcast: true
Expand Down Expand Up @@ -70,7 +72,7 @@ controller_server:
controller_frequency: 20.0
costmap_update_timeout: 0.30
min_x_velocity_threshold: 0.001
min_y_velocity_threshold: 0.5
min_y_velocity_threshold: 0.001
min_theta_velocity_threshold: 0.001
failure_tolerance: 0.3
progress_checker_plugins: ["progress_checker"]
Expand All @@ -81,12 +83,12 @@ controller_server:
# Progress checker parameters
progress_checker:
plugin: "nav2_controller::SimpleProgressChecker"
required_movement_radius: 0.5
required_movement_radius: 0.1
movement_time_allowance: 10.0
general_goal_checker:
stateful: True
plugin: "nav2_controller::SimpleGoalChecker"
xy_goal_tolerance: 0.4
xy_goal_tolerance: 0.1
yaw_goal_tolerance: 6.2
FollowPath:
plugin: "nav2_mppi_controller::MPPIController"
Expand All @@ -109,7 +111,7 @@ controller_server:
transform_tolerance: 0.1
temperature: 0.3
gamma: 0.015
motion_model: "DiffDrive"
motion_model: "Omni"
visualize: true
regenerate_noises: true
TrajectoryVisualizer:
Expand Down Expand Up @@ -313,12 +315,12 @@ behavior_server:
plugin: "nav2_behaviors/BackUp"
acceleration_limit: 2.5
deceleration_limit: -2.5
minimum_speed: 0.10
minimum_speed: 1.0
drive_on_heading:
plugin: "nav2_behaviors/DriveOnHeading"
acceleration_limit: 2.5
deceleration_limit: -2.5
minimum_speed: 0.10
minimum_speed: 1.0
wait:
plugin: "nav2_behaviors/Wait"
assisted_teleop:
Expand Down Expand Up @@ -348,10 +350,10 @@ velocity_smoother:
smoothing_frequency: 20.0
scale_velocities: False
feedback: "OPEN_LOOP"
max_velocity: [0.5, 0.0, 1.0]
min_velocity: [-0.5, 0.0, -1.0]
max_accel: [2.5, 0.0, 3.2]
max_decel: [-2.5, 0.0, -3.2]
max_velocity: [1.0, 1.0, 1.0]
min_velocity: [-1.0, -1.0, -1.0]
max_accel: [2.5, 2.0, 3.2]
max_decel: [-2.5, -2.0, -3.2]
odom_topic: "odom"
odom_duration: 0.1
deadband_velocity: [0.0, 0.0, 0.0]
Expand Down