5 #include <rosgraph_msgs/Clock.h> 8 #include <controller_manager/controller_manager.h> 12 int main(
int argc,
char **argv)
14 ros::init(argc, argv,
"four_wheel_steering");
23 controller_manager::ControllerManager cm(&robot, nh);
30 boost::chrono::system_clock::time_point begin = boost::chrono::system_clock::now();
31 boost::chrono::system_clock::time_point end = boost::chrono::system_clock::now();
35 double elapsed_secs = 0;
39 begin = boost::chrono::system_clock::now();
42 cm.update(internal_time, dt);
45 end = boost::chrono::system_clock::now();
47 elapsed_secs = boost::chrono::duration_cast<boost::chrono::duration<double> >((end - begin)).count();
49 if (dt.
toSec() - elapsed_secs < 0.0)
52 0.1,
"Control cycle is taking to much time, elapsed: " << elapsed_secs);
57 usleep((dt.
toSec() - elapsed_secs) * 1e6);
60 rosgraph_msgs::Clock clock;
#define ROS_DEBUG_STREAM_THROTTLE(rate, args)
int main(int argc, char **argv)
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