Skip to content

Commit

Permalink
Add param 'main_loop_rate' for allowing higher publish rates
Browse files Browse the repository at this point in the history
  • Loading branch information
henningkayser committed Jun 15, 2022
1 parent 9db82d1 commit 7ffdbfb
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 3 deletions.
6 changes: 6 additions & 0 deletions fake_joint_driver/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,12 @@ sliders to set the joint trajectory goals.

# Parameters

- `main_loop_rate`

The internal loop rate at which the robot controls are updated.
This rate is a hard limit for joint state publishers. The default
value is set to 100 Hz.

- `use_robot_description`

When it is true, the driver read the parameter `/robot_description`
Expand Down
9 changes: 6 additions & 3 deletions fake_joint_driver/src/fake_joint_driver_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,15 +24,18 @@ int main(int argc, char **argv)
// Connect to controller manager
controller_manager::ControllerManager cm(&robot, nh);

// Set spin ratge
ros::Rate rate(1.0 / ros::Duration(0.010).toSec());
// Set loop rate
ros::NodeHandle pnh("~");
int loop_rate;
pnh.param<int>("main_loop_rate", loop_rate, 100);
ros::Rate rate(loop_rate);
ros::AsyncSpinner spinner(1);
spinner.start();

while (ros::ok())
{
robot.update();
cm.update(ros::Time::now(), ros::Duration(0.010));
cm.update(ros::Time::now(), rate.expectedCycleTime());
rate.sleep();
}
spinner.stop();
Expand Down

0 comments on commit 7ffdbfb

Please sign in to comment.