Skip to content

Commit

Permalink
Merge pull request #6 from LCAS/assessment_map
Browse files Browse the repository at this point in the history
Map of the assessment task, vanilla and refined
  • Loading branch information
pulver22 authored Nov 14, 2023
2 parents 62c8757 + eb0fc92 commit d1ae1bb
Show file tree
Hide file tree
Showing 5 changed files with 126 additions and 0 deletions.
72 changes: 72 additions & 0 deletions src/limo_navigation/launch/ekf_localization.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node

def generate_launch_description():
# Get the launch directory
launch_dir = os.path.join(
get_package_share_directory('limo_navigation'), 'launch')

# Create the launch configuration variables
# namespace = LaunchConfiguration('namespace')
use_sim_time = LaunchConfiguration('use_sim_time')
# autostart = LaunchConfiguration('autostart')

# lifecycle_nodes = [
# 'map_server',
# 'amcl',
# 'controller_server',
# 'planner_server',
# 'behavior_server',
# 'bt_navigator',
# 'waypoint_follower']

# declare_namespace = DeclareLaunchArgument(
# 'namespace', default_value='',
# description='Top-level namespace')

declare_use_sim_time = DeclareLaunchArgument(
'use_sim_time', default_value='false',
description='Use simulation (Gazebo) clock if true')

# declare_autostart = DeclareLaunchArgument(
# 'autostart', default_value='true',
# description='Automatically startup the nav2 stack')

robot_localization_node = Node(
package='robot_localization',
executable='ekf_node',
name='ekf_filter_node',
output='screen',
parameters=[os.path.join(get_package_share_directory('limo_navigation'), 'params/ekf.yaml'), {'use_sim_time': use_sim_time}]
)

# start_lifecycle_mgr = Node(
# package='nav2_lifecycle_manager',
# executable='lifecycle_manager',
# name='lifecycle_manager_navigation',
# output='screen',
# parameters=[{'use_sim_time': use_sim_time},
# {'autostart': autostart},
# {'node_names': lifecycle_nodes}])

# Create the launch description and populate
ld = LaunchDescription()

# Declare the launch options
ld.add_action(declare_use_sim_time)
# ld.add_action(declare_autostart)
# ld.add_action(declare_namespace)

# ld.add_action(launch_limo_localization)
ld.add_action(robot_localization_node)

# ld.add_action(start_lifecycle_mgr)

return ld
Binary file added src/limo_navigation/maps/assessment_map.pgm
Binary file not shown.
7 changes: 7 additions & 0 deletions src/limo_navigation/maps/assessment_map.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
image: assessment_map.pgm
mode: trinary
resolution: 0.05
origin: [-1.51, -0.758, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25
Binary file added src/limo_navigation/maps/assessment_map2.pgm
Binary file not shown.
47 changes: 47 additions & 0 deletions src/limo_navigation/params/ekf.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
### ekf config file ###
ekf_filter_node:
ros__parameters:
# The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin
# computation until it receives at least one message from one of theinputs. It will then run continuously at the
# frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified.
frequency: 30.0

# ekf_localization_node and ukf_localization_node both use a 3D omnidirectional motion model. If this parameter is
# set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar
# environment and want to ignore the effect of small variations in the ground plane that might otherwise be detected
# by, for example, an IMU. Defaults to false if unspecified.
two_d_mode: true

# Whether to publish the acceleration state. Defaults to false if unspecified.
publish_acceleration: false

# Whether to broadcast the transformation over the /tf topic. Defaults to true if unspecified.
publish_tf: false

# 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system.
# 1a. If your system does not have a map_frame, just remove it, and make sure "world_frame" is set to the value of odom_frame.
# 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data, set "world_frame"
# to your odom_frame value. This is the default behavior for robot_localization's state estimation nodes.
# 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates from landmark
# observations) then:
# 3a. Set your "world_frame" to your map_frame value
# 3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be another state estimation node
# from robot_localization! However, that instance should *not* fuse the global data.
map_frame: map # Defaults to "map" if unspecified
odom_frame: odom # Defaults to "odom" if unspecified
base_link_frame: base_link # Defaults to "base_link" ifunspecified
world_frame: odom # Defaults to the value of odom_frame if unspecified

odom0: /odom
odom0_config: [true, true, true,
false, false, false,
false, false, false,
false, false, true,
false, false, false]

imu0: /imu
imu0_config: [false, false, false,
true, true, true,
false, false, false,
false, false, false,
false, false, false]

0 comments on commit d1ae1bb

Please sign in to comment.