Skip to content

Commit

Permalink
Renaming wideangle rear camera
Browse files Browse the repository at this point in the history
  • Loading branch information
RobinSchmid7 committed Jan 24, 2024
1 parent de2ef9a commit 38df748
Show file tree
Hide file tree
Showing 5 changed files with 30 additions and 10 deletions.
12 changes: 9 additions & 3 deletions wild_visual_navigation_ros/launch/replay_launch.launch
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
<arg name="params_file" default="$(find wild_visual_navigation_ros)/config/wild_visual_navigation/default.yaml"/>
<arg name="rviz_config" default="anymal_dodo.rviz" />
<arg name="anymal_config" default="/home/rschmid/RosBags/uetliberg/dodo_params.yaml" />
<arg name="reload_default_params" value="False"/>

<arg name="anymal_converter" default="True"/>
<arg name="anymal_rsl_launch" default="True"/>
Expand All @@ -14,8 +15,10 @@
<arg name="uncompress_alphasense_cam3" default="False"/>
<arg name="uncompress_alphasense_cam4" default="False"/>
<arg name="uncompress_alphasense_cam5" default="False"/>
<arg name="uncompress_wide_angle_front" default="True"/>
<arg name="resize_images_wide_angle_front" default="True"/>
<arg name="uncompress_wide_angle_front" default="False"/>
<arg name="uncompress_wide_angle_rear" default="True"/>
<arg name="resize_images_wide_angle_front" default="False"/>
<arg name="resize_images_wide_angle_rear" default="True"/>


<!-- Set sim time to true -->
Expand Down Expand Up @@ -76,8 +79,11 @@
<node if="$(arg uncompress_alphasense_cam4)" name="uncompress_cam4" pkg="image_transport" type="republish" args="compressed in:=/alphasense_driver_ros/cam4/debayered raw out:=/alphasense_driver_ros/cam4/debayered" />
<node if="$(arg uncompress_alphasense_cam5)" name="uncompress_cam5" pkg="image_transport" type="republish" args="compressed in:=/alphasense_driver_ros/cam5/debayered raw out:=/alphasense_driver_ros/cam5/debayered" />

<node if="$(arg uncompress_wide_angle_front)" name="uncompress_wide_angle_front" pkg="image_transport" type="republish" args="compressed in:=/wide_angle_camera_rear/image_color_rect raw out:=/wide_angle_camera_rear/image_color" />
<node if="$(arg uncompress_wide_angle_front)" name="uncompress_wide_angle_front" pkg="image_transport" type="republish" args="compressed in:=/wide_angle_camera_front/image_color_rect raw out:=/wide_angle_camera_front/image_color" />
<include if="$(arg resize_images_wide_angle_front)" file="$(find wild_visual_navigation_ros)/launch/resize_images_wide_angle_front.launch"/>

<node if="$(arg uncompress_wide_angle_rear)" name="uncompress_wide_angle_rear" pkg="image_transport" type="republish" args="compressed in:=/wide_angle_camera_rear/image_color_rect raw out:=/wide_angle_camera_rear/image_color" />
<include if="$(arg resize_images_wide_angle_rear)" file="$(find wild_visual_navigation_ros)/launch/resize_images_wide_angle_rear.launch"/>


</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,10 @@
<!-- Launch the image_proc nodelet -->
<node pkg="nodelet" type="nodelet" name="standalone_nodelet_wide_angle_front" args="manager"/>
<node pkg="nodelet" type="nodelet" name="image_proc_nodelet_wide_angle_front" args="load image_proc/resize standalone_nodelet_wide_angle_front">
<remap from="camera_info" to="/wide_angle_camera_rear/camera_info" />
<remap from="~camera_info" to="/wide_angle_camera_rear_resize/camera_info" />
<remap from="image" to="/wide_angle_camera_rear/image_color" />
<remap from="~image" to="/wide_angle_camera_rear/image_color_resize" />
<remap from="camera_info" to="/wide_angle_camera_front/camera_info" />
<remap from="~camera_info" to="/wide_angle_camera_front_resize/camera_info" />
<remap from="image" to="/wide_angle_camera_front/image_color" />
<remap from="~image" to="/wide_angle_camera_front/image_color_resize" />
<param name="scale_width" value="0.2074077" />
<param name="scale_height" value="0.2074077" />
</node>
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
<launch>
<!-- Launch the image_proc nodelet -->
<node pkg="nodelet" type="nodelet" name="standalone_nodelet_wide_angle_rear" args="manager"/>
<node pkg="nodelet" type="nodelet" name="image_proc_nodelet_wide_angle_rear" args="load image_proc/resize standalone_nodelet_wide_angle_rear">
<remap from="camera_info" to="/wide_angle_camera_rear/camera_info" />
<remap from="~camera_info" to="/wide_angle_camera_rear_resize/camera_info" />
<remap from="image" to="/wide_angle_camera_rear/image_color" />
<remap from="~image" to="/wide_angle_camera_rear/image_color_resize" />
<param name="scale_width" value="0.2074077" />
<param name="scale_height" value="0.2074077" />
</node>
<node name="dynparam_width_wide_angle_rear" pkg="dynamic_reconfigure" type="dynparam" args="set /image_proc_nodelet_wide_angle_rear scale_width 0.2074077" />
<node name="dynparam_height_wide_angle_rear" pkg="dynamic_reconfigure" type="dynparam" args="set /image_proc_nodelet_wide_angle_rear scale_height 0.2074077" />
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -412,10 +412,10 @@ def load_model(self):
wvn_path = rospack.get_path("wild_visual_navigation_ros")
os.system(f"rosparam load {wvn_path}/config/wild_visual_navigation/default.yaml wvn_feature_extractor_node")
os.system(
f"rosparam load {wvn_path}/config/wild_visual_navigation/inputs/hdr_compressed.yaml wvn_feature_extractor_node"
f"rosparam load {wvn_path}/config/wild_visual_navigation/inputs/wide_angle_rear_compressed.yaml wvn_feature_extractor_node"
)
print(
f"rosparam load {wvn_path}/config/wild_visual_navigation/inputs/hdr_compressed.yaml wvn_feature_extractor_node"
f"rosparam load {wvn_path}/config/wild_visual_navigation/inputs/wide_angle_rear_compressed.yaml wvn_feature_extractor_node"
)
wvn = WvnFeatureExtractor()
rospy.spin()
2 changes: 1 addition & 1 deletion wild_visual_navigation_ros/scripts/wvn_learning_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -875,7 +875,7 @@ def visualize_image_overlay(self):
wvn_path = rospack.get_path("wild_visual_navigation_ros")
os.system(f"rosparam load {wvn_path}/config/wild_visual_navigation/default.yaml wvn_learning_node")
os.system(
f"rosparam load {wvn_path}/config/wild_visual_navigation/inputs/hdr_compressed.yaml wvn_learning_node"
f"rosparam load {wvn_path}/config/wild_visual_navigation/inputs/wide_angle_rear_compressed.yaml wvn_learning_node"
)

wvn = WvnLearning()
Expand Down

0 comments on commit 38df748

Please sign in to comment.