Skip to content
Snippets Groups Projects
Commit 4d0b120f authored by Fernando Herrero's avatar Fernando Herrero
Browse files

Use setRate() instead of loop_rate

parent b36ccae8
No related branches found
No related tags found
No related merge requests found
...@@ -82,7 +82,9 @@ void DynamicTransformPublisherAlgNode::node_config_update(Config &config, uint32 ...@@ -82,7 +82,9 @@ void DynamicTransformPublisherAlgNode::node_config_update(Config &config, uint32
geometry_msgs::Quaternion q = tf::createQuaternionMsgFromRollPitchYaw(config.roll,config.pitch,config.yaw); geometry_msgs::Quaternion q = tf::createQuaternionMsgFromRollPitchYaw(config.roll,config.pitch,config.yaw);
t.rotation = q; t.rotation = q;
this->transform.transform = t; this->transform.transform = t;
this->loop_rate_ = 1000.0/config.period;
this->setRate(1000.0/config.period);
//this->loop_rate_ = 1000.0/config.period;
if(config.show_rosrun) if(config.show_rosrun)
{ {
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment