Looprate setting bug fix.
This commit is contained in:
parent
7830235c78
commit
b41a086ede
|
@ -197,7 +197,7 @@ void roscontroller::RosControllerRun()
|
||||||
std::string standby_bo = Compile_bzz(stand_by) + ".bo";
|
std::string standby_bo = Compile_bzz(stand_by) + ".bo";
|
||||||
//init_update_monitor(bcfname.c_str(), standby_bo.c_str());
|
//init_update_monitor(bcfname.c_str(), standby_bo.c_str());
|
||||||
/*loop rate of ros*/
|
/*loop rate of ros*/
|
||||||
ros::Rate loop_rate(15);
|
ros::Rate loop_rate(BUZZRATE);
|
||||||
///////////////////////////////////////////////////////
|
///////////////////////////////////////////////////////
|
||||||
// MAIN LOOP
|
// MAIN LOOP
|
||||||
//////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////
|
||||||
|
@ -295,8 +295,6 @@ void roscontroller::RosControllerRun()
|
||||||
get_xbee_status();
|
get_xbee_status();
|
||||||
/*run once*/
|
/*run once*/
|
||||||
ros::spinOnce();
|
ros::spinOnce();
|
||||||
/*loop rate of ros*/
|
|
||||||
ros::Rate loop_rate(BUZZRATE);
|
|
||||||
loop_rate.sleep();
|
loop_rate.sleep();
|
||||||
if (fcu_timeout <= 0)
|
if (fcu_timeout <= 0)
|
||||||
buzzuav_closures::rc_call(mavros_msgs::CommandCode::NAV_LAND);
|
buzzuav_closures::rc_call(mavros_msgs::CommandCode::NAV_LAND);
|
||||||
|
|
Loading…
Reference in New Issue