The control loop - repeatidly calls read() and write() to the hardware interface at a specified frequency We use MONOTONIC time to ensure robustness in the event of system time updates/change. See http://stackoverflow.com/questions/3523442/difference-between-clock-realtime-and-clock-monotonic. More...
#include <generic_hw_control_loop.h>
Public Member Functions | |
GenericHWControlLoop (ros::NodeHandle &nh, boost::shared_ptr< ros_control_boilerplate::GenericHWInterface > hardware_interface) | |
Constructor. | |
void | update (const ros::TimerEvent &e) |
Timer event Note: we do not use the TimerEvent time difference because it does NOT guarantee that the time source is strictly linearly increasing. | |
Protected Attributes | |
boost::shared_ptr < controller_manager::ControllerManager > | controller_manager_ |
ROS Controller Manager and Runner. | |
struct timespec | current_time_ |
double | cycle_time_error_threshold_ |
ros::Duration | desired_update_freq_ |
ros::Duration | elapsed_time_ |
boost::shared_ptr < ros_control_boilerplate::GenericHWInterface > | hardware_interface_ |
Abstract Hardware Interface for your robot. | |
struct timespec | last_time_ |
double | loop_hz_ |
std::string | name_ = "generic_hw_control_loop" |
ros::NodeHandle | nh_ |
ros::Timer | non_realtime_loop_ |
The control loop - repeatidly calls read() and write() to the hardware interface at a specified frequency We use MONOTONIC time to ensure robustness in the event of system time updates/change. See http://stackoverflow.com/questions/3523442/difference-between-clock-realtime-and-clock-monotonic.
Definition at line 55 of file generic_hw_control_loop.h.
ros_control_boilerplate::GenericHWControlLoop::GenericHWControlLoop | ( | ros::NodeHandle & | nh, |
boost::shared_ptr< ros_control_boilerplate::GenericHWInterface > | hardware_interface | ||
) |
Constructor.
NodeHandle | |
hardware_interface | - the robot-specific hardware interface to be use with your robot |
Definition at line 47 of file generic_hw_control_loop.cpp.
void ros_control_boilerplate::GenericHWControlLoop::update | ( | const ros::TimerEvent & | e | ) |
Timer event Note: we do not use the TimerEvent time difference because it does NOT guarantee that the time source is strictly linearly increasing.
Definition at line 69 of file generic_hw_control_loop.cpp.
boost::shared_ptr<controller_manager::ControllerManager> ros_control_boilerplate::GenericHWControlLoop::controller_manager_ [protected] |
ROS Controller Manager and Runner.
This class advertises a ROS interface for loading, unloading, starting, and stopping ros_control-based controllers. It also serializes execution of all running controllers in update.
Definition at line 98 of file generic_hw_control_loop.h.
struct timespec ros_control_boilerplate::GenericHWControlLoop::current_time_ [protected] |
Definition at line 90 of file generic_hw_control_loop.h.
double ros_control_boilerplate::GenericHWControlLoop::cycle_time_error_threshold_ [protected] |
Definition at line 83 of file generic_hw_control_loop.h.
Definition at line 82 of file generic_hw_control_loop.h.
Definition at line 87 of file generic_hw_control_loop.h.
boost::shared_ptr<ros_control_boilerplate::GenericHWInterface> ros_control_boilerplate::GenericHWControlLoop::hardware_interface_ [protected] |
Abstract Hardware Interface for your robot.
Definition at line 101 of file generic_hw_control_loop.h.
struct timespec ros_control_boilerplate::GenericHWControlLoop::last_time_ [protected] |
Definition at line 89 of file generic_hw_control_loop.h.
double ros_control_boilerplate::GenericHWControlLoop::loop_hz_ [protected] |
Definition at line 88 of file generic_hw_control_loop.h.
std::string ros_control_boilerplate::GenericHWControlLoop::name_ = "generic_hw_control_loop" [protected] |
Definition at line 79 of file generic_hw_control_loop.h.
Definition at line 76 of file generic_hw_control_loop.h.
Definition at line 86 of file generic_hw_control_loop.h.