00001 // NOTE: The contents of this file have been taken largely from the ros_control wiki tutorials 00002 00003 // ROS 00004 #include <ros/ros.h> 00005 00006 // ros_control 00007 #include <controller_manager/controller_manager.h> 00008 00009 #include "ackermann.h" 00010 00011 int main(int argc, char **argv) 00012 { 00013 ros::init(argc, argv, "ackermann"); 00014 ros::NodeHandle nh; 00015 00016 Ackermann robot; 00017 ROS_WARN_STREAM("period: " << robot.getPeriod().toSec()); 00018 controller_manager::ControllerManager cm(&robot, nh); 00019 00020 ros::Rate rate(1.0 / robot.getPeriod().toSec()); 00021 ros::AsyncSpinner spinner(1); 00022 spinner.start(); 00023 while(ros::ok()) 00024 { 00025 robot.read(); 00026 cm.update(robot.getTime(), robot.getPeriod()); 00027 robot.write(); 00028 rate.sleep(); 00029 } 00030 spinner.stop(); 00031 00032 return 0; 00033 }