Skip to content

Commit

Permalink
Extra plots
Browse files Browse the repository at this point in the history
  • Loading branch information
Your Name committed Apr 11, 2024
1 parent 16afea1 commit 13319f4
Show file tree
Hide file tree
Showing 5 changed files with 40 additions and 43 deletions.
2 changes: 1 addition & 1 deletion include/detect/uv_led_detect_adaptive.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -363,7 +363,7 @@ std::vector<cv::Point> UVDARLedDetectAdaptive::applyAdaptiveThreshold(const cv::
//lastProcessedBinaryROIs_.push_back(new_binaryRoi); // Store the binary ROI (For debugging/visualization)
// Store the binary ROI (For debugging/visualization)
lastProcessedBinaryROIs_.push_back(binaryRoi);
//saveRoiImage(binaryRoi, point, roiIndex_++, optimalThreshold, 1.0);
//saveRoiImage(binaryRoi, point, roiIndex_++, thresholdValue_, 1.0);
//std::cout << "[UVDARLedDetectAdaptive]: ADDING ROI DETECTED POINTS: " << roiDetectedPoints.size() << std::endl;


Expand Down
2 changes: 1 addition & 1 deletion launch/sim_three_sided_combined_marlon.launch
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@
<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_method" type="string" value="KL"/>
<param name="adaptive_method" type="string" value="Otsu"/>

<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
68 changes: 30 additions & 38 deletions scripts/Processing_evaluation_distance.ipynb
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
},
{
"cell_type": "code",
"execution_count": 35,
"execution_count": 3,
"metadata": {},
"outputs": [
{
Expand Down Expand Up @@ -47,9 +47,9 @@
" <tbody>\n",
" <tr>\n",
" <th>1</th>\n",
" <td>60.980</td>\n",
" <td>4.996939</td>\n",
" <td>[2.0, 1.0, 3.0]</td>\n",
" <td>66.124</td>\n",
" <td>4.995741</td>\n",
" <td>[2.0, 3.0, 1.0]</td>\n",
" <td>3</td>\n",
" <td>0</td>\n",
" <td>1</td>\n",
Expand All @@ -58,9 +58,9 @@
" <td>5</td>\n",
" </tr>\n",
" <tr>\n",
" <th>3</th>\n",
" <td>60.992</td>\n",
" <td>4.996921</td>\n",
" <th>2</th>\n",
" <td>66.124</td>\n",
" <td>4.995741</td>\n",
" <td>[2.0, 1.0, 3.0]</td>\n",
" <td>3</td>\n",
" <td>0</td>\n",
Expand All @@ -71,9 +71,9 @@
" </tr>\n",
" <tr>\n",
" <th>4</th>\n",
" <td>60.996</td>\n",
" <td>4.996921</td>\n",
" <td>[2.0, 1.0, 3.0]</td>\n",
" <td>66.140</td>\n",
" <td>4.995741</td>\n",
" <td>[2.0, 3.0, 1.0]</td>\n",
" <td>3</td>\n",
" <td>0</td>\n",
" <td>1</td>\n",
Expand All @@ -82,9 +82,9 @@
" <td>5</td>\n",
" </tr>\n",
" <tr>\n",
" <th>7</th>\n",
" <td>61.008</td>\n",
" <td>4.996884</td>\n",
" <th>5</th>\n",
" <td>66.140</td>\n",
" <td>4.995741</td>\n",
" <td>[2.0, 1.0, 3.0]</td>\n",
" <td>3</td>\n",
" <td>0</td>\n",
Expand All @@ -95,9 +95,9 @@
" </tr>\n",
" <tr>\n",
" <th>8</th>\n",
" <td>61.012</td>\n",
" <td>4.996884</td>\n",
" <td>[2.0, 1.0, 3.0]</td>\n",
" <td>66.156</td>\n",
" <td>4.995741</td>\n",
" <td>[2.0, 3.0, 1.0]</td>\n",
" <td>3</td>\n",
" <td>0</td>\n",
" <td>1</td>\n",
Expand All @@ -111,21 +111,21 @@
],
"text/plain": [
" timestamp distance_x value num_points error_count signal_3 \\\n",
"1 60.980 4.996939 [2.0, 1.0, 3.0] 3 0 1 \n",
"3 60.992 4.996921 [2.0, 1.0, 3.0] 3 0 1 \n",
"4 60.996 4.996921 [2.0, 1.0, 3.0] 3 0 1 \n",
"7 61.008 4.996884 [2.0, 1.0, 3.0] 3 0 1 \n",
"8 61.012 4.996884 [2.0, 1.0, 3.0] 3 0 1 \n",
"1 66.124 4.995741 [2.0, 3.0, 1.0] 3 0 1 \n",
"2 66.124 4.995741 [2.0, 1.0, 3.0] 3 0 1 \n",
"4 66.140 4.995741 [2.0, 3.0, 1.0] 3 0 1 \n",
"5 66.140 4.995741 [2.0, 1.0, 3.0] 3 0 1 \n",
"8 66.156 4.995741 [2.0, 3.0, 1.0] 3 0 1 \n",
"\n",
" signal_2 signal_1 nearest_distance \n",
"1 1 1 5 \n",
"3 1 1 5 \n",
"2 1 1 5 \n",
"4 1 1 5 \n",
"7 1 1 5 \n",
"5 1 1 5 \n",
"8 1 1 5 "
]
},
"execution_count": 35,
"execution_count": 3,
"metadata": {},
"output_type": "execute_result"
}
Expand All @@ -139,30 +139,24 @@
"import ast\n",
"\n",
"\n",
"\n",
"# Load the data\n",
"input_csv_path = os.path.expanduser('~/Desktop/MRS_Master_Project/rosbags/simulation/dynamic_standard_th_100_v2_1.csv')\n",
"input_csv_path = os.path.expanduser('~/Desktop/MRS_Master_Project/rosbags/simulation/raw_csv/static_otsu_adaptive_experiment_v3.csv')\n",
"data = pd.read_csv(input_csv_path)\n",
"\n",
"# Convert 'value' column from string representation of lists to actual lists\n",
"#Ensure that the 'value' column is a list\n",
"data['value'] = data['value'].apply(lambda x: ast.literal_eval(x) if isinstance(x, str) else x)\n",
"\n",
"\n",
"\n",
"#Relative distance to the target (TX is at 10m from origin, and we recorded the position of the RX)\n",
"data['distance_x'] = 10.0 - data['distance_x']\n",
"\n",
"\n",
"# Fill missing 'distance_x' with the previous value\n",
"data['distance_x'] = data['distance_x'].fillna(method='ffill')\n",
"\n",
"\n",
"# Remove missing 'value'\n",
"data = data.dropna(subset=['value'])\n",
"\n",
"#Add a column for the number of points in each row\n",
"data['num_points'] = data['value'].apply(len)\n",
"\n",
"# Assume calculate_error_rate is defined as before\n",
"\n",
"def calculate_error_rate(values):\n",
" error_count = 0\n",
" for value in values:\n",
Expand All @@ -172,7 +166,6 @@
" \n",
" return error_count\n",
"\n",
"#print(first_row_test)\n",
"data['error_count'] = data['value'].apply(calculate_error_rate)\n",
"\n",
"#Function to check occurrence of signal 3\n",
Expand All @@ -198,18 +191,17 @@
"data['signal_1'] = data['value'].apply(check_signal_1)\n",
"\n",
"\n",
"# Specified relative distances\n",
"specified_distances = np.array([5, 8, 11, 14, 17, 20])\n",
"\n",
"# Assigning each data point to the nearest specified distance\n",
"data['nearest_distance'] = specified_distances[np.abs(specified_distances[:, np.newaxis] - data['distance_x'].values).argmin(axis=0)]\n",
"\n",
"# Save the cleaned data to a new CSV file\n",
"cleaned_file_path = os.path.expanduser('~/Desktop/MRS_Master_Project/rosbags/simulation/dynamic_standard_th_100_v2_1_processed.csv')\n",
"cleaned_file_path = os.path.expanduser('~/Desktop/MRS_Master_Project/rosbags/simulation/processed_csv/static_otsu_adaptive_heading_exp_v3_processed.csv')\n",
"\n",
"data.to_csv(cleaned_file_path, index=False)\n",
"\n",
"cleaned_file_path # Return the path to the new CSV and display the first few rows of the cleaned data.\n",
"cleaned_file_path \n",
"\n",
"\n",
"data.head()\n",
Expand Down
9 changes: 7 additions & 2 deletions scripts/extracting_evaluation_distance.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,12 @@

