diff --git a/config/adc_sim/basler_camera_sim_config.yaml b/config/adc_sim/basler_camera_sim_config.yaml index 56ffb8c5c196afd1dc6c3ebf3182d12d0a6331af..2fbe6d5fc1db8b3a404dd50f94abcf1cac8cb416 100644 --- a/config/adc_sim/basler_camera_sim_config.yaml +++ b/config/adc_sim/basler_camera_sim_config.yaml @@ -1,6 +1,6 @@ horizontal_fov: 2.25 -width: 640 -height: 480 +width: 1280 +height: 960 format: 'R8G8B8' clip_near: 0.1 clip_far: 100 diff --git a/launch/adc_global_localization.launch b/launch/adc_global_localization.launch index 56f450ee98ce142c95a912618f0c59c80d506138..1c20312161c5aedbce939532cff410eb7cedcd36 100644 --- a/launch/adc_global_localization.launch +++ b/launch/adc_global_localization.launch @@ -18,28 +18,30 @@ <arg name="amcl_config" default="$(find iri_adc_launch)/config/adc_rosnav/amcl_no_tf.yaml"/> <!-- Ar track alvar (bringup??) --> - <node name="ar_track_alvar" - pkg="ar_track_alvar" - type="individualMarkersNoKinect" - respawn="false" - output="screen"> - <param name="marker_size" type="double" value="$(arg marker_size)" /> - <param name="max_new_marker_error" type="double" value="0.08" /> - <param name="max_track_error" type="double" value="0.2" /> - <param name="output_frame" type="string" value="$(arg car_name)/front_camera_uvc_camera_optical" /> - <remap from="/camera_image" to="$(arg car_name)/sensors/basler_camera/image_raw" /> - <remap from="/camera_info" to="$(arg car_name)/sensors/basler_camera/camera_info" /> - <remap from="/ar_pose_marker" to="/$(arg car_name)/ar_pose_marker" /> - </node> + <group ns="$(arg car_name)"> + <node name="ar_track_alvar" + pkg="ar_track_alvar" + type="individualMarkersNoKinect" + respawn="false" + output="screen"> + <param name="marker_size" type="double" value="$(arg marker_size)" /> + <param name="max_new_marker_error" type="double" value="0.08" /> + <param name="max_track_error" type="double" value="0.2" /> + <param name="output_frame" type="string" value="$(arg car_name)/front_camera_uvc_camera_optical" /> + <remap from="/$(arg car_name)/camera_image" to="/$(arg car_name)/sensors/basler_camera/image_raw" /> + <remap from="/$(arg car_name)/camera_info" to="/$(arg car_name)/sensors/basler_camera/camera_info" /> + <remap from="/$(arg car_name)/ar_pose_marker" to="/$(arg car_name)/ar_pose_marker" /> + </node> - <include file="$(find iri_adc_tag_localization_filter)/launch/node.launch"> - <arg name="node_name" value="iri_adc_tag_localization_filter"/> - <arg name="output" value="$(arg output)"/> - <arg name="launch_prefix" value="$(arg launch_prefix)"/> - <arg name="config_file" value="$(find iri_adc_tag_localization_filter)/config/params.yaml"/> - <arg name="robot_name" value="$(arg car_name)"/> - <arg name="ar_input_topic" value="/$(arg car_name)/ar_pose_marker"/> - </include> + <include file="$(find iri_adc_tag_localization_filter)/launch/node.launch"> + <arg name="node_name" value="iri_adc_tag_localization_filter"/> + <arg name="output" value="$(arg output)"/> + <arg name="launch_prefix" value="$(arg launch_prefix)"/> + <arg name="config_file" value="$(find iri_adc_tag_localization_filter)/config/params.yaml"/> + <arg name="robot_name" value="$(arg car_name)"/> + <arg name="ar_input_topic" value="/$(arg car_name)/ar_pose_marker"/> + </include> + </group> <include file="$(find iri_rosnav)/launch/include/map_server.launch"> <arg name="ns" value="$(arg car_name)"/> diff --git a/rviz/localization_global.rviz b/rviz/localization_global.rviz index 3f0ab03a54d4062df960bf0c87ce0d011684eda6..04c3442739a5c5231dff6c0cd4197c3fb8f6c73c 100644 --- a/rviz/localization_global.rviz +++ b/rviz/localization_global.rviz @@ -739,23 +739,23 @@ Visualization Manager: Displays: - Class: rviz/Marker Enabled: true - Marker Topic: /visualization_marker + Marker Topic: /adc_car/visualization_marker Name: Alvar_marker Namespaces: - basic_shapes: true + {} Queue Size: 100 Value: true - Class: rviz/MarkerArray Enabled: true - Marker Topic: /iri_adc_tag_localization_filter/vis_features + Marker Topic: /adc_car/iri_adc_tag_localization_filter/vis_features Name: Features Namespaces: - adc_car/front_camera_uvc_camera_optical_features: true + {} Queue Size: 100 Value: true - Class: rviz/MarkerArray Enabled: true - Marker Topic: /iri_adc_landmarks_slam_solver/landmarks + Marker Topic: /adc_car/iri_adc_landmarks_slam_solver/landmarks Name: Landmarks Namespaces: {}