Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #include <ros_control_boilerplate/generic_hw_control_loop.h>
00041
00042
00043 #include <rosparam_shortcuts/rosparam_shortcuts.h>
00044
00045 namespace ros_control_boilerplate
00046 {
00047 GenericHWControlLoop::GenericHWControlLoop(
00048 ros::NodeHandle& nh, boost::shared_ptr<ros_control_boilerplate::GenericHWInterface> hardware_interface)
00049 : nh_(nh), hardware_interface_(hardware_interface)
00050 {
00051
00052 controller_manager_.reset(new controller_manager::ControllerManager(hardware_interface_.get(), nh_));
00053
00054
00055 ros::NodeHandle rpsnh(nh, name_);
00056 std::size_t error = 0;
00057 error += !rosparam_shortcuts::get(name_, rpsnh, "loop_hz", loop_hz_);
00058 error += !rosparam_shortcuts::get(name_, rpsnh, "cycle_time_error_threshold", cycle_time_error_threshold_);
00059 rosparam_shortcuts::shutdownIfError(name_, error);
00060
00061
00062 clock_gettime(CLOCK_MONOTONIC, &last_time_);
00063
00064
00065 ros::Duration desired_update_freq = ros::Duration(1 / loop_hz_);
00066 non_realtime_loop_ = nh_.createTimer(desired_update_freq, &GenericHWControlLoop::update, this);
00067 }
00068
00069 void GenericHWControlLoop::update(const ros::TimerEvent& e)
00070 {
00071
00072 clock_gettime(CLOCK_MONOTONIC, ¤t_time_);
00073 elapsed_time_ =
00074 ros::Duration(current_time_.tv_sec - last_time_.tv_sec + (current_time_.tv_nsec - last_time_.tv_nsec) / BILLION);
00075 last_time_ = current_time_;
00076
00077
00078
00079
00080 const double cycle_time_error = (elapsed_time_ - desired_update_freq_).toSec();
00081 if (cycle_time_error > cycle_time_error_threshold_)
00082 {
00083 ROS_WARN_STREAM_NAMED(name_, "Cycle time exceeded error threshold by: "
00084 << cycle_time_error << ", cycle time: " << elapsed_time_
00085 << ", threshold: " << cycle_time_error_threshold_);
00086 }
00087
00088
00089 hardware_interface_->read(elapsed_time_);
00090
00091
00092 controller_manager_->update(ros::Time::now(), elapsed_time_);
00093
00094
00095 hardware_interface_->write(elapsed_time_);
00096 }
00097
00098 }