# true, true, false,
# false, false, true,
# false, false, false]
- odom0_config: [true, true, false,
- false, false, true,
+ odom0_config: [true, true, false,
false, false, false,
+ true, true, false,
false, false, false,
false, false, false]
- # imu0: sensor/imu
+ imu0: sensor/imu
# robot localization recommendation
- # imu0_config: [false, false, false,
- # false, false, true,
- # false, false, false,
- # false, false, true,
- # true, false, false]
+ imu0_config: [false, false, false,
+ false, false, true,
+ false, false, false,
+ false, false, true,
+ false, false, false]
+ # a localizaçao pela aceleracao do imu nao é boa. testei só com ela e ficou terrivel e ao fundir, piorou o do ground_truth
# nav2 docs recommendation
# imu0_config: [false, false, false,
# true, true, true,
<node pkg="robot_localization" exec="ekf_node" name="ekf_filter_node">
<param name="use_sim_time" value="$(var use_sim_time)"/>
- <param name="odom0" value="$(var controller)/odom"/>
+ <param name="odom0" value="/ground_truth"/>
<param from="$(find-pkg-share twil_2dnav)/config/ekf_params.yaml"/>
</node>
<arg name="gps" value="$(var gps)"/>
</include>
- <node name="twil_spawner" pkg="gazebo_ros" exec="spawn_entity.py" args="-topic robot_description -entity twil"/>
+ <node name="twil_spawner" pkg="gazebo_ros" exec="spawn_entity.py" args="-topic robot_description -entity twil -timeout 60"/>
</launch>