Skip to content

Commit

Permalink
Update params
Browse files Browse the repository at this point in the history
  • Loading branch information
ajtudela committed Jun 21, 2021
1 parent 1314921 commit 33d1084
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 11 deletions.
5 changes: 1 addition & 4 deletions include/object_detection_openvino/objectDetectionOpenvino.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@

// ROS
#include <ros/ros.h>
#include <std_srvs/Empty.h>
#include <std_msgs/Header.h>
#include <geometry_msgs/Pose.h>
#include <geometry_msgs/Vector3.h>
Expand Down Expand Up @@ -59,7 +58,6 @@ class ObjectDetectionOpenvino{
private:
// ROS related
ros::NodeHandle node_, nodePrivate_;
ros::ServiceServer paramsSrv_;
image_transport::ImageTransport imageTransport_;
image_transport::SubscriberFilter colorSub_, depthSub_;
image_transport::Publisher detectionColorPub_;
Expand All @@ -77,8 +75,7 @@ class ObjectDetectionOpenvino{
float fx_, fy_, cx_, cy_;
bool showFPS_, useDepth_, outputImage_;

void initialize() { std_srvs::Empty empt; updateParams(empt.request, empt.response); }
bool updateParams(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
void getParams();
void infoCallback(const sensor_msgs::CameraInfo::ConstPtr& infoMsg);
void oneImageCallback(sensor_msgs::Image::ConstPtr colorImageMsg);
void twoImageCallback(sensor_msgs::Image::ConstPtr colorImageMsg, sensor_msgs::Image::ConstPtr depthImageMsg);
Expand Down
11 changes: 4 additions & 7 deletions src/objectDetectionOpenvino.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,10 +28,7 @@
ObjectDetectionOpenvino::ObjectDetectionOpenvino(ros::NodeHandle& node, ros::NodeHandle& node_private): node_(node), nodePrivate_(node_private), imageTransport_(nodePrivate_),
syncTwoImage_(SyncPolicyTwoImage(5), colorSub_, depthSub_){
// Initialize ROS parameters
ROS_INFO("[Object detection Openvino]: Reading ROS parameters");
paramsSrv_ = nodePrivate_.advertiseService("params", &ObjectDetectionOpenvino::updateParams, this);

initialize();
getParams();

ROS_INFO_STREAM("[Object detection Openvino]: Loading Inference Engine" << InferenceEngine::GetInferenceEngineVersion());
ROS_INFO_STREAM("[Object detection Openvino]: Device info: " << core_.GetVersions(deviceTarget_));
Expand Down Expand Up @@ -187,7 +184,9 @@ ObjectDetectionOpenvino::~ObjectDetectionOpenvino(){
}

/* Update parameters of the node */
bool ObjectDetectionOpenvino::updateParams(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res){
void ObjectDetectionOpenvino::getParams(){
ROS_INFO("[Object detection Openvino]: Reading ROS parameters");

nodePrivate_.param<float>("model_thresh", thresh_, 0.3);
nodePrivate_.param<float>("model_iou_thresh", iouThresh_, 0.4);

Expand All @@ -206,8 +205,6 @@ bool ObjectDetectionOpenvino::updateParams(std_srvs::Empty::Request &req, std_sr

nodePrivate_.param<bool>("show_fps", showFPS_, false);
nodePrivate_.param<bool>("output_image", outputImage_, true);

return true;
}

/* Camera info Callback */
Expand Down

0 comments on commit 33d1084

Please sign in to comment.