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

Jw add cuda dependency #210

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
2 changes: 1 addition & 1 deletion darknet_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ project(darknet_ros)

# Set c++11 cmake flags
set(CMAKE_CXX_FLAGS "-std=c++11 ${CMAKE_CXX_FLAGS}")
set(CMAKE_C_FLAGS "-Wall -Wno-unused-result -Wno-unknown-pragmas -Wno-unused-variable -Wfatal-errors -fPIC ${CMAKE_C_FLAGS}")
set(CMAKE_C_FLAGS "-Wall -Wno-unused-result -Wno-unknown-pragmas -Wno-unused-variable -Wfatal-errors -Wno-deprecated-declarations -fPIC ${CMAKE_C_FLAGS}")

# Define path of darknet folder here.
find_path(DARKNET_PATH
Expand Down
18 changes: 6 additions & 12 deletions darknet_ros/include/darknet_ros/YoloObjectDetector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,23 +214,17 @@ class YoloObjectDetector
int actionId_;
boost::shared_mutex mutexActionStatus_;

// double getWallTime();

int sizeNetwork(network *net);

void rememberNetwork(network *net);

detection *avgPredictions(network *net, int *nboxes);

void *detectInThread();

void *fetchInThread();

void *displayInThread(void *ptr);
void detectInThread();

void *displayLoop(void *ptr);
void fetchInThread();

void *detectLoop(void *ptr);
void displayInThread();

void setupNetwork(char *cfgfile, char *weightfile, char *datafile, float thresh,
char **names, int classes,
Expand All @@ -241,11 +235,11 @@ class YoloObjectDetector

IplImageWithHeader_ getIplImageWithHeader();

bool getImageStatus(void);
bool getImageStatus();

bool isNodeRunning(void);
bool isNodeRunning();

void *publishInThread();
void publishInThread();
};

} /* namespace darknet_ros*/
2 changes: 1 addition & 1 deletion darknet_ros/launch/darknet_ros.launch
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
<rosparam command="load" ns="darknet_ros" file="$(arg network_param_file)"/>

<!-- Start darknet and ros wrapper -->
<node pkg="darknet_ros" type="darknet_ros" name="darknet_ros" output="screen" launch-prefix="$(arg launch_prefix)">
<node pkg="darknet_ros" type="darknet_ros" name="darknet_ros" output="log" launch-prefix="$(arg launch_prefix)">
<param name="weights_path" value="$(arg yolo_weights_path)" />
<param name="config_path" value="$(arg yolo_config_path)" />
</node>
Expand Down
60 changes: 20 additions & 40 deletions darknet_ros/src/YoloObjectDetector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,6 @@ void YoloObjectDetector::cameraCallback(const sensor_msgs::ImageConstPtr& msg)
frameWidth_ = cam_image->image.size().width;
frameHeight_ = cam_image->image.size().height;
}
return;
}

void YoloObjectDetector::checkForObjectsActionGoalCB()
Expand Down Expand Up @@ -241,7 +240,6 @@ void YoloObjectDetector::checkForObjectsActionGoalCB()
frameWidth_ = cam_image->image.size().width;
frameHeight_ = cam_image->image.size().height;
}
return;
}

void YoloObjectDetector::checkForObjectsActionPreemptCB()
Expand Down Expand Up @@ -270,15 +268,6 @@ bool YoloObjectDetector::publishDetectionImage(const cv::Mat& detectionImage)
return true;
}

// double YoloObjectDetector::getWallTime()
// {
// struct timeval time;
// if (gettimeofday(&time, NULL)) {
// return 0;
// }
// return (double) time.tv_sec + (double) time.tv_usec * .000001;
// }

