Skip to content

Commit

Permalink
Saving devel before checking upstream changes
Browse files Browse the repository at this point in the history
  • Loading branch information
MarlonRiv committed Mar 24, 2024
1 parent 1d95221 commit f99962d
Show file tree
Hide file tree
Showing 4 changed files with 42 additions and 20 deletions.
8 changes: 4 additions & 4 deletions launch/sim_three_sided_combined_marlon.launch
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@
<param name="num_worker_threads" value="8" />
</node>

<node name="bluefox_emulator" pkg="nodelet" type="nodelet" args="$(arg nodelet) uvdar/UVDARBluefoxEmulator $(arg nodelet_manager)" output="screen" respawn="false" launch-prefix="bash -c 'sleep 0; $0 $@'">
<node name="bluefox_emulator" pkg="nodelet" type="nodelet" args="$(arg nodelet) uvdar/UVDARBluefoxEmulator $(arg nodelet_manager)" output="screen" respawn="false" launch-prefix="bash -c 'sleep 5; $0 $@'">
<rosparam param="camera_output_topics"> ["camera_left", "camera_right", "camera_back"] </rosparam>
<rosparam param="calib_files"> ["default", "default", "default"] </rosparam>
<remap from="~camera_left" to="/$(arg uav_name)/uvdar_bluefox_left/image_raw"/>
Expand All @@ -129,7 +129,7 @@
<param name="publish" type="bool" value="$(arg publish)"/>
<param name="justReport" type="bool" value="true"/>
<param name="threshold" type="int" value="$(arg threshold)"/>
<param name="adaptive_threshold" type="bool" value="true"/>
<param name="adaptive_threshold" type="bool" value="false"/>

<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>
Expand Down Expand Up @@ -162,7 +162,7 @@
</node>


<node name="blink_processor" pkg="nodelet" type="nodelet" args="load uvdar/UVDARBlinkProcessor $(arg nodelet_manager)" output="screen" respawn="false" launch-prefix="bash -c 'sleep 20; $0 $@'">
<node name="blink_processor" pkg="nodelet" type="nodelet" args="load uvdar/UVDARBlinkProcessor $(arg nodelet_manager)" output="screen" respawn="false" launch-prefix="bash -c 'sleep 15; $0 $@'">
<!-- <node name="UVDARBlinkProcessor" pkg="nodelet" type="nodelet" args="load uvdar/UVDARBlinkProcessor $(arg nodelet_manager)" output="screen" respawn="false" launch-prefix="debug_roslaunch"> -->

<param name="uav_name" type = "string" value="$(arg uav_name)"/>
Expand Down Expand Up @@ -236,7 +236,7 @@


<!-- <node name="uvdar_pose_calculator_node" pkg="uvdar_core" type="uvdar_pose_calculator_node" output="screen" launch-prefix="debug_roslaunch"> -->
<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" output="screen" launch-prefix="bash -c 'sleep 20; $0 $@'">>
<!-- <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)"/>
Expand Down
3 changes: 2 additions & 1 deletion scripts/two_drones/config/custom_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -11,10 +11,11 @@ mrs_uav_managers:
state_estimators: [
"gps_garmin",
"gps_baro",
"rtk",

]

initial_state_estimator: "gps_baro" # will be used as the first state estimator
initial_state_estimator: "rtk" # will be used as the first state estimator
agl_height_estimator: "garmin_agl" # only slightly filtered height for checking min height (not used in control feedback)

uav_manager:
Expand Down
2 changes: 1 addition & 1 deletion scripts/two_drones/session_marlon.yml
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ windows:
- record:
layout: even-vertical
panes:
# - waitForRos; sleep 3; rosbag record -O ~/Desktop/MRS_Master_Project/rosbags/simulation/sim_otsu_topics.bag /uav1/uvdar/adaptive_logging_back /uav1/uvdar/adaptive_logging_left /uav1/uvdar/adaptive_logging_right --duration=3m
- 'history -s rosbag record -O ~/Desktop/MRS_Master_Project/rosbags/simulation/standard_topics.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'
#- rosbag record -O rosbags/first/omta_38.bag -e "(.*)_camp"
# - rosbag record -O rosbags/first/omta_39.bag -e "(.*)_camp"

