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

minor adjustments: use ROS_INFO(), and publish timestamped messages #42

Open
wants to merge 1 commit 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
7 changes: 5 additions & 2 deletions src/node_detectnet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,8 +85,8 @@ void img_callback( const sensor_msgs::ImageConstPtr& input )
{
detectNet::Detection* det = detections + n;

printf("object %i class #%u (%s) confidence=%f\n", n, det->ClassID, net->GetClassDesc(det->ClassID), det->Confidence);
printf("object %i bounding box (%f, %f) (%f, %f) w=%f h=%f\n", n, det->Left, det->Top, det->Right, det->Bottom, det->Width(), det->Height());
ROS_INFO("object %i class #%u (%s) confidence=%f\n", n, det->ClassID, net->GetClassDesc(det->ClassID), det->Confidence);
ROS_INFO("object %i bounding box (%f, %f) (%f, %f) w=%f h=%f\n", n, det->Left, det->Top, det->Right, det->Bottom, det->Width(), det->Height());

// create a detection sub-message
vision_msgs::Detection2D detMsg;
Expand All @@ -112,6 +112,9 @@ void img_callback( const sensor_msgs::ImageConstPtr& input )
msg.detections.push_back(detMsg);
}

// populate timestamp filed in header
msg.header.stamp = ros::Time::now();

// publish the detection message
detection_pub->publish(msg);
}
Expand Down
3 changes: 3 additions & 0 deletions src/node_imagenet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,9 @@ void img_callback( const sensor_msgs::ImageConstPtr& input )
obj.score = confidence;

msg.results.push_back(obj); // TODO optionally add source image to msg

// populate timestamp in header field
msg.header.stamp = ros::Time::now();

// publish the classification message
classify_pub->publish(msg);
Expand Down
3 changes: 3 additions & 0 deletions src/node_segnet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,7 @@ bool publish_overlay( uint32_t width, uint32_t height )
return false;

// publish the message
msg.header.stamp = ros::Time::now();
overlay_pub->publish(msg);
}

Expand All @@ -100,6 +101,7 @@ bool publish_mask_color( uint32_t width, uint32_t height )
return false;

// publish the message
msg.header.stamp = ros::Time::now();
mask_color_pub->publish(msg);
}

Expand All @@ -122,6 +124,7 @@ bool publish_mask_class( uint32_t width, uint32_t height )
return false;

// publish the message
msg.header.stamp = ros::Time::now();
mask_class_pub->publish(msg);
}

Expand Down