diff --git a/launch/include/localization.launch b/launch/include/localization.launch index e2d13f60839295d3cd4f75daa9f57fde7a9b1315..d2f1955ff6e794162d0ea48768fd725a1c7cc201 100644 --- a/launch/include/localization.launch +++ b/launch/include/localization.launch @@ -3,51 +3,16 @@ <launch> <arg name="name" default="model_car"/> - <arg name="local_ekf_config_file" default="$(find iri_model_car_rosnav)/params/$(arg name)_local_ekf.yaml"/> - <arg name="global_ekf_config_file" default="$(find iri_model_car_rosnav)/params/$(arg name)_global_ekf.yaml"/> - <arg name="global_loc" default="false"/> - - <node pkg="imu_msg_fix" - name="imu_msg_fix" - ns="$(arg name)" - type="imu_msg_fix" - output="screen"> - <param name="fix_frame_id" value="false"/> - <param name="frame_id" value=""/> - <param name="fix_cov" value="false"/> - <param name="cov_orientation" value="0.01"/> - <param name="cov_vel" value="0.01"/> - <param name="cov_acc" value="0.01"/> - <param name="imu_reference" value="1"/><!-- 0->NED, 1->ENU --> - <remap from="~imu_in" to="sensors/imu"/> - <remap from="~imu_out" to="sensors/imu_enu"/> - - </node> - - <!-- combines odom+imu to generate odom_combined odometry --> - <node pkg="robot_localization" - type="ekf_localization_node" - name="local_ekf" - ns="$(arg name)" - clear_params="true" - output="screen"> - <rosparam command="load" file="$(arg local_ekf_config_file)" /> - <remap from="odometry/filtered" to="/$(arg name)/local_odom_combined"/> - </node> - - <node pkg="tf" - type="static_transform_publisher" - name="map_transform" args="0 0 0 0 0 0 map model_car/odom 20" - unless="$(arg global_loc)"/> + <arg name="global_ekf_config_file" default="$(find iri_model_car_rosnav)/params/global_ekf_odom_imu_amcl.yaml"/> <node pkg="robot_localization" type="ekf_localization_node" name="global_ekf" ns="$(arg name)" clear_params="true" - output="screen" - if="$(arg global_loc)"> + output="screen"> <rosparam command="load" file="$(arg global_ekf_config_file)" /> <remap from="odometry/filtered" to="/$(arg name)/global_odom_combined"/> </node> + </launch> diff --git a/launch/nav_map.launch b/launch/nav_map.launch index a23c6fe17ef1dfa6c3b0a21671e7544e39eb7ec1..32a9398978b03def0a9ec3853e4cc722a81e9283 100644 --- a/launch/nav_map.launch +++ b/launch/nav_map.launch @@ -14,8 +14,7 @@ <arg name="initial_x" default="0.0"/> <arg name="initial_y" default="0.0"/> <arg name="initial_yaw" default="0.0"/> - <arg name="local_ekf_config_file" default="$(find iri_model_car_rosnav)/params/local_ekf_odom_imu.yaml"/> - <arg name="global_ekf_config_file" default="$(find iri_model_car_rosnav)/params/global_ekf_odom_imu_amcl.yaml"/> + <arg name="global_ekf_config_file" default="$(find iri_model_car_rosnav)/params/global_ekf_odom_imu_amcl.yaml"/> <include file="$(find iri_rosnav)/launch/nav.launch"> <arg name="ns" value="$(arg name)"/> @@ -51,9 +50,7 @@ <include file="$(find iri_model_car_rosnav)/launch/include/localization.launch"> <arg name="name" value="$(arg name)"/> - <arg name="local_ekf_config_file" value="$(arg local_ekf_config_file)"/> <arg name="global_ekf_config_file" value="$(arg global_ekf_config_file)"/> - <arg name="global_loc" value="true"/> </include> <param name="/$(arg name)/move_base/SBPLLatticePlanner/primitive_filename" value="$(find iri_model_car_rosnav)/model_car.mprim" /> diff --git a/launch/nav_mapping.launch b/launch/nav_mapping.launch index b476138061d875541b0318bcd685fb530fb916a7..2f80a6d6fa161f3c6a279801ffcdcbd99d1c661f 100644 --- a/launch/nav_mapping.launch +++ b/launch/nav_mapping.launch @@ -11,7 +11,6 @@ <arg name="resolution" default="0.05"/> <arg name="output" default="screen" /> <arg name="launch_prefix" default="" /> - <arg name="local_ekf_config_file" default="$(find iri_model_car_rosnav)/params/local_ekf_odom_imu.yaml"/> <include file="$(find iri_rosnav)/launch/nav.launch"> <arg name="ns" value="$(arg name)"/> @@ -43,12 +42,6 @@ <arg name="launch_prefix" value="$(arg launch_prefix)" /> </include> - <include file="$(find iri_model_car_rosnav)/launch/include/localization.launch"> - <arg name="name" value="$(arg name)"/> - <arg name="local_ekf_config_file" value="$(arg local_ekf_config_file)"/> - <arg name="global_loc" value="false"/> - </include> - <param name="/$(arg name)/move_base/SBPLLatticePlanner/primitive_filename" value="$(find iri_model_car_rosnav)/model_car.mprim" /> </launch> diff --git a/launch/nav_nomap.launch b/launch/nav_nomap.launch index 8a880a54643bf87551f4f28a38e55d6c9d129144..41ab665e9af95ea91b594fc6f230483cca0cf559 100644 --- a/launch/nav_nomap.launch +++ b/launch/nav_nomap.launch @@ -9,7 +9,6 @@ <arg name="costmap_common_params" default="common_params.yaml"/> <arg name="costmap_local_params" default="local_params.yaml"/> <arg name="costmap_global_params" default="global_params.yaml"/> - <arg name="local_ekf_config_file" default="$(find iri_model_car_rosnav)/params/local_ekf_odom_imu.yaml"/> <include file="$(find iri_rosnav)/launch/nav.launch"> <arg name="ns" value="$(arg name)"/> @@ -38,11 +37,9 @@ <arg name="launch_prefix" value="$(arg launch_prefix)" /> </include> - <include file="$(find iri_model_car_rosnav)/launch/include/localization.launch"> - <arg name="name" value="$(arg name)"/> - <arg name="local_ekf_config_file" value="$(arg local_ekf_config_file)"/> - <arg name="global_loc" value="false"/> - </include> + <node pkg="tf" + type="static_transform_publisher" + name="map_transform" args="0 0 0 0 0 0 map $(arg name)/odom 20"/> <param name="/$(arg name)/move_base/SBPLLatticePlanner/primitive_filename" value="$(find iri_model_car_rosnav)/model_car.mprim" /> diff --git a/params/local_ekf_odom_imu.yaml b/params/local_ekf_odom_imu.yaml deleted file mode 100644 index 4821068942aa97ba957c0d6e9bbee398a943f04a..0000000000000000000000000000000000000000 --- a/params/local_ekf_odom_imu.yaml +++ /dev/null @@ -1,38 +0,0 @@ -frequency: 30 -sensor_timeout: 1.0 -transform_time_offset: 0.0 -two_d_mode: true -print_diagnostics: true -debug: false -debug_out_file: /tmp/debug_ekf_localization.txt -use_control: false - -publish_tf: true -map_frame: map -odom_frame: model_car/odom -base_link_frame: model_car/base_footprint -world_frame: model_car/odom - -odom0: /model_car/odom -odom0_config: [false, false, false, - false, false, false, - true, true, false, - false, false, true, - false, false, false] - -imu0: /model_car/sensors/imu_enu -imu0_config: [false, false, false, - false, false, true, - false, false, false, - false, false, true, - true, false, false] - -imu0_differential: false -imu0_relative: false -imu0_remove_gravitational_acceleration: true - -#meaning_config: [x, y, z, -# roll, pitch, yaw, -# vx, vy, vz, -# vroll, vpitch, vyaw, -# ax, ay, az] diff --git a/rviz/model_car_map_ekf.rviz b/rviz/model_car_map_ekf.rviz index f1336196a03b1d5701db0a57e1198b8a83b0754c..83e2e57798e5cf9d537d4221478c2354dcbd2956 100644 --- a/rviz/model_car_map_ekf.rviz +++ b/rviz/model_car_map_ekf.rviz @@ -8,6 +8,7 @@ Panels: - /Sensors1 - /Sensors1/GroundTruthOdometry1/Shape1 - /Sensors1/Odometry1/Shape1 + - /Sensors1/RP_Lidar1 - /global_planner1/global_plan1/Status1 Splitter Ratio: 0.625 Tree Height: 794 @@ -385,15 +386,15 @@ Visualization Manager: Axis: Z Channel Name: intensity Class: rviz/LaserScan - Color: 255; 255; 255 - Color Transformer: Intensity + Color: 255; 25; 0 + Color Transformer: FlatColor Decay Time: 0 Enabled: true Invert Rainbow: false - Max Color: 255; 255; 255 - Max Intensity: 0 + Max Color: 255; 25; 0 + Max Intensity: -999999 Min Color: 0; 0; 0 - Min Intensity: 0 + Min Intensity: 999999 Name: RP_Lidar Position Transformer: XYZ Queue Size: 10 @@ -551,16 +552,16 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 11.253925323486328 + Distance: 18.180187225341797 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 3.3934614658355713 - Y: 0.5182212591171265 - Z: 0.33107441663742065 + X: 3.496770143508911 + Y: 2.299980401992798 + Z: 0.33115777373313904 Focal Shape Fixed Size: false Focal Shape Size: 0.05000000074505806 Invert Z Axis: false