33 #include <controller_manager/controller_manager.h> 35 #include <rosgraph_msgs/Clock.h> 37 int main(
int argc,
char **argv)
47 controller_manager::ControllerManager cm(&robot, nh);
55 std::chrono::system_clock::time_point begin = std::chrono::system_clock::now();
56 std::chrono::system_clock::time_point end = std::chrono::system_clock::now();
60 double elapsed_secs = 0;
64 begin = std::chrono::system_clock::now();
67 cm.update(internal_time, dt);
70 end = std::chrono::system_clock::now();
72 elapsed_secs = std::chrono::duration_cast<std::chrono::duration<double> >((end - begin)).count();
74 if (dt.
toSec() - elapsed_secs < 0.0)
77 0.1,
"Control cycle is taking to much time, elapsed: " << elapsed_secs);
82 std::this_thread::sleep_for(std::chrono::duration<double>(dt.
toSec() - elapsed_secs));
85 rosgraph_msgs::Clock clock;
#define ROS_WARN_STREAM_THROTTLE(period, args)
ros::Duration getPeriod() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_DEBUG_STREAM_THROTTLE(period, args)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
int main(int argc, char **argv)