diff --git a/config/ekf.yaml b/config/ekf.yaml index 08e8972..2e4f2a6 100644 --- a/config/ekf.yaml +++ b/config/ekf.yaml @@ -16,7 +16,7 @@ ekf_filter_node: publish_acceleration: true # Whether to broadcast the transformation over the /tf topic. Defaultsto true if unspecified. - publish_tf: true #was true + publish_tf: false #was 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. @@ -30,14 +30,14 @@ ekf_filter_node: 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 + world_frame: odom # Defaults to the value of odom_frame if unspecified odom0: /odom # The order of the values of this parameter is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. # Configure it for x,y,z,vyaw on the odom topic - odom0_config: [true , true , false, + odom0_config: [false , false , false, false, false, true, - false, false, false, + true, false, false, false, false, true, false, false, false] odom0_differential: true