node.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
3 
5 
6 using namespace ros;
7 
8 int main(int argc, char **argv)
9 {
10  init(argc, argv, NODE_NAME);
11  NodeHandle n("~/");
12 
13  double frequency;
14  n.param("frequency", frequency, 100.0);
15  ROS_INFO("Operator will run at %.2f Hz.", frequency);
16 
17  RobotOperator robOp;
18 
19  Rate loopRate(frequency);
20  while(ok())
21  {
22  spinOnce();
23  robOp.executeCommand();
24  loopRate.sleep();
25  if(loopRate.cycleTime() > ros::Duration(1.0 / frequency))
26  ROS_WARN("Missed desired rate of %.2f Hz! Loop actually took %.4f seconds!",frequency, loopRate.cycleTime().toSec());
27  }
28  return 0;
29 }
void executeCommand()
Generates and sends Twist-Message to Robot This is the Operator&#39;s core function and should be called ...
The core of a ROS node to provide purely reactive obstacle avoidance The RobotOperator is supposed to...
Duration cycleTime() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_WARN(...)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
bool sleep()
#define NODE_NAME
Definition: RobotOperator.h:4
int main(int argc, char **argv)
Definition: node.cpp:8
ROSCPP_DECL void spinOnce()


nav2d_operator
Author(s): Sebastian Kasperski
autogenerated on Thu Jun 6 2019 19:20:40