# List of ROS bag files
bag_files = [
os.path.expanduser('~/Desktop/MRS_Master_Project/rosbags/simulation/otsu_dynamic_adaptive_topics.bag')
os.path.expanduser('~/Desktop/MRS_Master_Project/rosbags/simulation/heading_experiments/static_static_topics_5m_0.4.bag'),
os.path.expanduser('~/Desktop/MRS_Master_Project/rosbags/simulation/heading_experiments/static_static_topics_8m_0.4.bag'),
os.path.expanduser('~/Desktop/MRS_Master_Project/rosbags/simulation/heading_experiments/static_static_topics_11m_0.4.bag'),
os.path.expanduser('~/Desktop/MRS_Master_Project/rosbags/simulation/heading_experiments/static_static_topics_14m_0.4.bag'),



#os.path.expanduser('~/Desktop/MRS_Master_Project/rosbags/simulation/static_standard_topics_8m.bag'),
#os.path.expanduser('~/Desktop/MRS_Master_Project/rosbags/simulation/static_standard_topics_11m.bag'),
Expand All @@ -22,7 +27,7 @@
#output_csv = os.path.expanduser('~/Desktop/MRS_Master_Project/rosbags/simulation/standard_test_3.csv')

# Output CSV file
output_csv = os.path.expanduser('~/Desktop/MRS_Master_Project/rosbags/simulation/otsu_dynamic_adaptive_v2.csv')
output_csv = os.path.expanduser('~/Desktop/MRS_Master_Project/rosbags/simulation/raw_csv/static_static_heading_experiment_v3.csv')

# Define the topics to extract
topics = ['/uav1/uvdar/blinkers_seen_left','/uav1/uvdar/blinkers_seen_right','/uav1/control_manager/control_reference']
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:
- 'history -s rosbag record -O ~/Desktop/MRS_Master_Project/rosbags/simulation/static_standard_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'
- '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'
#- rosbag record -O rosbags/first/omta_38.bag -e "(.*)_camp"
# - rosbag record -O rosbags/first/omta_39.bag -e "(.*)_camp"

0 comments on commit 13319f4

Please sign in to comment.