Skip to content

Commit

Permalink
refactor: update logging format along with project-zetton/zetton-common@
Browse files Browse the repository at this point in the history
  • Loading branch information
corenel committed Oct 26, 2021
1 parent 5f939f9 commit 2b7534d
Show file tree
Hide file tree
Showing 13 changed files with 61 additions and 58 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ find_package(catkin REQUIRED COMPONENTS
sensor_msgs
message_generation
zetton_common
zetton_stream
)
catkin_python_setup()
catkin_package(
Expand Down
17 changes: 9 additions & 8 deletions example/ros_mot_tracker.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
#include "zetton_inference/tracker/sort_tracker.h"

void signalHandler(int sig) {
ROS_WARN("Trying to exit!");
AWARN_F("Trying to exit!");
ros::shutdown();
}

Expand All @@ -28,7 +28,7 @@ class RosMotTracker {
try {
cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
} catch (cv_bridge::Exception& e) {
ROS_ERROR("cv_bridge exception: %s", e.what());
AERROR_F("cv_bridge exception: {}", e.what());
return;
}

Expand All @@ -40,15 +40,15 @@ class RosMotTracker {
tracker_.Track(cv_ptr->image, ros::Time::now(), detections);

// print detections and tracks
ROS_INFO("Detections:");
AINFO_F("Detections:");
for (auto& detection : detections) {
ROS_INFO_STREAM(detection);
AINFO << detection;
detection.Draw(cv_ptr->image);
}
ROS_INFO("Trackings:");
AINFO_F("Trackings:");
for (auto& track : tracker_.tracks()) {
// if (track.tracking_fail_count <= 3) {
ROS_INFO_STREAM(track);
AINFO << track;
track.Draw(cv_ptr->image);
// }
}
Expand All @@ -57,7 +57,7 @@ class RosMotTracker {
image_pub_.publish(
cv_bridge::CvImage(std_msgs::Header(), "bgr8", cv_ptr->image)
.toImageMsg());
ROS_INFO("---");
AINFO_F("---");
}

ros::NodeHandle* nh_;
Expand All @@ -74,7 +74,8 @@ class RosMotTracker {
RosMotTracker(ros::NodeHandle* nh) : nh_(nh), it_(*nh_) {
// load params
// hardcoded or using GPARAM
// std::string image_topic_sub = "/uvds_communication/image_streaming/mavic_0";
// std::string image_topic_sub =
// "/uvds_communication/image_streaming/mavic_0";
std::string image_topic_sub = "/camera/image";

// subscribe to input video feed
Expand Down
6 changes: 3 additions & 3 deletions example/ros_yolo_object_detector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#include "zetton_inference/detector/yolo_object_detector.h"

void signalHandler(int sig) {
ROS_WARN("Trying to exit!");
AWARN_F("Trying to exit!");
ros::shutdown();
}

Expand All @@ -23,7 +23,7 @@ class RosYoloObjectDetector {
try {
cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
} catch (cv_bridge::Exception& e) {
ROS_ERROR("cv_bridge exception: %s", e.what());
AERROR_F("cv_bridge exception: {}", e.what());
return;
}

Expand All @@ -33,7 +33,7 @@ class RosYoloObjectDetector {

// print results
for (const auto& result : results) {
ROS_INFO_STREAM(result);
AINFO << result;
}
}

Expand Down
18 changes: 9 additions & 9 deletions example/rtsp_yolo_object_detector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@
#include "opencv2/opencv.hpp"
#include "ros/package.h"
#include "ros/ros.h"
#include "zetton_common/stream/cv_gst_stream_source.h"
#include "zetton_inference/detector/yolo_object_detector.h"
#include "zetton_stream/stream/cv_gst_stream_source.h"

#define SHOW_GUI false

Expand All @@ -35,7 +35,7 @@ class RtspYoloObjectDetector {
std::string url_;

std::shared_ptr<zetton::inference::YoloObjectDetector> detector_;
std::shared_ptr<zetton::common::CvGstStreamSource> streamer_;
std::shared_ptr<zetton::stream::CvGstStreamSource> streamer_;

std::atomic<bool> stop_flag_{false};
std::shared_ptr<std::thread> thread_;
Expand Down Expand Up @@ -68,11 +68,11 @@ bool RtspYoloObjectDetector::Open() {
detector_ = std::make_shared<zetton::inference::YoloObjectDetector>();
detector_->Init(config_);
// init streamer
zetton::common::StreamOptions options;
zetton::stream::StreamOptions options;
options.resource = url_;
options.codec = zetton::common::StreamCodec::CODEC_H264;
options.platform = zetton::common::StreamPlatformType::PLATFORM_CPU;
streamer_ = std::make_shared<zetton::common::CvGstStreamSource>();
options.codec = zetton::stream::StreamCodec::CODEC_H264;
options.platform = zetton::stream::StreamPlatformType::PLATFORM_CPU;
streamer_ = std::make_shared<zetton::stream::CvGstStreamSource>();
streamer_->Init(options);

thread_ = std::make_shared<std::thread>([&]() { Process(); });
Expand Down Expand Up @@ -135,7 +135,7 @@ int main(int argc, char** argv) {
detector.SetHeightLimitation(50, 1920);

// start
ROS_INFO("Starting detection");
AINFO_F("Starting detection");
while (detector.IsOpened()) {
cv::Mat frame;
zetton::inference::ObjectDetectionResults results;
Expand All @@ -144,7 +144,7 @@ int main(int argc, char** argv) {
detector.Capture(frame, results);
// print results
for (const auto& result : results) {
ROS_INFO_STREAM(result);
AINFO << result;
}
// show results in GUI
if (SHOW_GUI) {
Expand All @@ -154,7 +154,7 @@ int main(int argc, char** argv) {
cv::imshow("Results", frame);
char key = cv::waitKey(10);
if (key == 27) {
ROS_INFO("Stopping detection");
AINFO_F("Stopping detection");
break;
}
}
Expand Down
11 changes: 7 additions & 4 deletions include/zetton_inference/tracker/mot/association_type.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@

#include <ros/ros.h>

#include "zetton_common/util/log.h"

namespace zetton {
namespace inference {
namespace tracker {
Expand Down Expand Up @@ -50,10 +52,11 @@ class AssociationVector {
}

void report() {
ROS_INFO("Data Association Report:");
for (auto ass : ass_vector)
ROS_INFO_STREAM("id: " << ass.id << " | score: " << ass.score);
ROS_INFO(" ");
AINFO_F("Data Association Report:");
for (auto ass : ass_vector) {
AINFO_F("id: {} | score: {}", ass.id, ass.score);
}
AINFO_F(" ");
}

std::vector<AssociationType> ass_vector;
Expand Down
5 changes: 3 additions & 2 deletions include/zetton_inference/tracker/mot/util.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@
#include <Eigen/Dense>
#include <string>

#include "zetton_common/util/log.h"

namespace zetton {
namespace inference {
namespace tracker {
Expand Down Expand Up @@ -50,8 +52,7 @@ inline std::vector<Eigen::VectorXf> feature_vector_to_eigen(
}

inline void print_bbox(cv::Rect2d bbox) {
ROS_INFO_STREAM("Bbox Info: " << bbox.x << ", " << bbox.y << ", "
<< bbox.width << ", " << bbox.height);
AINFO_F("Bbox Info: {},{},{},{}", bbox.x, bbox.y, bbox.width, bbox.height);
}

inline double cal_bbox_overlap_ratio(cv::Rect2d track_bbox,
Expand Down
1 change: 1 addition & 0 deletions include/zetton_inference/tracker/mot_tracker.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

#include <std_msgs/UInt16MultiArray.h>

#include "zetton_common/util/log.h"
#include "zetton_inference/interface/base_object_detector.h"
#include "zetton_inference/interface/base_object_tracker.h"
#include "zetton_inference/tracker/mot/association_type.h"
Expand Down
1 change: 1 addition & 0 deletions include/zetton_inference/tracker/sort_tracker.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#pragma once

#include "ros/ros.h"
#include "zetton_inference/interface/base_object_detector.h"
#include "zetton_inference/interface/base_object_tracker.h"
#include "zetton_inference/tracker/sort/hungarian.h"
Expand Down
2 changes: 2 additions & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<build_depend>sensor_msgs</build_depend>
<build_depend>message_generation</build_depend>
<build_depend>zetton_common</build_depend>
<build_depend>zetton_stream</build_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>roslib</exec_depend>
Expand All @@ -24,4 +25,5 @@
<exec_depend>message_generation</exec_depend>
<exec_depend>message_runtime</exec_depend>
<exec_depend>zetton_common</exec_depend>
<exec_depend>zetton_stream</exec_depend>
</package>
4 changes: 2 additions & 2 deletions src/zetton_inference/detector/yolo_object_detector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ bool YoloObjectDetector::Init(const std::string& param_uri,
} else if (net_type == "YOLOV4_TINY") {
config_.net_type = yolo_trt::ModelType::YOLOV4_TINY;
} else {
ROS_ERROR_STREAM("Unsupported net type: " << net_type);
AERROR_F("Unsupported net type: {}", net_type);
return false;
}
auto precision = static_cast<std::string>(params["inference_precision"]);
Expand All @@ -37,7 +37,7 @@ bool YoloObjectDetector::Init(const std::string& param_uri,
package_path +
static_cast<std::string>(params["calibration_image_list_file_txt"]);
} else {
ROS_ERROR_STREAM("Unsupported inference precision: " << precision);
AERROR_F("Unsupported inference precision: {}", precision);
return false;
}

Expand Down
2 changes: 1 addition & 1 deletion src/zetton_inference/tracker/mot/local_object.cc
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ void LocalObject::track_bbox_by_optical_flow(const ros::Time &time_now) {
tracking_fail_count = 0;
} else {
tracking_fail_count++;
ROS_INFO_STREAM("Object " << id << " tracking failure detected!");
AINFO_F("Object {} tracking failure detected!", id);
}

// update the bbox last updated time
Expand Down
Loading

0 comments on commit 2b7534d

Please sign in to comment.