int YoloObjectDetector::sizeNetwork(network *net)
{
int i;
Expand Down Expand Up @@ -311,7 +300,7 @@ detection *YoloObjectDetector::avgPredictions(network *net, int *nboxes)
int count = 0;
fill_cpu(demoTotal_, 0, avg_, 1);
for(j = 0; j < demoFrame_; ++j){
axpy_cpu(demoTotal_, 1./demoFrame_, predictions_[j], 1, avg_, 1);
axpy_cpu(demoTotal_, 1.f/demoFrame_, predictions_[j], 1, avg_, 1);
}
for(i = 0; i < net->n; ++i){
layer l = net->layers[i];
Expand All @@ -324,7 +313,7 @@ detection *YoloObjectDetector::avgPredictions(network *net, int *nboxes)
return dets;
}

void *YoloObjectDetector::detectInThread()
void YoloObjectDetector::detectInThread()
{
running_ = 1;
float nms = .4;
Expand Down Expand Up @@ -401,10 +390,9 @@ void *YoloObjectDetector::detectInThread()
free_detections(dets, nboxes);
demoIndex_ = (demoIndex_ + 1) % demoFrame_;
running_ = 0;
return 0;
}

void *YoloObjectDetector::fetchInThread()
void YoloObjectDetector::fetchInThread()
{
IplImageWithHeader_ imageAndHeader = getIplImageWithHeader();
IplImage* ROS_img = imageAndHeader.image;
Expand All @@ -416,17 +404,16 @@ void *YoloObjectDetector::fetchInThread()
}
rgbgr_image(buff_[buffIndex_]);
letterbox_image_into(buff_[buffIndex_], net_->w, net_->h, buffLetter_[buffIndex_]);
return 0;
}

void *YoloObjectDetector::displayInThread(void *ptr)
void YoloObjectDetector::displayInThread()
{
show_image_cv(buff_[(buffIndex_ + 1)%3], "YOLO V3", ipl_);
int c = cvWaitKey(waitKeyDelay_);
if (c != -1) c = c%256;
if (c == 27) {
demoDone_ = 1;
return 0;
return;
} else if (c == 82) {
demoThresh_ += .02;
} else if (c == 84) {
Expand All @@ -438,21 +425,6 @@ void *YoloObjectDetector::displayInThread(void *ptr)
demoHier_ -= .02;
if(demoHier_ <= .0) demoHier_ = .0;
}
return 0;
}

void *YoloObjectDetector::displayLoop(void *ptr)
{
while (1) {
displayInThread(0);
}
}

void *YoloObjectDetector::detectLoop(void *ptr)
{
while (1) {
detectInThread();
}
}

void YoloObjectDetector::setupNetwork(char *cfgfile, char *weightfile, char *datafile, float thresh,
Expand Down Expand Up @@ -534,10 +506,20 @@ void YoloObjectDetector::yolo()
fetch_thread = std::thread(&YoloObjectDetector::fetchInThread, this);
detect_thread = std::thread(&YoloObjectDetector::detectInThread, this);
if (!demoPrefix_) {
fps_ = 1./(what_time_is_it_now() - demoTime_);
fps_ = 1.f/(what_time_is_it_now() - demoTime_);
demoTime_ = what_time_is_it_now();
if (viewImage_) {
displayInThread(0);
displayInThread();
} else {
const auto& p = buff_[(buffIndex_ + 1)%3];
int step = ipl_->widthStep;
for(int y = 0; y < p.h; ++y){
for(int x = 0; x < p.w; ++x){
for(int k= 0; k < p.c; ++k){
ipl_->imageData[y*step + x*p.c + k] = (unsigned char)(p.data[k*p.h*p.w + y*p.w + x]*255);
}
}
}
}
publishInThread();
} else {
Expand All @@ -563,19 +545,19 @@ IplImageWithHeader_ YoloObjectDetector::getIplImageWithHeader()
return header;
}

bool YoloObjectDetector::getImageStatus(void)
bool YoloObjectDetector::getImageStatus()
{
boost::shared_lock<boost::shared_mutex> lock(mutexImageStatus_);
return imageStatus_;
}

bool YoloObjectDetector::isNodeRunning(void)
bool YoloObjectDetector::isNodeRunning()
{
boost::shared_lock<boost::shared_mutex> lock(mutexNodeStatus_);
return isNodeRunning_;
}

void *YoloObjectDetector::publishInThread()
void YoloObjectDetector::publishInThread()
{
// Publish image.
cv::Mat cvImage = cv::cvarrToMat(ipl_);
Expand Down Expand Up @@ -640,8 +622,6 @@ void *YoloObjectDetector::publishInThread()
rosBoxes_[i].clear();
rosBoxCounter_[i] = 0;
}

return 0;
}


Expand Down