49 changes: 35 additions & 14 deletions src/detector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -348,10 +348,9 @@ class UVDARDetector : public nodelet::Nodelet{
}
//}



/* publishVisualizationImage //{ */
void publishVisualizationImage(const cv::Mat& visualization_image) {

if (!visualization_image.empty()) {
// Convert OpenCV image to ROS message
cv_bridge::CvImage cv_image;
Expand All @@ -369,6 +368,16 @@ class UVDARDetector : public nodelet::Nodelet{

/* processStandard //{ */
void processStandard(const cv_bridge::CvImageConstPtr& image, int image_index){
/**
* @brief Extracts small bright points from input image
*
* @param image - the input image
* @param image_index - index of the camera that produced this image
*
* @return success
*
*
*/
ROS_INFO_STREAM("[UVDARDetector]: Processing image with standard thresholding.");

if ( ! (uvdf_[image_index]->processImage(
Expand Down Expand Up @@ -397,6 +406,17 @@ class UVDARDetector : public nodelet::Nodelet{

/* processAdaptive //{ */
void processAdaptive(const cv_bridge::CvImageConstPtr& image, int image_index, const std::vector<cv::Point>& trackingPoints){
/**
* @brief Extracts adaptively small bright points from input image
*
* @param image - the input image
* @param image_index - index of the camera that produced this image
* @param trackingPoints - the tracking points for the camera
*
* @return success
*/


ROS_INFO_STREAM("[UVDARDetector]: Processing image with tracking points only.");

if( ! (uvda_[image_index]->processImageAdaptive(
Expand All @@ -418,18 +438,8 @@ class UVDARDetector : public nodelet::Nodelet{

}
//}
/* processSingleImage //{ */

/**
* @brief Extracts small bright points from input image and publishes them. Optionally also publishes points corresponding to the sun.
*
* @param te - timer event - necessary for use of this method as a timer callback
* @param image - the input image
* @param image_index - index of the camera that produced this image
*/



/* publishAdaptive //{ */
void publishAdaptive(const cv_bridge::CvImageConstPtr& image, int image_index, const std::vector<cv::Point>& adaptive_detected_points) {
ROS_INFO_STREAM("[UVDARDetector]: Publishing adaptive points.");
uvdar_core::ImagePointsWithFloatStamped msg_detected;
Expand All @@ -455,8 +465,10 @@ class UVDARDetector : public nodelet::Nodelet{

pub_adaptive_logging_[image_index].publish(msg_adaptive);
}
//}


/* publishStandard //{ */
void publishStandard(const cv_bridge::CvImageConstPtr& image, int image_index, const std::vector<cv::Point>& detected_points) {
ROS_INFO_STREAM("[UVDARDetector]: Publishing standard points.");
ROS_INFO_STREAM("[UVDARDetector]: This is the image index: " << image_index);
Expand Down Expand Up @@ -484,9 +496,18 @@ class UVDARDetector : public nodelet::Nodelet{
}
pub_candidate_points_[image_index].publish(msg_detected);
}
//}

/* processSingleImage //{ */


/**
* @brief Extracts small bright points from input image and publishes them. Optionally also publishes points corresponding to the sun.
*
* @param te - timer event - necessary for use of this method as a timer callback
* @param image - the input image
* @param image_index - index of the camera that produced this image
*/

void processSingleImage([[maybe_unused]] const ros::TimerEvent& te, const cv_bridge::CvImageConstPtr image, int image_index) {
if (!initialized_){
ROS_WARN_STREAM_THROTTLE(1.0,"[UVDARDetector]: Not yet initialized, dropping message...");
Expand Down

0 comments on commit f99962d

Please sign in to comment.