Skip to content

Commit

Permalink
Merge pull request #233 from CPFL/fix_high_CPU_occupancy
Browse files Browse the repository at this point in the history
Add sleep command to decrease CPU occupancy
  • Loading branch information
manato committed Feb 9, 2016
2 parents dbb4c6d + b1e531f commit bdc66ac
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,8 @@

using namespace std;

static constexpr double LOOP_RATE = 15.0;

typedef struct _OBJPOS{
int x1;
int y1;
Expand Down Expand Up @@ -378,6 +380,7 @@ int main(int argc, char **argv){
ndtGetFlag = false;

tf::TransformListener listener;
ros::Rate loop_rate(LOOP_RATE); // Try to loop in "LOOP_RATE" [Hz]
while(n.ok())
{
/* try to get coordinate system conversion from "camera" to "map" */
Expand All @@ -390,6 +393,7 @@ int main(int argc, char **argv){
}

ros::spinOnce();
loop_rate.sleep();

}
return 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
static constexpr uint32_t SUBSCRIBE_QUEUE_SIZE = 100;
static constexpr uint32_t ADVERTISE_QUEUE_SIZE = 10;
static constexpr bool ADVERTISE_LATCH = false;
static constexpr double LOOP_RATE = 15.0;

ros::Publisher obj_pose_pub;

Expand Down Expand Up @@ -173,7 +174,7 @@ int main(int argc, char* argv[])
obj_pose_pub = n.advertise<visualization_msgs::MarkerArray>("obj_pose", ADVERTISE_QUEUE_SIZE, ADVERTISE_LATCH);

tf::TransformListener trf_listener;

ros::Rate loop_rate(LOOP_RATE); // Try to loop in "LOOP_RATE" [Hz]
while (n.ok())
{
try {
Expand All @@ -185,6 +186,7 @@ int main(int argc, char* argv[])
}

ros::spinOnce();
loop_rate.sleep();
}

return 0;
Expand Down

0 comments on commit bdc66ac

Please sign in to comment.