Skip to content

Commit

Permalink
fix(bytetrack): fix cppcheck warnings (#7576)
Browse files Browse the repository at this point in the history
* fix unreadVariable

Signed-off-by: Ryuta Kambe <[email protected]>

* fix variableScope

Signed-off-by: Ryuta Kambe <[email protected]>

* fix unusedVariable

Signed-off-by: Ryuta Kambe <[email protected]>

* fix constParameterPointer

Signed-off-by: Ryuta Kambe <[email protected]>

* fix unreadVariable

Signed-off-by: Ryuta Kambe <[email protected]>

* style(pre-commit): autofix

---------

Signed-off-by: Ryuta Kambe <[email protected]>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
veqcc and pre-commit-ci[bot] authored Jun 24, 2024
1 parent 5bead38 commit ed0c45d
Show file tree
Hide file tree
Showing 4 changed files with 7 additions and 16 deletions.
5 changes: 3 additions & 2 deletions perception/bytetrack/lib/src/lapjv.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -181,7 +181,8 @@ int_t _carr_dense(

/** Find columns with minimum d[j] and put them on the SCAN list.
*/
uint_t _find_dense(const uint_t n, uint_t lo, cost_t * d, int_t * cols, [[maybe_unused]] int_t * y)
uint_t _find_dense(
const uint_t n, uint_t lo, const cost_t * d, int_t * cols, [[maybe_unused]] int_t * y)
{
uint_t hi = lo + 1;
cost_t mind = d[cols[lo]];
Expand All @@ -203,7 +204,7 @@ uint_t _find_dense(const uint_t n, uint_t lo, cost_t * d, int_t * cols, [[maybe_
// and try to decrease d of the TODO columns using the SCAN column.
int_t _scan_dense(
const uint_t n, cost_t * cost[], uint_t * plo, uint_t * phi, cost_t * d, int_t * cols,
int_t * pred, int_t * y, cost_t * v)
int_t * pred, const int_t * y, const cost_t * v)
{
uint_t lo = *plo;
uint_t hi = *phi;
Expand Down
9 changes: 0 additions & 9 deletions perception/bytetrack/lib/src/strack.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,12 +112,6 @@ void STrack::activate(int frame_id)
this->track_id = this->next_id();
this->unique_id = boost::uuids::random_generator()();

std::vector<float> _tlwh_tmp(4);
_tlwh_tmp[0] = this->original_tlwh[0];
_tlwh_tmp[1] = this->original_tlwh[1];
_tlwh_tmp[2] = this->original_tlwh[2];
_tlwh_tmp[3] = this->original_tlwh[3];
std::vector<float> xyah = tlwh_to_xyah(_tlwh_tmp);
// init kf
init_kalman_filter();
// reflect state
Expand All @@ -132,7 +126,6 @@ void STrack::activate(int frame_id)

void STrack::re_activate(STrack & new_track, int frame_id, bool new_id)
{
std::vector<float> xyah = tlwh_to_xyah(new_track.tlwh);
// TODO(me): write kf update
Eigen::MatrixXd measurement = Eigen::MatrixXd::Zero(_kf_parameters.dim_z, 1);
measurement << new_track.tlwh[0], new_track.tlwh[1], new_track.tlwh[2], new_track.tlwh[3];
Expand All @@ -156,8 +149,6 @@ void STrack::update(STrack & new_track, int frame_id)
this->frame_id = frame_id;
this->tracklet_len++;

std::vector<float> xyah = tlwh_to_xyah(new_track.tlwh);

// update
// TODO(me): write update
Eigen::MatrixXd measurement = Eigen::MatrixXd::Zero(_kf_parameters.dim_z, 1);
Expand Down
5 changes: 2 additions & 3 deletions perception/bytetrack/lib/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -190,7 +190,6 @@ std::vector<std::vector<float>> ByteTracker::ious(

// bbox_ious
for (size_t k = 0; k < btlbrs.size(); k++) {
std::vector<float> ious_tmp;
float box_area = (btlbrs[k][2] - btlbrs[k][0] + 1) * (btlbrs[k][3] - btlbrs[k][1] + 1);
for (size_t n = 0; n < atlbrs.size(); n++) {
float iw = std::min(atlbrs[n][2], btlbrs[k][2]) - std::max(atlbrs[n][0], btlbrs[k][0]) + 1;
Expand Down Expand Up @@ -277,8 +276,6 @@ double ByteTracker::lapjv(
std::vector<std::vector<float>> cost_c;
cost_c.assign(cost.begin(), cost.end());

std::vector<std::vector<float>> cost_c_extended;

int n_rows = cost.size();
int n_cols = cost[0].size();
rowsol.resize(n_rows);
Expand All @@ -296,6 +293,8 @@ double ByteTracker::lapjv(
}

if (extend_cost || cost_limit < LONG_MAX) {
std::vector<std::vector<float>> cost_c_extended;

n = n_rows + n_cols;
cost_c_extended.resize(n);
for (size_t i = 0; i < cost_c_extended.size(); i++) cost_c_extended[i].resize(n);
Expand Down
4 changes: 2 additions & 2 deletions perception/bytetrack/src/bytetrack_visualizer_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,14 +128,14 @@ void ByteTrackVisualizerNode::callback(
}

std::vector<cv::Rect> bboxes;
for (auto & feat_obj : rect_msg->feature_objects) {
for (const auto & feat_obj : rect_msg->feature_objects) {
auto roi_msg = feat_obj.feature.roi;
cv::Rect rect(roi_msg.x_offset, roi_msg.y_offset, roi_msg.width, roi_msg.height);
bboxes.push_back(rect);
}

std::vector<boost::uuids::uuid> uuids;
for (auto & dynamic_obj : uuid_msg->objects) {
for (const auto & dynamic_obj : uuid_msg->objects) {
auto uuid_msg = dynamic_obj.id.uuid;
boost::uuids::uuid uuid_raw;
std::copy(uuid_msg.begin(), uuid_msg.end(), uuid_raw.begin());
Expand Down

0 comments on commit ed0c45d

Please sign in to comment.