Skip to content

Commit d960019

Browse files
more const&
1 parent a3137f1 commit d960019

File tree

2 files changed

+7
-9
lines changed

2 files changed

+7
-9
lines changed

src/extended_object_detection_node/eod_node.cpp

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,7 @@
99
#include <geometry_msgs/TransformStamped.h>
1010

1111

12-
geometry_msgs::Vector3 fromCvVector(cv::Vec3d cv_vector){
12+
geometry_msgs::Vector3 fromCvVector(const cv::Vec3d& cv_vector){
1313
geometry_msgs::Vector3 ros_vector;
1414
ros_vector.x = cv_vector[0];
1515
ros_vector.y = cv_vector[1];
@@ -132,14 +132,14 @@ EOD_ROS::EOD_ROS(ros::NodeHandle nh, ros::NodeHandle nh_p){
132132
}
133133

134134

135-
bool EOD_ROS::check_time(ros::Time stamp){
135+
bool EOD_ROS::check_time(const ros::Time& stamp){
136136
if( frame_sequence == 0)
137137
return true;
138138
return (stamp - prev_detected_time).toSec() > rate_limit_sec;
139139
}
140140

141141

142-
bool EOD_ROS::check_lag(ros::Time stamp, double& lag){
142+
bool EOD_ROS::check_lag(const ros::Time& stamp, double& lag){
143143
if( allowed_lag_sec == 0)
144144
return true;
145145
lag = (ros::Time::now() - stamp).toSec();
@@ -214,14 +214,12 @@ void EOD_ROS::rgbd_info_cb(const sensor_msgs::ImageConstPtr& rgb_image, const se
214214
return;
215215
}
216216
cv::Mat depth;
217-
if (depth_image->encoding == sensor_msgs::image_encodings::TYPE_16UC1){
218-
//ROS_INFO("Depth encoding is 16uc1");
217+
if (depth_image->encoding == sensor_msgs::image_encodings::TYPE_16UC1){
219218
depth = cv_bridge::toCvCopy(depth_image, sensor_msgs::image_encodings::TYPE_16UC1)->image;
220219
depth.convertTo(depth, CV_32F);
221220
depth *= 0.001f;
222221
}
223-
else if(depth_image->encoding == sensor_msgs::image_encodings::TYPE_32FC1){
224-
//ROS_INFO("Depth encoding is 32fc1");
222+
else if(depth_image->encoding == sensor_msgs::image_encodings::TYPE_32FC1){
225223
depth = cv_bridge::toCvCopy(depth_image, sensor_msgs::image_encodings::TYPE_32FC1)->image;
226224
}
227225
else{

src/extended_object_detection_node/eod_node.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -95,8 +95,8 @@ class EOD_ROS{
9595
// functions
9696
//void detect(const cv::Mat& rgb, const cv::Mat& depth, std_msgs::Header header);
9797
void detect(const eod::InfoImage& rgb, const eod::InfoImage& depth, std_msgs::Header header);
98-
bool check_time(ros::Time stamp);
99-
bool check_lag(ros::Time stamp, double &lag);
98+
bool check_time(const ros::Time& stamp);
99+
bool check_lag(const ros::Time& stamp, double &lag);
100100
//void add_data_to_simple_msg( eod::SimpleObject*, extended_object_detection::SimpleObjectArray& msg, const cv::Mat& K);
101101
extended_object_detection::BaseObject eoi_to_base_object(std::string name, int id, eod::ExtendedObjectInfo* eoi, const cv::Mat& K);
102102
cv::Mat getK(const sensor_msgs::CameraInfoConstPtr& info_msg);

0 commit comments

Comments
 (0)