Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Gemfan #2

Open
wants to merge 4 commits into
base: slam_w_2lasers
Choose a base branch
from
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
3 changes: 3 additions & 0 deletions .vscode/settings.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
{
"cmake.configureOnOpen": false
}
13 changes: 12 additions & 1 deletion articubot_one/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,15 @@ endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(rclcpp REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)

add_executable(realsense_coordinate_converter src/realsense_coordinate_converter.cpp)
ament_target_dependencies(realsense_coordinate_converter rclcpp sensor_msgs)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
Expand All @@ -37,4 +42,10 @@ install(
DESTINATION share/${PROJECT_NAME}
)

ament_package()
install(
TARGETS
realsense_coordinate_converter
DESTINATION lib/${PROJECT_NAME}
)

ament_package()
83 changes: 83 additions & 0 deletions articubot_one/config/ekf.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
### 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: false

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

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

# 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 ofodom_frame if unspecified

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

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

process_noise_covariance: [0.05, 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.05, 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.06, 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.03, 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.03, 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.06, 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.025, 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.025, 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.04, 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.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.02, 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.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.015]
# [ADVANCED] This represents the initial value for the state estimate error covariance matrix. Setting a diagonal
# value (variance) to a large value will result in rapid convergence for initial measurements of the variable in
# question. Users should take care not to use large values for variables that will not be measured directly. The values
# are ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below
#if unspecified.
initial_estimate_covariance: [1e-9, 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-9, 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-9, 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-9, 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-9, 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-9, 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-9, 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-9, 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-9, 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-9, 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-9, 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-9, 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-9, 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-9, 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-9]
9 changes: 5 additions & 4 deletions articubot_one/config/mapper_params_online_async.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -13,24 +13,25 @@ slam_toolbox:
odom_frame: odom
map_frame: map
base_frame: base_footprint
scan_topic: /scan1
scan_topic: /scan
# mode: localization
mode: mapping

# if you'd like to immediately start continuing a map at a given pose
# or at the dock, but they are mutually exclusive, if pose is given
# will use pose
# map_file_name: /home/orangepi/articubot_ws/src/articubot_one/config/maps/ada
# map_start_at_dock: true
# map_file_name: /home/orangepi/cloudy_nemo_ws/src/articubot_one/config/maps/italy
# # map_start_at_dock: true
# map_start_pose: [0.0, 0.0, 0.0]


debug_logging: false
throttle_scans: 1
transform_publish_period: 0.02 #if 0 never publishes odometry
map_update_interval: 5.0
resolution: 0.05
max_laser_range: 20.0 #for rastering images
minimum_time_interval: 0.5
minimum_time_interval: 0.5
transform_timeout: 0.2
tf_buffer_duration: 30.
stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
Expand Down
Binary file added articubot_one/config/maps/astec.data
Binary file not shown.
Binary file added articubot_one/config/maps/astec.pgm
Binary file not shown.
Binary file added articubot_one/config/maps/astec.posegraph
Binary file not shown.
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
image: milita.pgm
image: astec.pgm
mode: trinary
resolution: 0.05
origin: [-3.81, -7.6, 0]
origin: [-5.83, -8.55, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25
Binary file added articubot_one/config/maps/dust2.data
Binary file not shown.
4 changes: 4 additions & 0 deletions articubot_one/config/maps/dust2.pgm

Large diffs are not rendered by default.

Binary file not shown.
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
image: map_1688368041.pgm
image: dust2.pgm
mode: trinary
resolution: 0.05
origin: [-21.1, -9.42, 0]
origin: [-5.88, -8.66, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25
Binary file added articubot_one/config/maps/inferno.data
Binary file not shown.
Binary file added articubot_one/config/maps/inferno.pgm
Binary file not shown.
Binary file added articubot_one/config/maps/inferno.posegraph
Binary file not shown.
7 changes: 7 additions & 0 deletions articubot_one/config/maps/inferno.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
image: inferno.pgm
mode: trinary
resolution: 0.05
origin: [-5.83, -8.59, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25
Binary file added articubot_one/config/maps/italy.data
Binary file not shown.
Binary file added articubot_one/config/maps/italy.pgm
Binary file not shown.
Binary file added articubot_one/config/maps/italy.posegraph
Binary file not shown.
7 changes: 7 additions & 0 deletions articubot_one/config/maps/italy.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
image: italy.pgm
mode: trinary
resolution: 0.05
origin: [-6.04, -8.99, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25
Binary file removed articubot_one/config/maps/milita.data
Binary file not shown.
Binary file removed articubot_one/config/maps/milita.pgm
Binary file not shown.
Binary file added articubot_one/config/maps/ofis.data
Binary file not shown.
Binary file not shown.
Binary file added articubot_one/config/maps/ofis.posegraph
Binary file not shown.
7 changes: 7 additions & 0 deletions articubot_one/config/maps/ofis.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
image: ofis.pgm
mode: trinary
resolution: 0.05
origin: [-25.5, -10, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25
Loading