32 #include <rosgraph_msgs/Clock.h> 35 #include <controller_manager/controller_manager.h> 39 int main(
int argc,
char **argv)
50 controller_manager::ControllerManager cm(&robot, nh);
58 boost::chrono::system_clock::time_point begin = boost::chrono::system_clock::now();
59 boost::chrono::system_clock::time_point end = boost::chrono::system_clock::now();
63 double elapsed_secs = 0;
67 begin = boost::chrono::system_clock::now();
70 cm.update(internal_time, dt);
73 end = boost::chrono::system_clock::now();
75 elapsed_secs = boost::chrono::duration_cast<boost::chrono::duration<double> >((end - begin)).count();
77 if (dt.
toSec() - elapsed_secs < 0.0)
80 0.1,
"Control cycle is taking to much time, elapsed: " << elapsed_secs);
85 usleep((dt.
toSec() - elapsed_secs) * 1e6);
88 rosgraph_msgs::Clock clock;
#define ROS_DEBUG_STREAM_THROTTLE(rate, args)
void publish(const boost::shared_ptr< M > &message) const
ros::Duration getPeriod() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
#define ROS_WARN_STREAM_THROTTLE(rate, args)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
int main(int argc, char **argv)