From b41a086ede24c213a8264588f36a4403a87b3efa Mon Sep 17 00:00:00 2001 From: vivek-shankar Date: Thu, 7 Sep 2017 18:42:26 -0400 Subject: [PATCH] Looprate setting bug fix. --- src/roscontroller.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/roscontroller.cpp b/src/roscontroller.cpp index 6ecd042..342b0ed 100644 --- a/src/roscontroller.cpp +++ b/src/roscontroller.cpp @@ -197,7 +197,7 @@ void roscontroller::RosControllerRun() std::string standby_bo = Compile_bzz(stand_by) + ".bo"; //init_update_monitor(bcfname.c_str(), standby_bo.c_str()); /*loop rate of ros*/ - ros::Rate loop_rate(15); + ros::Rate loop_rate(BUZZRATE); /////////////////////////////////////////////////////// // MAIN LOOP ////////////////////////////////////////////////////// @@ -295,8 +295,6 @@ void roscontroller::RosControllerRun() get_xbee_status(); /*run once*/ ros::spinOnce(); - /*loop rate of ros*/ - ros::Rate loop_rate(BUZZRATE); loop_rate.sleep(); if (fcu_timeout <= 0) buzzuav_closures::rc_call(mavros_msgs::CommandCode::NAV_LAND);