Skip to content

Commit

Permalink
Added real world tmux files and turn on the merging with standard points
Browse files Browse the repository at this point in the history
Your Name committed Apr 12, 2024
1 parent 13319f4 commit 511b19a
Showing 4 changed files with 731 additions and 3 deletions.
6 changes: 3 additions & 3 deletions include/detect/uv_led_detect_adaptive.cpp
Original file line number Diff line number Diff line change
@@ -96,7 +96,7 @@ const std::vector<cv::Point>& standardPoints) {
}
}

//std::vector<cv::Point> final_detected_points = mergePoints(detectedPoints, standardPoints, point_similarity_threshold_);
std::vector<cv::Point> final_detected_points = mergePoints(detectedPoints, standardPoints, point_similarity_threshold_);


/*
@@ -107,7 +107,7 @@ const std::vector<cv::Point>& standardPoints) {
}
*/
//detectedPoints = final_detected_points;
detectedPoints = final_detected_points;
//standardPoints = final_detected_points;

//Fail if no points are detected TODO
@@ -673,7 +673,7 @@ void UVDARLedDetectAdaptive::generateVisualizationAdaptive(const cv::Mat& inputI
*/

// Create a copy of the current image for visualization
//Set the a black background with the same size as the input image
//3the a black background with the same size as the input image

visualization_image = inputImage.clone();

368 changes: 368 additions & 0 deletions launch/rw_three_sided_marlon.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,368 @@
<launch>
<arg name="uav_name" default="$(optenv UAV_NAME uav2)"/>

<arg name="standalone" default="false"/>

<arg unless="$(arg standalone)" name="nodelet" value="load"/>
<arg if="$(arg standalone)" name="nodelet" value="standalone"/>
<arg unless="$(arg standalone)" name="nodelet_manager" value="$(arg uav_name)_uvdar_nodelet_manager"/>
<arg if="$(arg standalone)" name="nodelet_manager" value=""/>

<arg name="threshold" default="50"/>

<arg name="left" default="$(optenv BLUEFOX_UV_LEFT)"/>
<arg name="right" default="$(optenv BLUEFOX_UV_RIGHT)"/>
<arg name="back" default="$(optenv BLUEFOX_UV_BACK)"/>
<arg name="left_camera_name" default="mv_$(arg left)"/>
<arg name="right_camera_name" default="mv_$(arg right)"/>
<arg name="back_camera_name" default="mv_$(arg back)"/>
<arg name="expose_us_left" default="$(optenv BLUEFOX_UV_LEFT_EXPOSE_US)"/>
<arg name="expose_us_right" default="$(optenv BLUEFOX_UV_RIGHT_EXPOSE_US)"/>
<arg name="expose_us_back" default="$(optenv BLUEFOX_UV_BACK_EXPOSE_US)"/>

<arg name="calibrations_folder" default="$(find mrs_uav_deployment)/config/uvdar_calibrations"/>

<arg name="camera_rate" default="60"/>
<arg name="fps" default="$(arg camera_rate)"/>
<arg name="idpf" default="0"/>
<arg name="aec" default="false"/>
<arg name="agc" default="false"/>
<arg name="gain_db" default="0.0"/>
<arg name="cbm" default="0"/>
<arg name="ctm" default="1"/>
<arg name="dcfm" default="0"/>
<arg name="hdr" default="false"/>
<arg name="wbp" default="-1"/>
<arg name="request" default="0"/>
<arg name="mm" default="0"/>
<arg name="jpeg_quality" default="90"/>

<arg name="blink_process_rate" default="10"/>

<arg name="accumulator_length" default="14"/>
<arg name="pitch_steps" default="16"/>
<arg name="yaw_steps" default="16"/>
<arg name="max_pixel_shift" default="4"/>

<arg name="filterDistLength" default="10"/>
<arg name="filterOrientationLength" default="10"/>

<!-- Node Settings -->
<arg name="output" default="screen"/>
<arg name="proc" default="false"/>
<arg name="view" default="false"/>
<arg name="calib" default="false"/>

<arg name="debug" default="false"/>
<arg name="visual_debug" default="false"/>
<!-- <arg name="gui" default="true"/> -->
<arg name="gui" default="false"/>
<arg name="publish_visualization" default="true"/>
<arg name="visualization_rate" default="2"/>

<arg name="publish" default="true"/>
<arg name="useOdom" default="false"/>
<arg name="cemeraRotated" default="false"/>
<arg name="FromVideo" default="false"/>
<arg name="VideoNumber" default="9"/>
<arg name="cellSize" default="64"/>
<arg name="cellOverlay" default="16"/>
<arg name="camNum" default="0"/>
<arg name="Delay" default="100"/>
<arg name="TimeScale" default="1.0"/>

<arg name="mrs_id" default="$(optenv MRS_ID)"/>

<arg name="beacon" default="false"/>

<arg name="output_frame" default="local_origin"/>

<arg name="id1" value="0"/>
<arg name="id2" value="1"/>
<arg name="id3" value="2"/>
<arg name="id4" value="3"/>
<arg name="id5" value="4"/>
<arg name="id6" value="5"/>
<arg name="id7" value="6"/>
<arg name="id8" value="7"/>
<arg name="id9" value="8"/>
<arg name="id10" value="9"/>
<arg name="id11" value="10"/>
<arg name="id12" value="11"/>
<arg name="id13" value="12"/>
<arg name="id14" value="13"/>
<arg name="id15" value="14"/>
<arg name="id16" value="15"/>
<arg name="id17" value="16"/>
<arg name="id18" value="17"/>
<arg name="id19" value="18"/>
<arg name="id20" value="19"/>
<arg name="id21" value="20"/>

<arg name="sequence_file" default="$(find uvdar_core)/config/selected.txt"/>
<arg name="model_file" default="$(find uvdar_core)/config/models/quadrotor_foursided_px4_motor_aligned.txt"/>

<arg name="use_masks" default="true"/>

<arg name="blink_throttle_rate" default="10"/>

<node
name="uvcam_left_tf_$(arg uav_name)"
pkg="tf2_ros"
type="static_transform_publisher"
args="0.03 0.10 0.06 -0.3490658504 0.0 -1.57079632679 $(arg uav_name)/fcu $(arg uav_name)/uvcam_left"/>

<node
name="uvcam_right_tf_$(arg uav_name)"
pkg="tf2_ros"
type="static_transform_publisher"
args="0.03 -0.10 0.06 -2.792526803 0.0 -1.57079632679 $(arg uav_name)/fcu $(arg uav_name)/uvcam_right"/>

<node
name="uvcam_back_tf_$(arg uav_name)"
pkg="tf2_ros"
type="static_transform_publisher"
args="-0.10 0.0 -0.02 0.0 1.57079632679 3.14159265 $(arg uav_name)/fcu $(arg uav_name)/uvcam_back"/>
<!-- ideal angle: 1.221730476 - pi/2 -->

<!-- <origin xyz="0.108 0 0.085" rpy="1.57079632679 4.71238898038 1.57079632679" /> -->
<!--Usage: static_transform_publisher x y z yaw pitch roll frame_id child_frame_id period(milliseconds)-->
<!-- OR -->
<group ns="$(arg uav_name)">

<!-- <node pkg="nodelet" type="nodelet" name="$(arg uav_name)_uvdar_nodelet_manager" args="manager" output="screen" launch-prefix="debug_roslaunch"> -->
<node pkg="nodelet" type="nodelet" name="$(arg uav_name)_uvdar_nodelet_manager" args="manager" output="screen">
<param name="num_worker_threads" value="8" />
</node>


<node pkg="nodelet" type="nodelet" name="uvdar_bluefox_left" args="$(arg nodelet) bluefox2/SingleNodelet $(arg nodelet_manager)" respawn="true" output="screen" launch-prefix="bash -c 'sleep 5; $0 $@'">
<param name="camera_name" type="string" value="$(arg left_camera_name)"/>
<param name="identifier" type="string" value="$(arg left)"/>

<param name="frame_id" type="string" value="uvcam_left_tf_$(arg uav_name)"/>
<param name="fps" type="double" value="$(arg fps)"/>
<param name="idpf" type="int" value="$(arg idpf)"/>
<param name="aec" type="bool" value="$(arg aec)"/>
<param name="expose_us" type="int" value="$(arg expose_us_left)"/>
<param name="agc" type="bool" value="$(arg agc)"/>
<param name="gain_db" type="double" value="$(arg gain_db)"/>
<param name="cbm" type="int" value="$(arg cbm)"/>
<param name="ctm" type="int" value="$(arg ctm)"/>
<param name="dcfm" type="int" value="$(arg dcfm)"/>
<param name="hdr" type="bool" value="$(arg hdr)"/>
<param name="wbp" type="int" value="$(arg wbp)"/>
<param name="request" type="int" value="$(arg request)"/>
<param name="mm" type="int" value="$(arg mm)"/>

<param name="image_raw/compressed/jpeg_quality" type="int" value="$(arg jpeg_quality)"/>
<param name="image_raw/theora/keyframe_frequency" value="60" />
<param name="image_raw/theora/target_bitrate" value="50000" />
<param name="image_raw/theora/quality" value="8" />
<param name="image_raw/theora/optimize_for" value="0" />

<remap from="/$(arg uav_name)/uvdar_bluefox_left/image_raw" to="/$(arg uav_name)/uvdar_bluefox/left/image_raw"/>
</node>

<node pkg="nodelet" type="nodelet" name="uvdar_bluefox_right" args="$(arg nodelet) bluefox2/SingleNodelet $(arg nodelet_manager)" respawn="true" output="screen" launch-prefix="bash -c 'sleep 7; $0 $@'">
<param name="camera_name" type="string" value="$(arg right_camera_name)"/>
<param name="identifier" type="string" value="$(arg right)"/>

<param name="frame_id" type="string" value="uvcam_right_tf_$(arg uav_name)"/>
<param name="fps" type="double" value="$(arg fps)"/>
<param name="idpf" type="int" value="$(arg idpf)"/>
<param name="aec" type="bool" value="$(arg aec)"/>
<param name="expose_us" type="int" value="$(arg expose_us_right)"/>
<param name="agc" type="bool" value="$(arg agc)"/>
<param name="gain_db" type="double" value="$(arg gain_db)"/>
<param name="cbm" type="int" value="$(arg cbm)"/>
<param name="ctm" type="int" value="$(arg ctm)"/>
<param name="dcfm" type="int" value="$(arg dcfm)"/>
<param name="hdr" type="bool" value="$(arg hdr)"/>
<param name="wbp" type="int" value="$(arg wbp)"/>
<param name="request" type="int" value="$(arg request)"/>
<param name="mm" type="int" value="$(arg mm)"/>

<param name="image_raw/compressed/jpeg_quality" type="int" value="$(arg jpeg_quality)"/>
<param name="image_raw/theora/keyframe_frequency" value="60" />
<param name="image_raw/theora/target_bitrate" value="50000" />
<param name="image_raw/theora/quality" value="8" />
<param name="image_raw/theora/optimize_for" value="0" />

<remap from="/$(arg uav_name)/uvdar_bluefox_right/image_raw" to="/$(arg uav_name)/uvdar_bluefox/right/image_raw"/>
</node>

<node pkg="nodelet" type="nodelet" name="uvdar_bluefox_back" args="$(arg nodelet) bluefox2/SingleNodelet $(arg nodelet_manager)" respawn="true" output="screen" launch-prefix="bash -c 'sleep 7; $0 $@'">
<param name="camera_name" type="string" value="$(arg back_camera_name)"/>
<param name="identifier" type="string" value="$(arg back)"/>

<param name="frame_id" type="string" value="uvcam_back_tf_$(arg uav_name)"/>
<param name="fps" type="double" value="$(arg fps)"/>
<param name="idpf" type="int" value="$(arg idpf)"/>
<param name="aec" type="bool" value="$(arg aec)"/>
<param name="expose_us" type="int" value="$(arg expose_us_back)"/>
<param name="agc" type="bool" value="$(arg agc)"/>
<param name="gain_db" type="double" value="$(arg gain_db)"/>
<param name="cbm" type="int" value="$(arg cbm)"/>
<param name="ctm" type="int" value="$(arg ctm)"/>
<param name="dcfm" type="int" value="$(arg dcfm)"/>
<param name="hdr" type="bool" value="$(arg hdr)"/>
<param name="wbp" type="int" value="$(arg wbp)"/>
<param name="request" type="int" value="$(arg request)"/>
<param name="mm" type="int" value="$(arg mm)"/>

<param name="image_raw/compressed/jpeg_quality" type="int" value="$(arg jpeg_quality)"/>
<param name="image_raw/theora/keyframe_frequency" value="60" />
<param name="image_raw/theora/target_bitrate" value="50000" />
<param name="image_raw/theora/quality" value="8" />
<param name="image_raw/theora/optimize_for" value="0" />

<remap from="/$(arg uav_name)/uvdar_bluefox_back/image_raw" to="/$(arg uav_name)/uvdar_bluefox/back/image_raw"/>
</node>


<node name="uv_detect" pkg="nodelet" type="nodelet" args="$(arg nodelet) uvdar/UVDARDetector $(arg nodelet_manager)" output="screen" respawn="true">
<!-- <node name="uv_detect" pkg="nodelet" type="nodelet" args="$(arg nodelet) uvdar/UVDARDetector $(arg nodelet_manager)" output="screen" respawn="true" launch-prefix="debug_roslaunch"> -->
<!-- <node name="uv_detect" pkg="uvdar" type="uv_detector_node" output="screen" launch-prefix="urxvt -e gdb -q -x /home/viktor/gdb.cmds -/-args"> -->
<param name="uav_name" type = "string" value="$(arg uav_name)"/>
<param name="debug" type="bool" value="$(arg debug)"/>
<!-- <param name="debug" type="bool" value="true"/> -->
<param name="gui" type="bool" value="false"/>
<param name="publish_visualization" type="bool" value="false"/>
<param name="justReport" type="bool" value="true"/>
<param name="threshold" type="int" value="$(arg threshold)"/>
<!-- Params for Marlon's Adaptive Binarization-->
<param name="adaptive_threshold" type="bool" value="true"/>
<param name="adaptive_method" type="string" value="Otsu"/>
<!-- ////////////////////////////////////////// -->

<param name="use_masks" type="bool" value="$(arg use_masks)"/>
<param name="body_name" type = "string" value="$(arg mrs_id)"/>
<rosparam param="mask_file_names" subst_value="True"> ["$(arg calibrations_folder)/masks/$(arg mrs_id)_$(arg left).png", "$(arg calibrations_folder)/masks/$(arg mrs_id)_$(arg right).png", "$(arg calibrations_folder)/masks/default_back.png"] </rosparam>

<rosparam param="camera_topics"> ["camera_left", "camera_right", "camera_back"] </rosparam>
<rosparam param="points_seen_topics"> ["points_seen_left", "points_seen_right", "points_seen_back"] </rosparam>
<!-- Params for Marlon's Adaptive Binarization-->
<rosparam param="blinkers_seen_topics"> ["blinkers_seen_left", "blinkers_seen_right", "blinkers_seen_back"] </rosparam>
<rosparam param="adaptive_logging_topics"> ["adaptive_logging_left", "adaptive_logging_right", "adaptive_logging_back"] </rosparam>
<!-- ////////////////////////////////////////// -->

<remap from="~camera_left" to="/$(arg uav_name)/uvdar_bluefox/left/image_raw"/>
<remap from="~camera_right" to="/$(arg uav_name)/uvdar_bluefox/right/image_raw"/>
<remap from="~camera_back" to="/$(arg uav_name)/uvdar_bluefox/back/image_raw"/>
<remap from="~points_seen_left" to="/$(arg uav_name)/uvdar/points_seen_left"/>
<remap from="~points_seen_right" to="/$(arg uav_name)/uvdar/points_seen_right"/>
<remap from="~points_seen_back" to="/$(arg uav_name)/uvdar/points_seen_back"/>

<!-- Params for Marlon's Adaptive Binarization-->
<remap from="~blinkers_seen_left" to="/$(arg uav_name)/uvdar/blinkers_seen_left"/>
<remap from="~blinkers_seen_right" to="/$(arg uav_name)/uvdar/blinkers_seen_right"/>
<remap from="~blinkers_seen_back" to="/$(arg uav_name)/uvdar/blinkers_seen_back"/>
<remap from="~adaptive_logging_left" to="/$(arg uav_name)/uvdar/adaptive_logging_left"/>
<remap from="~adaptive_logging_right" to="/$(arg uav_name)/uvdar/adaptive_logging_right"/>
<remap from="~adaptive_logging_back" to="/$(arg uav_name)/uvdar/adaptive_logging_back"/>
<!-- ////////////////////////////////////////// -->

<remap from="~odometry" to="/$(arg uav_name)/mrs_odometry/new_odom"/>
<remap from="~imu" to="mavros/imu/data"/>
</node>

<node name="blink_processor" pkg="nodelet" type="nodelet" args="$(arg nodelet) uvdar/UVDARBlinkProcessor $(arg nodelet_manager)" output="screen" respawn="true">
<!-- <node name="blink_processor" pkg="nodelet" type="nodelet" args="$(arg nodelet) uvdar/UVDARBlinkProcessor $(arg nodelet_manager)" output="screen" respawn="true" launch-prefix="roslaunch_debug"> -->
<param name="uav_name" type = "string" value="$(arg uav_name)"/>
<!-- <param name="debug" type="bool" value="$(arg debug)"/> -->
<param name="debug" type="bool" value="false"/>
<param name="visual_debug" type="bool" value="$(arg visual_debug)"/>
<param name="gui" type="bool" value="$(arg gui)"/>
<param name="publish_visualization" type="bool" value="$(arg publish_visualization)"/>
<param name="use_camera_for_visualization" type="bool" value="true"/>
<param name="visualization_rate" type="int" value="$(arg visualization_rate)"/>
<!-- <rosparam param="frequencies" subst_value="true"> [$(arg frequency1), $(arg frequency2), $(arg frequency3), $(arg frequency4)] </rosparam> -->
<rosparam param="signal_ids" subst_value="true"> [$(arg id1), $(arg id2), $(arg id3), $(arg id4), $(arg id5), $(arg id6), $(arg id7), $(arg id8), $(arg id9), $(arg id10), $(arg id11), $(arg id12), $(arg id13), $(arg id14), $(arg id15), $(arg id16), $(arg id17), $(arg id18), $(arg id19), $(arg id20), $(arg id21)] </rosparam>
<param name="sequence_file" type="string" value="$(arg sequence_file)"/>

<param name="blink_process_rate" type="int" value="$(arg blink_process_rate)"/>

<param name="accumulator_length" type="int" value="$(arg accumulator_length)"/>
<param name="pitch_steps" type="int" value="$(arg pitch_steps)"/>
<param name="yaw_steps" type="int" value="$(arg yaw_steps)"/>
<param name="max_pixel_shift" type="int" value="$(arg max_pixel_shift)"/>
<param name="nullify_radius" type="int" value="5"/>

<rosparam param="camera_topics"> ["camera_left", "camera_right", "camera_back"] </rosparam>
<rosparam param="points_seen_topics"> ["points_seen_left", "points_seen_right", "points_seen_back"] </rosparam>
<rosparam param="blinkers_seen_topics"> ["blinkers_seen_left", "blinkers_seen_right", "blinkers_seen_back"] </rosparam>
<rosparam param="estimated_framerate_topics"> ["estimated_framerate_left", "estimated_framerate_right", "estimated_framerate_back"] </rosparam>

<rosparam param="omta_logging_topics"> ["omta_logging_left", "omta_logging_right", "omta_logging_back"] </rosparam>
<rosparam param="omta_all_seq_info_topics"> ["omta_all_seq_info_left", "omta_all_seq_info_right", "omta_all_seq_info_back"] </rosparam>

<remap from="~camera_left" to="/$(arg uav_name)/uvdar_bluefox/left/image_raw"/>
<remap from="~camera_right" to="/$(arg uav_name)/uvdar_bluefox/right/image_raw"/>
<remap from="~camera_back" to="/$(arg uav_name)/uvdar_bluefox/back/image_raw"/>
<remap from="~points_seen_left" to="/$(arg uav_name)/uvdar/points_seen_left"/>
<remap from="~points_seen_right" to="/$(arg uav_name)/uvdar/points_seen_right"/>
<remap from="~points_seen_back" to="/$(arg uav_name)/uvdar/points_seen_back"/>
<remap from="~blinkers_seen_left" to="/$(arg uav_name)/uvdar/blinkers_seen_left"/>
<remap from="~blinkers_seen_right" to="/$(arg uav_name)/uvdar/blinkers_seen_right"/>
<remap from="~blinkers_seen_back" to="/$(arg uav_name)/uvdar/blinkers_seen_back"/>
<remap from="~estimated_framerate_left" to="/$(arg uav_name)/uvdar/estimated_framerate_left"/>
<remap from="~estimated_framerate_right" to="/$(arg uav_name)/uvdar/estimated_framerate_right"/>
<remap from="~estimated_framerate_back" to="/$(arg uav_name)/uvdar/estimated_framerate_back"/>
<!-- <remap from="~visualization" to="/$(arg uav_name)/uvdar/blink_visualization/image_raw"/> -->

<remap from="~omta_logging_left" to="/$(arg uav_name)/uvdar/omta_logging_left"/>
<remap from="~omta_logging_right" to="/$(arg uav_name)/uvdar/omta_logging_right"/>
<remap from="~omta_logging_back" to="/$(arg uav_name)/uvdar/omta_logging_back"/>

<remap from="~omta_all_seq_info_left" to="/$(arg uav_name)/uvdar/omta_all_seq_info_left"/>
<remap from="~omta_all_seq_info_right" to="/$(arg uav_name)/uvdar/omta_all_seq_info_right"/>
<remap from="~omta_all_seq_info_back" to="/$(arg uav_name)/uvdar/omta_all_seq_info_back"/>
</node>

<node name="throttle_blinkers_left" type="throttle" pkg="topic_tools"
args="messages /$(arg uav_name)/uvdar/blinkers_seen_left $(arg blink_throttle_rate) /$(arg uav_name)/uvdar/blinkers_seen_left/throttled" />
<node name="throttle_blinkers_right" type="throttle" pkg="topic_tools"
args="messages /$(arg uav_name)/uvdar/blinkers_seen_right $(arg blink_throttle_rate) /$(arg uav_name)/uvdar/blinkers_seen_right/throttled" />
<node name="throttle_blinkers_back" type="throttle" pkg="topic_tools"
args="messages /$(arg uav_name)/uvdar/blinkers_seen_back $(arg blink_throttle_rate) /$(arg uav_name)/uvdar/blinkers_seen_back/throttled" />

<node name="uvdar_pose_calculator_node" pkg="uvdar_core" type="uvdar_pose_calculator_node" output="screen" >
<!-- <node name="uvdar_pose_calculator_node" pkg="uvdar_core" type="uvdar_pose_calculator_node" launch-prefix="valgrind -/-tool=callgrind -/-callgrind-out-file=/home/viktor/callgrind.out -/-instr-atstart=no -/-collect-atstart=yes"> -->
<!-- <node name="uvdar_pose_calculator_node" pkg="uvdar_core" type="uvdar_pose_calculator_node" launch-prefix="valgrind -/-tool=callgrind -/-callgrind-out-file=/home/viktor/callgrind.out"> -->
<param name="uav_name" type = "string" value="$(arg uav_name)"/>
<param name="debug" type="bool" value="false"/>
<!-- <param name="debug" type="bool" value="false"/> -->
<!-- <param name="gui" type="bool" value="false"/> -->
<param name="gui" type="bool" value="false"/>
<param name="publish_visualization" type="bool" value="false"/>
<param name="publish_constituents" type="bool" value="true"/>
<!-- <param name="publish_visualization" type="bool" value="false"/> -->
<rosparam param="signal_ids" subst_value="true"> [$(arg id1), $(arg id2), $(arg id3), $(arg id4), $(arg id5), $(arg id6), $(arg id7), $(arg id8), $(arg id9), $(arg id10), $(arg id11), $(arg id12), $(arg id13), $(arg id14), $(arg id15), $(arg id16), $(arg id17), $(arg id18), $(arg id19), $(arg id20), $(arg id21)] </rosparam>

<param name="quadrotor" type="bool" value="true"/>
<param name="custom_model" type="bool" value="true"/>
<param name="model_file" type="string" value="$(arg model_file)"/>
<param name="beacon" type="bool" value="false"/>

<rosparam param="blinkers_seen_topics"> ["blinkers_seen_left", "blinkers_seen_right", "blinkers_seen_back"] </rosparam>
<rosparam param="estimated_framerate_topics"> ["estimated_framerate_left", "estimated_framerate_right", "estimated_framerate_back"] </rosparam>
<rosparam param="camera_frames" subst_value="true"> ["$(arg uav_name)/uvcam_left", "$(arg uav_name)/uvcam_right", "$(arg uav_name)/uvcam_back"] </rosparam>

<remap from="~blinkers_seen_left" to="/$(arg uav_name)/uvdar/blinkers_seen_left/throttled"/>
<remap from="~blinkers_seen_right" to="/$(arg uav_name)/uvdar/blinkers_seen_right/throttled"/>
<remap from="~blinkers_seen_back" to="/$(arg uav_name)/uvdar/blinkers_seen_back/throttled"/>
<remap from="~estimated_framerate_left" to="/$(arg uav_name)/uvdar/estimated_framerate_left"/>
<remap from="~estimated_framerate_right" to="/$(arg uav_name)/uvdar/estimated_framerate_right"/>
<remap from="~estimated_framerate_back" to="/$(arg uav_name)/uvdar/estimated_framerate_back"/>

<rosparam param="calib_files" subst_value="true"> ["$(arg calibrations_folder)/camera_calibrations/calib_results_bf_uv_$(arg left).txt", "$(arg calibrations_folder)/camera_calibrations/calib_results_bf_uv_$(arg right).txt", "$(arg calibrations_folder)/camera_calibrations/calib_results_bf_uv_$(arg back).txt"] </rosparam>

<remap from="~constituentHypotheses" to="/$(arg uav_name)/uvdar/constituentHypotheses"/>
<remap from="~measuredPoses" to="/$(arg uav_name)/uvdar/measuredPoses"/>

<param name="output_frame" type="string" value="$(arg output_frame)"/>
</node>
</group>

</launch>
181 changes: 181 additions & 0 deletions scripts/rx.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,181 @@
#!/bin/bash
### BEGIN INIT INFO
# Provides: tmux
# Required-Start: $local_fs $network dbus
# Required-Stop: $local_fs $network
# Default-Start: 2 3 4 5
# Default-Stop: 0 1 6
# Short-Description: start the uav
### END INIT INFO
if [ "$(id -u)" == "0" ]; then
exec sudo -u mrs "$0" "$@"
fi

source $HOME/.bashrc

# location for storing the bag files
# * do not change unless you know what you are doing
MAIN_DIR=~/"bag_files"

# the project name
# * is used to define folder name in ~/$MAIN_DIR
PROJECT_NAME=just_flying

# the name of the TMUX session
# * can be used for attaching as 'tmux a -t <session name>'
SESSION_NAME=mav

# following commands will be executed first in each window
# * do NOT put ; at the end
pre_input=""

# define commands
# 'name' 'command'
# * DO NOT PUT SPACES IN THE NAMES
# * "new line" after the command => the command will be called after start
# * NO "new line" after the command => the command will wait for user's <enter>
input=(
'Rosbag' 'waitForOffboard; ./record.sh
'
'Sensors' 'waitForTime; roslaunch mrs_uav_deployment sensors.launch
'
'Nimbro' 'waitForTime; rosrun mrs_uav_deployment run_nimbro.py ./config/network_config.yaml `rospack find mrs_uav_deployment`/config/communication_config.yaml
'
'HwApi' 'waitForTime; roslaunch mrs_uav_px4_api api.launch
'
'Status' 'waitForHw; roslaunch mrs_uav_status status.launch
'
'Core' 'waitForTime; roslaunch mrs_uav_core core.launch platform_config:=`rospack find mrs_uav_deployment`/config/mrs_uav_system/$UAV_TYPE.yaml world_config:=`rospack find mrs_uav_deployment`/config/worlds/world_$WORLD_NAME.yaml custom_config:=./config/custom_config.yaml network_config:=./config/network_config.yaml
'
'AutoStart' 'waitForHw; roslaunch mrs_uav_autostart automatic_start.launch
'
'uvdar_observer' 'waitForRos; roslaunch uvdar_core rw_three_sided_marlon.launch
'
'uvdar_filter' 'waitForRos; roslaunch uvdar_core uvdar_kalman.launch output_frame:='"$UAV_NAME"'/stable_origin
'
'uav_waypoint_flier' 'export '"$UAV_NAME"'; waitForControl; roslaunch example_waypoint_flier example_waypoint_flier.launch; history -s rosservice call /'"$UAV_NAME"'/example_waypoint_flier/fly_to_first_waypoint; export '"$UAV_NAME"'; history -s rosservice call /'"$UAV_NAME"'/example_waypoint_flier/start_waypoints_following;export '"$UAV_NAME"'; history -s rosservice call /'"$UAV_NAME"'/example_waypoint_flier/stop_waypoints_following;
'
'record' 'waitForRos; history -s rosbag record -O ~/Desktop/MRS_Master_Project/rosbags/simulation/static_static_topics_5m_0.4.bag /uav1/uvdar/adaptive_logging_back /uav1/uvdar/adaptive_logging_left /uav1/uvdar/adaptive_logging_right /uav1/uvdar/blinkers_seen_back /uav1/uvdar/blinkers_seen_left /uav1/uvdar/blinkers_seen_right /uav1/control_manager/control_reference --duration=30s;
'
# do NOT modify the command list below
'EstimDiag' 'waitForHw; rostopic echo /'"$UAV_NAME"'/estimation_manager/diagnostics
'
'kernel_log' 'tail -f /var/log/kern.log -n 100
'
'roscore' 'roscore
'
'simtime' 'waitForRos; rosparam set use_sim_time false
'
)

# the name of the window to focus after start
init_window="Status"

# automatically attach to the new session?
# {true, false}, default true
attach=true

###########################
### DO NOT MODIFY BELOW ###
###########################

export TMUX_BIN="/usr/bin/tmux -L mrs -f /etc/ctu-mrs/tmux.conf"

# find the session
FOUND=$( $TMUX_BIN ls | grep $SESSION_NAME )

if [ $? == "0" ]; then
echo "The session already exists"
$TMUX_BIN -2 attach-session -t $SESSION_NAME
exit
fi

# Absolute path to this script. /home/user/bin/foo.sh
SCRIPT=$(readlink -f $0)
# Absolute path this script is in. /home/user/bin
SCRIPTPATH=`dirname $SCRIPT`

TMUX= $TMUX_BIN new-session -s "$SESSION_NAME" -d
echo "Starting new session."

# get the iterator
ITERATOR_FILE="$MAIN_DIR/$PROJECT_NAME"/iterator.txt
if [ -e "$ITERATOR_FILE" ]
then
ITERATOR=`cat "$ITERATOR_FILE"`
ITERATOR=$(($ITERATOR+1))
else
echo "iterator.txt does not exist, creating it"
mkdir -p "$MAIN_DIR/$PROJECT_NAME"
touch "$ITERATOR_FILE"
ITERATOR="1"
fi
echo "$ITERATOR" > "$ITERATOR_FILE"

# create file for logging terminals' output
LOG_DIR="$MAIN_DIR/$PROJECT_NAME/"
SUFFIX=$(date +"%Y_%m_%d_%H_%M_%S")
SUBLOG_DIR="$LOG_DIR/"$ITERATOR"_"$SUFFIX""
TMUX_DIR="$SUBLOG_DIR/tmux"
mkdir -p "$SUBLOG_DIR"
mkdir -p "$TMUX_DIR"

# link the "latest" folder to the recently created one
rm "$LOG_DIR/latest" > /dev/null 2>&1
rm "$MAIN_DIR/latest" > /dev/null 2>&1
ln -sf "$SUBLOG_DIR" "$LOG_DIR/latest"
ln -sf "$SUBLOG_DIR" "$MAIN_DIR/latest"

# create arrays of names and commands
for ((i=0; i < ${#input[*]}; i++));
do
((i%2==0)) && names[$i/2]="${input[$i]}"
((i%2==1)) && cmds[$i/2]="${input[$i]}"
done

# run tmux windows
for ((i=0; i < ${#names[*]}; i++));
do
$TMUX_BIN new-window -t $SESSION_NAME:$(($i+1)) -n "${names[$i]}"
done

sleep 3

# start loggers
for ((i=0; i < ${#names[*]}; i++));
do
$TMUX_BIN pipe-pane -t $SESSION_NAME:$(($i+1)) -o "ts | cat >> $TMUX_DIR/$(($i+1))_${names[$i]}.log"
done

# send commands
for ((i=0; i < ${#cmds[*]}; i++));
do
$TMUX_BIN send-keys -t $SESSION_NAME:$(($i+1)) "cd $SCRIPTPATH;
${pre_input};
${cmds[$i]}"
done

# identify the index of the init window
init_index=0
for ((i=0; i < ((${#names[*]})); i++));
do
if [ ${names[$i]} == "$init_window" ]; then
init_index=$(expr $i + 1)
fi
done

$TMUX_BIN select-window -t $SESSION_NAME:$init_index

if $attach; then

if [ -z ${TMUX} ];
then
$TMUX_BIN -2 attach-session -t $SESSION_NAME
else
tmux detach-client -E "tmux -L mrs a -t $SESSION_NAME"
fi
else
echo "The session was started"
echo "You can later attach by calling:"
echo " tmux -L mrs a -t $SESSION_NAME"
fi
179 changes: 179 additions & 0 deletions scripts/tx.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,179 @@
#!/bin/bash
### BEGIN INIT INFO
# Provides: tmux
# Required-Start: $local_fs $network dbus
# Required-Stop: $local_fs $network
# Default-Start: 2 3 4 5
# Default-Stop: 0 1 6
# Short-Description: start the uav
### END INIT INFO
if [ "$(id -u)" == "0" ]; then
exec sudo -u mrs "$0" "$@"
fi

source $HOME/.bashrc

# location for storing the bag files
# * do not change unless you know what you are doing
MAIN_DIR=~/"bag_files"

# the project name
# * is used to define folder name in ~/$MAIN_DIR
PROJECT_NAME=just_flying

# the name of the TMUX session
# * can be used for attaching as 'tmux a -t <session name>'
SESSION_NAME=mav

# following commands will be executed first in each window
# * do NOT put ; at the end
pre_input=""

# define commands
# 'name' 'command'
# * DO NOT PUT SPACES IN THE NAMES
# * "new line" after the command => the command will be called after start
# * NO "new line" after the command => the command will wait for user's <enter>
input=(
'Rosbag' 'waitForOffboard; ./record.sh
'
'Sensors' 'waitForTime; roslaunch mrs_uav_deployment sensors.launch
'
'Nimbro' 'waitForTime; rosrun mrs_uav_deployment run_nimbro.py ./config/network_config.yaml `rospack find mrs_uav_deployment`/config/communication_config.yaml
'
'HwApi' 'waitForTime; roslaunch mrs_uav_px4_api api.launch
'
'Status' 'waitForHw; roslaunch mrs_uav_status status.launch
'
'Core' 'waitForTime; roslaunch mrs_uav_core core.launch platform_config:=`rospack find mrs_uav_deployment`/config/mrs_uav_system/$UAV_TYPE.yaml world_config:=`rospack find mrs_uav_deployment`/config/worlds/world_$WORLD_NAME.yaml custom_config:=./config/custom_config.yaml network_config:=./config/network_config.yaml
'
'AutoStart' 'waitForHw; roslaunch mrs_uav_autostart automatic_start.launch
'
'led_manager' 'waitForRos; roslaunch uvdar_core led_manager.launch
'
'load_sequence' 'waitForRos; history -s rosservice call /'"$UAV_NAME"'/uvdar_led_manager_node/select_sequences [0,1,2,3]; history -s rosservice call /'"$UAV_NAME"'/uvdar_led_manager_node/load_sequences;
'
'uav_waypoint_flier' 'export '"$UAV_NAME"'; waitForControl; roslaunch example_waypoint_flier example_waypoint_flier.launch; history -s rosservice call /'"$UAV_NAME"'/example_waypoint_flier/fly_to_first_waypoint; export '"$UAV_NAME"'; history -s rosservice call /'"$UAV_NAME"'/example_waypoint_flier/start_waypoints_following;export '"$UAV_NAME"'; history -s rosservice call /'"$UAV_NAME"'/example_waypoint_flier/stop_waypoints_following;
'
# do NOT modify the command list below
'EstimDiag' 'waitForHw; rostopic echo /'"$UAV_NAME"'/estimation_manager/diagnostics
'
'kernel_log' 'tail -f /var/log/kern.log -n 100
'
'roscore' 'roscore
'
'simtime' 'waitForRos; rosparam set use_sim_time false
'
)

# the name of the window to focus after start
init_window="Status"

# automatically attach to the new session?
# {true, false}, default true
attach=true

###########################
### DO NOT MODIFY BELOW ###
###########################

export TMUX_BIN="/usr/bin/tmux -L mrs -f /etc/ctu-mrs/tmux.conf"

# find the session
FOUND=$( $TMUX_BIN ls | grep $SESSION_NAME )

if [ $? == "0" ]; then
echo "The session already exists"
$TMUX_BIN -2 attach-session -t $SESSION_NAME
exit
fi

# Absolute path to this script. /home/user/bin/foo.sh
SCRIPT=$(readlink -f $0)
# Absolute path this script is in. /home/user/bin
SCRIPTPATH=`dirname $SCRIPT`

TMUX= $TMUX_BIN new-session -s "$SESSION_NAME" -d
echo "Starting new session."

# get the iterator
ITERATOR_FILE="$MAIN_DIR/$PROJECT_NAME"/iterator.txt
if [ -e "$ITERATOR_FILE" ]
then
ITERATOR=`cat "$ITERATOR_FILE"`
ITERATOR=$(($ITERATOR+1))
else
echo "iterator.txt does not exist, creating it"
mkdir -p "$MAIN_DIR/$PROJECT_NAME"
touch "$ITERATOR_FILE"
ITERATOR="1"
fi
echo "$ITERATOR" > "$ITERATOR_FILE"

# create file for logging terminals' output
LOG_DIR="$MAIN_DIR/$PROJECT_NAME/"
SUFFIX=$(date +"%Y_%m_%d_%H_%M_%S")
SUBLOG_DIR="$LOG_DIR/"$ITERATOR"_"$SUFFIX""
TMUX_DIR="$SUBLOG_DIR/tmux"
mkdir -p "$SUBLOG_DIR"
mkdir -p "$TMUX_DIR"

# link the "latest" folder to the recently created one
rm "$LOG_DIR/latest" > /dev/null 2>&1
rm "$MAIN_DIR/latest" > /dev/null 2>&1
ln -sf "$SUBLOG_DIR" "$LOG_DIR/latest"
ln -sf "$SUBLOG_DIR" "$MAIN_DIR/latest"

# create arrays of names and commands
for ((i=0; i < ${#input[*]}; i++));
do
((i%2==0)) && names[$i/2]="${input[$i]}"
((i%2==1)) && cmds[$i/2]="${input[$i]}"
done

# run tmux windows
for ((i=0; i < ${#names[*]}; i++));
do
$TMUX_BIN new-window -t $SESSION_NAME:$(($i+1)) -n "${names[$i]}"
done

sleep 3

# start loggers
for ((i=0; i < ${#names[*]}; i++));
do
$TMUX_BIN pipe-pane -t $SESSION_NAME:$(($i+1)) -o "ts | cat >> $TMUX_DIR/$(($i+1))_${names[$i]}.log"
done

# send commands
for ((i=0; i < ${#cmds[*]}; i++));
do
$TMUX_BIN send-keys -t $SESSION_NAME:$(($i+1)) "cd $SCRIPTPATH;
${pre_input};
${cmds[$i]}"
done

# identify the index of the init window
init_index=0
for ((i=0; i < ((${#names[*]})); i++));
do
if [ ${names[$i]} == "$init_window" ]; then
init_index=$(expr $i + 1)
fi
done

$TMUX_BIN select-window -t $SESSION_NAME:$init_index

if $attach; then

if [ -z ${TMUX} ];
then
$TMUX_BIN -2 attach-session -t $SESSION_NAME
else
tmux detach-client -E "tmux -L mrs a -t $SESSION_NAME"
fi
else
echo "The session was started"
echo "You can later attach by calling:"
echo " tmux -L mrs a -t $SESSION_NAME"
fi

0 comments on commit 511b19a

Please sign in to comment.