Skip to content

Commit ce18b42

Browse files
wip
1 parent d09b076 commit ce18b42

File tree

3 files changed

+11
-12
lines changed

3 files changed

+11
-12
lines changed

docker/README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@
44

55
1) Install `git`, `make` and `docker`
66

7-
2) If you have an NVIDIA graphics card, install drivers. Tutorial is [`here`][https://docs.nvidia.com/datacenter/cloud-native/container-toolkit/install-guide.html]
7+
2) If you have an NVIDIA graphics card, install drivers. Tutorial is [here](https://docs.nvidia.com/datacenter/cloud-native/container-toolkit/install-guide.html).
88

99
3) Run docker daemon and add yourself to docker group
1010
```sh

mep3_localization/config/ekf.yaml

Lines changed: 9 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -34,10 +34,10 @@ ekf_filter_node:
3434
# Debug settings. Not for the faint of heart. Outputs a ludicrous amount of information to the file specified by
3535
# debug_out_file. I hope you like matrices! Please note that setting this to true will have strongly deleterious
3636
# effects on the performance of the node. Defaults to false if unspecified.
37-
debug: false
37+
debug: true
3838

3939
# Defaults to "robot_localization_debug.txt" if unspecified. Please specify the full path.
40-
debug_out_file: /path/to/debug/file.txt
40+
debug_out_file: ~/ros2_ws/src/mep3/mep3_localization/config/localization_debug.txt
4141

4242
# Whether we'll allow old measurements to cause a re-publication of the updated state
4343
permit_corrected_publication: false
@@ -135,11 +135,9 @@ ekf_filter_node:
135135
false, false, true,
136136
false, false, false]
137137
odom0_differential: false
138-
odom0_relative: true
139-
odom0_queue_size: 2
140-
odom0_pose_rejection_threshold: 2.0
141-
odom1_twist_rejection_threshold: 0.2
142-
odom1_nodelay: false
138+
odom0_relative: false
139+
odom0_queue_size: 1
140+
odom0_nodelay: true
143141
# ArUco pose big
144142
pose0: /camera/aruco_5
145143
pose0_config: [true, true, true,
@@ -149,12 +147,12 @@ ekf_filter_node:
149147
false, false, false]
150148
pose0_differential: true
151149
pose0_relative: false
152-
pose0_queue_size: 5
153-
pose0_nodelay: false
150+
pose0_queue_size: 1
151+
pose0_nodelay: true
154152

155153
# [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set
156154
# this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame.
157-
imu0_remove_gravitational_acceleration: true
155+
# imu0_remove_gravitational_acceleration: true
158156

159157
# [ADVANCED] The EKF and UKF models follow a standard predict/correct cycle. During prediction, if there is no
160158
# acceleration reference, the velocity at time t+1 is simply predicted to be the same as the velocity at time t. During
@@ -168,7 +166,7 @@ ekf_filter_node:
168166
# predicition. Note that if an acceleration measurement for the variable in question is available from one of the
169167
# inputs, the control term will be ignored.
170168
# Whether or not we use the control input during predicition. Defaults to false.
171-
use_control: true
169+
use_control: false
172170
# Whether the input (assumed to be cmd_vel) is a geometry_msgs/Twist or geometry_msgs/TwistStamped message. Defaults to
173171
# false.
174172
stamped_control: false

mep3_localization/launch/localization_launch.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -85,6 +85,7 @@ def generate_launch_description():
8585
executable='ekf_node',
8686
name='ekf_filter_node',
8787
output='screen',
88+
emulate_tty=True,
8889
parameters=[robot_localization_file_path,
8990
{'use_sim_time': use_sim_time}])
9091

0 commit comments

Comments
 (0)