Conversation
…ng publishing of move
Daniel-Martin576
left a comment
There was a problem hiding this comment.
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; |
There was a problem hiding this comment.
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 |
There was a problem hiding this comment.
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 |
There was a problem hiding this comment.
Does this break if distanceX = 0?
| findStopBarFromHough(frame, debug, stopBarAngle, stopBarGoalAngle, stopBarGoalAngleRange, | ||
| stopBarTriggerDistance, houghThreshold, houghMinLineLength, houghMaxLineGap); |
There was a problem hiding this comment.
Why are some of these variables passed if they are global?
| double rho = 1; // distance resolution | ||
| double theta = CV_PI / 180; // angular resolution (in radians) pi/180 is one degree res |
There was a problem hiding this comment.
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 |
There was a problem hiding this comment.
shortest_angular_distance() for fabs(stopBarGoalAngle - currAngle)?
| 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")); |
There was a problem hiding this comment.
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" /> |
There was a problem hiding this comment.
How did you even test this? Aka what launch file did you run to get this topic?
Closes #368