Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Feat/368 stop bar detector #384

Open
wants to merge 14 commits into
base: master
Choose a base branch
from
Open

Conversation

idale0001
Copy link
Contributor

@idale0001 idale0001 commented Mar 15, 2021

Closes #368

  • Decouples stop bar detector from sign detector
  • improves debug image by removing clutter
  • publishes stop bar angle
  • publishes when the robot is near the stop bar

Copy link
Contributor

@Daniel-Martin576 Daniel-Martin576 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looks good. Just some nitpicks 👍

int ddepth = CV_8UC1;
cv::Laplacian(frame, edges, ddepth); // use edge to get better Hough results
convertScaleAbs(edges, edges);
edges = frame;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does this override edges?

convertScaleAbs(edges, edges);
edges = frame;
cv::dilate(edges, edges, kernel(4, 4)); // clearer debug image and slightly better detection
cv::cvtColor(edges, output, cv::COLOR_GRAY2BGR); // for debugging
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Call output variable debug.

// calc angle and decide if it is a stop bar
double distanceX = p2.x - p1.x;
double distanceY = p2.y - p1.y;
double currAngle = atan(fabs(distanceY / distanceX)) * 180 / CV_PI; // in degrees
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does this break if distanceX = 0?

Comment on lines 124 to 125
findStopBarFromHough(frame, debug, stopBarAngle, stopBarGoalAngle, stopBarGoalAngleRange,
stopBarTriggerDistance, houghThreshold, houghMinLineLength, houghMaxLineGap);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why are some of these variables passed if they are global?

Comment on lines 69 to 70
double rho = 1; // distance resolution
double theta = CV_PI / 180; // angular resolution (in radians) pi/180 is one degree res
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Kinda magic numbers... Maybe const global variables? Doesn't matter that much


cv::Point midpoint = (p1 + p2) * 0.5;

if (fabs(stopBarGoalAngle - currAngle) <= stopBarGoalAngleRange) { // allows some amount of angle error
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

shortest_angular_distance() for fabs(stopBarGoalAngle - currAngle)?

Comment on lines 161 to 167
nhp.param("stopbar_near", stopbar_near_topic, std::string("/stopbar_near"));
nhp.param("stopbar_angle", stopbar_angle_topic, std::string("/stopbar_angle"));
nhp.param("sleep_adjust", sleepConstant, 1.0);

nhp.param("overhead_image_subscription", overhead_image_sub, std::string("/lines/detection_img_transformed"));

nhp.param("speed_subscription", speed_topic, std::string("/speed"));
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If you are going to do slash + topic name (/blah), you can just do nh.param, but you don't have to change it

<param name="stopbar_angle" type="string" value="/stopbar_angle"/>

<!-- Camera Params-->
<param name="overhead_image_subscription" type="string" value="/camera_center/lines/detection_img_transformed" />
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

How did you even test this? Aka what launch file did you run to get this topic?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

Stop Bar Detector
2 participants