Commit 2905e7bc authored by Alejandro Lopez Gestoso's avatar Alejandro Lopez Gestoso
Browse files

updated to image_roi node

parent b3146c53
rate: 200.0
rate: 50.0
global_frame: "map"
odom_frame: "adc_car/odom"
base_link_frame: "adc_car/base_link"
......
rate: 200.0
rate: 50.0
global_frame: "map"
odom_frame: "adc_car/odom"
base_link_frame: "adc_car/base_link"
......
rate: 200.0
rate: 50.0
global_frame: "map"
odom_frame: "adc_car/odom"
base_link_frame: "adc_car/base_link"
......
rate: 200.0
rate: 50.0
global_frame: "map"
odom_frame: "adc_car/odom"
base_link_frame: "adc_car/base_link"
......
rate: 200.0
rate: 50.0
global_frame: "map"
odom_frame: "adc_car/odom"
base_link_frame: "adc_car/base_link"
......
......@@ -7,6 +7,11 @@
<!--Ar track alvar parameters-->
<arg name="marker_size" default="5.0"/>
<arg name="ar_max_freq" default="30.0"/>
<!-- Img ROI parameters -->
<arg name="front_roi_config_file" default="$(find iri_adc_launch)/config/adc_common/basler_roi_config.yaml"/>
<arg name="rear_roi_config_file" default="$(find iri_adc_launch)/config/adc_common/delock_roi_config.yaml"/>
<!-- Global localization parameters-->
<arg name="car_x" default="0.0"/>
......@@ -23,23 +28,52 @@
<arg name="features_topic_name" default="/$(arg car_name)/features"/>
<arg name="use_rear_camera_loc" default="false"/>
<!-- opendrive and map tf -->
<arg name="opendrive_x" default="0.0"/>
<arg name="opendrive_y" default="0.0"/>
<arg name="opendrive_yaw" default="0.0"/>
<node name="static_tf_map_to_opendrive" pkg="tf" type="static_transform_publisher"
args="$(arg opendrive_x) $(arg opendrive_y) 0 $(arg opendrive_yaw) 0 0 map opendrive 100">
</node>
<group ns="$(arg car_name)">
<!--Front ar track_alvar -->
<!-- Front image ROI -->
<include file="$(find iri_image_roi)/launch/node.launch">
<arg name="node_name" value="front_iri_image_roi"/>
<arg name="output" value="$(arg output)"/>
<arg name="launch_prefix" value="$(arg launch_prefix)"/>
<arg name="config_file" value="$(arg front_roi_config_file)"/>
<arg name="image_raw_in_topic" value="/$(arg car_name)/sensors/basler_camera/image_raw"/>
<arg name="camera_info_in_topic" value="/$(arg car_name)/sensors/basler_camera/camera_info"/>
<arg name="image_raw_out_topic" value="/$(arg car_name)/sensors/basler_camera_roi/image_raw"/>
<arg name="camera_info_out_topic" value="/$(arg car_name)/sensors/basler_camera_roi/camera_info"/>
</include>
<!-- Front image inverter -->
<include file="$(find iri_image_inverter)/launch/node.launch">
<arg name="node_name" value="front_iri_image_inverter"/>
<arg name="output" value="$(arg output)"/>
<arg name="launch_prefix" value="$(arg launch_prefix)"/>
<arg name="image_in_topic" value="/$(arg car_name)/sensors/basler_camera_roi/image_raw"/>
<arg name="image_out_topic" value="/$(arg car_name)/sensors/basler_camera_inverse/image_raw"/>
</include>
<!-- Front ar track_alvar -->
<node name="front_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_frequency" type="double" value="$(arg ar_max_freq)" />
<param name="max_new_marker_error" type="double" value="0.08" />
<param name="max_track_error" type="double" value="0.2" />
<param name="marker_margin" type="double" value="1.0" />
<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_cropped/inverted_image_raw" />
<remap from="/$(arg car_name)/camera_info" to="/$(arg car_name)/sensors/basler_camera_cropped/camera_info" />-->
<remap from="/$(arg car_name)/camera_image" to="/$(arg car_name)/sensors/basler_camera/inverted_image_raw" />
<remap from="/$(arg car_name)/camera_info" to="/$(arg car_name)/sensors/basler_camera/camera_info" />
<remap from="/$(arg car_name)/camera_image" to="/$(arg car_name)/sensors/basler_camera_inverse/image_raw" />
<remap from="/$(arg car_name)/camera_info" to="/$(arg car_name)/sensors/basler_camera_inverse/camera_info" />
<remap from="/$(arg car_name)/ar_pose_marker" to="/$(arg car_name)/front_ar_pose_marker" />
</node>
......@@ -54,49 +88,47 @@
<arg name="features_output_topic" value="$(arg features_topic_name)"/>
</include>
<!-- Front image inverter -->
<include file="$(find iri_image_inverter)/launch/node.launch">
<arg name="node_name" value="front_iri_image_inverter"/>
<arg name="output" value="$(arg output)"/>
<arg name="launch_prefix" value="$(arg launch_prefix)"/>
<!--<arg name="image_in_topic" value="/$(arg car_name)/sensors/basler_camera_cropped/image_raw"/>
<arg name="image_out_topic" value="/$(arg car_name)/sensors/basler_camera_cropped/inverted_image_raw"/>-->
<arg name="image_in_topic" value="/$(arg car_name)/sensors/basler_camera/image_raw"/>
<arg name="image_out_topic" value="/$(arg car_name)/sensors/basler_camera/inverted_image_raw"/>
</include>
<group if="$(arg use_rear_camera_loc)">
<!-- Rear image ROI -->
<include file="$(find iri_image_roi)/launch/node.launch">
<arg name="node_name" value="rear_iri_image_roi"/>
<arg name="output" value="$(arg output)"/>
<arg name="launch_prefix" value="$(arg launch_prefix)"/>
<arg name="config_file" value="$(arg rear_roi_config_file)"/>
<arg name="image_raw_in_topic" value="/$(arg car_name)/sensors/delock_camera/image_raw"/>
<arg name="camera_info_in_topic" value="/$(arg car_name)/sensors/delock_camera/camera_info"/>
<arg name="image_raw_out_topic" value="/$(arg car_name)/sensors/delock_camera_roi/image_raw"/>
<arg name="camera_info_out_topic" value="/$(arg car_name)/sensors/delock_camera_roi/camera_info"/>
</include>
<!--<node pkg="nodelet" type="nodelet" name="standalone_nodelet" args="manager"/>
<node name="crop_image"
pkg="nodelet"
type="nodelet"
args="load image_proc/crop_decimate standalone_nodelet">
<remap from="camera" to="/$(arg car_name)/sensors/basler_camera"/>
<remap from="camera_out" to="/$(arg car_name)/sensors/basler_camera_cropped"/>
<rosparam file="$(find iri_adc_launch)/config/adc_common/crop_front_image.yaml" command="load"/>
</node>-->
<!-- Rear image inverter -->
<include file="$(find iri_image_inverter)/launch/node.launch">
<arg name="node_name" value="rear_iri_image_inverter"/>
<arg name="output" value="$(arg output)"/>
<arg name="launch_prefix" value="$(arg launch_prefix)"/>
<arg name="image_in_topic" value="/$(arg car_name)/sensors/delock_camera_roi/image_raw"/>
<arg name="image_out_topic" value="/$(arg car_name)/sensors/delock_camera_inverse/image_raw"/>
</include>
<group if="$(arg use_rear_camera_loc)">
<!--rear ar track_alvar -->
<node name="rear_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="marker_size" type="double" value="$(arg marker_size)"/>
<param name="max_frequency" type="double" value="$(arg ar_max_freq)"/>
<param name="max_new_marker_error" type="double" value="0.08" />
<param name="max_track_error" type="double" value="0.2" />
<param name="marker_margin" type="double" value="1.0" />
<param name="output_frame" type="string" value="$(arg car_name)/rear_camera_uvc_camera_optical" />
<!--<remap from="/$(arg car_name)/camera_image" to="/$(arg car_name)/sensors/delock_camera_cropped/inverted_image_raw" />
<remap from="/$(arg car_name)/camera_info" to="/$(arg car_name)/sensors/delock_camera_cropped/camera_info" />-->
<remap from="/$(arg car_name)/camera_image" to="/$(arg car_name)/sensors/delock_camera/inverted_image_raw" />
<remap from="/$(arg car_name)/camera_info" to="/$(arg car_name)/sensors/delock_camera/camera_info" />
<remap from="/$(arg car_name)/camera_image" to="/$(arg car_name)/sensors/delock_camera_inverse/image_raw" />
<remap from="/$(arg car_name)/camera_info" to="/$(arg car_name)/sensors/delock_camera_inverse/camera_info" />
<remap from="/$(arg car_name)/ar_pose_marker" to="/$(arg car_name)/rear_ar_pose_marker" />
</node>
<!-- Front ar tag filter -->
<!-- Rear ar tag filter -->
<include file="$(find iri_adc_tag_localization_filter)/launch/node.launch">
<arg name="node_name" value="rear_iri_adc_tag_localization_filter"/>
<arg name="output" value="$(arg output)"/>
......@@ -106,17 +138,6 @@
<arg name="ar_input_topic" value="/$(arg car_name)/rear_ar_pose_marker"/>
<arg name="features_output_topic" value="$(arg features_topic_name)"/>
</include>
<!-- Front image inverter -->
<include file="$(find iri_image_inverter)/launch/node.launch">
<arg name="node_name" value="rear_iri_image_inverter"/>
<arg name="output" value="$(arg output)"/>
<arg name="launch_prefix" value="$(arg launch_prefix)"/>
<!--<arg name="image_in_topic" value="/$(arg car_name)/sensors/delock_camera_cropped/image_raw"/>
<arg name="image_out_topic" value="/$(arg car_name)/sensors/delock_camera_cropped/inverted_image_raw"/>-->
<arg name="image_in_topic" value="/$(arg car_name)/sensors/delock_camera/image_raw"/>
<arg name="image_out_topic" value="/$(arg car_name)/sensors/delock_camera/inverted_image_raw"/>
</include>
</group>
<include file="$(find iri_adc_landmarks_slam_solver)/launch/node.launch">
......@@ -132,7 +153,6 @@
<arg name="initial_pose_y" value="$(arg car_y)"/>
<arg name="initial_pose_yaw" value="$(arg car_yaw)"/>
</include>
</group>
<include file="$(find iri_rosnav)/launch/include/map_server.launch">
......@@ -174,3 +194,4 @@
args="iri_adc_tag_localization_filter">
</node>
</launch>
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment