Skip to content

Commit

Permalink
minor bug fix
Browse files Browse the repository at this point in the history
  • Loading branch information
jingyi-xiang committed Jun 22, 2023
1 parent 975c71c commit 5f618de
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 10 deletions.
8 changes: 4 additions & 4 deletions trackdlo/src/trackdlo_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -347,10 +347,10 @@ sensor_msgs::ImagePtr Callback(const sensor_msgs::ImageConstPtr& image_msg, cons
double y1 = row_1;
double x2 = col_2;
double y2 = row_2;
x1 = x1 + (0.25*dlo_pixel_width) / sqrt(pow(x1-x2, 2) + pow(y1-y2, 2)) * (x2 - x1);
y1 = y1 + (0.25*dlo_pixel_width) / sqrt(pow(x1-x2, 2) + pow(y1-y2, 2)) * (y2 - y1);
x2 = x2 + (0.25*dlo_pixel_width) / sqrt(pow(x1-x2, 2) + pow(y1-y2, 2)) * (x1 - x2);
y2 = y2 + (0.25*dlo_pixel_width) / sqrt(pow(x1-x2, 2) + pow(y1-y2, 2)) * (y1 - y2);
// x1 = x1 + (0.25*dlo_pixel_width) / sqrt(pow(x1-x2, 2) + pow(y1-y2, 2)) * (x2 - x1);
// y1 = y1 + (0.25*dlo_pixel_width) / sqrt(pow(x1-x2, 2) + pow(y1-y2, 2)) * (y2 - y1);
// x2 = x2 + (0.25*dlo_pixel_width) / sqrt(pow(x1-x2, 2) + pow(y1-y2, 2)) * (x1 - x2);
// y2 = y2 + (0.25*dlo_pixel_width) / sqrt(pow(x1-x2, 2) + pow(y1-y2, 2)) * (y1 - y2);
cv::line(projected_edges, cv::Point(x1, y1), cv::Point(x2, y2), cv::Scalar(255, 255, 255), dlo_pixel_width);
}

Expand Down
12 changes: 6 additions & 6 deletions trackdlo/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -263,7 +263,7 @@ visualization_msgs::MarkerArray MatrixXd2MarkerArray (MatrixXd Y,
// cur_node_result.header.stamp = ros::Time::now();
cur_node_result.type = visualization_msgs::Marker::SPHERE;
cur_node_result.action = visualization_msgs::Marker::ADD;
cur_node_result.ns = marker_ns + std::to_string(i);
cur_node_result.ns = marker_ns + "_node_" + std::to_string(i);
cur_node_result.id = i;

// add position
Expand Down Expand Up @@ -309,10 +309,10 @@ visualization_msgs::MarkerArray MatrixXd2MarkerArray (MatrixXd Y,
visualization_msgs::Marker cur_line_result = visualization_msgs::Marker();

// add header
cur_line_result.header.frame_id = "camera_color_optical_frame";
cur_line_result.header.frame_id = marker_frame;
cur_line_result.type = visualization_msgs::Marker::CYLINDER;
cur_line_result.action = visualization_msgs::Marker::ADD;
cur_line_result.ns = "line_results" + std::to_string(i);
cur_line_result.ns = marker_ns + "_line_" + std::to_string(i);
cur_line_result.id = i;

// add position
Expand Down Expand Up @@ -381,7 +381,7 @@ visualization_msgs::MarkerArray MatrixXd2MarkerArray (std::vector<MatrixXd> Y,
// cur_node_result.header.stamp = ros::Time::now();
cur_node_result.type = visualization_msgs::Marker::SPHERE;
cur_node_result.action = visualization_msgs::Marker::ADD;
cur_node_result.ns = marker_ns + std::to_string(i);
cur_node_result.ns = marker_ns + "_node_" + std::to_string(i);
cur_node_result.id = i;

// add position
Expand Down Expand Up @@ -427,10 +427,10 @@ visualization_msgs::MarkerArray MatrixXd2MarkerArray (std::vector<MatrixXd> Y,
visualization_msgs::Marker cur_line_result = visualization_msgs::Marker();

// add header
cur_line_result.header.frame_id = "camera_color_optical_frame";
cur_line_result.header.frame_id = marker_frame;
cur_line_result.type = visualization_msgs::Marker::CYLINDER;
cur_line_result.action = visualization_msgs::Marker::ADD;
cur_line_result.ns = "line_results" + std::to_string(i);
cur_line_result.ns = marker_ns + "_line_" + std::to_string(i);
cur_line_result.id = i;

// add position
Expand Down

0 comments on commit 5f618de

Please sign in to comment.