change in loop rate while in update mode
This commit is contained in:
parent
4dbd506fbb
commit
6fc6d91ddb
|
@ -68,9 +68,16 @@ namespace rosbzz_node{
|
||||||
/*run once*/
|
/*run once*/
|
||||||
ros::spinOnce();
|
ros::spinOnce();
|
||||||
/*loop rate of ros*/
|
/*loop rate of ros*/
|
||||||
ros::Rate loop_rate(10);
|
if( get_update_mode() == CODE_STANDBY){
|
||||||
/*sleep for the mentioned loop rate*/
|
ros::Rate loop_rate(2);
|
||||||
loop_rate.sleep();
|
loop_rate.sleep();
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
ros::Rate loop_rate(10);
|
||||||
|
loop_rate.sleep();
|
||||||
|
}
|
||||||
|
/*sleep for the mentioned loop rate*/
|
||||||
|
|
||||||
timer_step+=1;
|
timer_step+=1;
|
||||||
maintain_pos(timer_step);
|
maintain_pos(timer_step);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue