#include <dynamixel_loop.hpp>
Public Member Functions | |
DynamixelLoop (ros::NodeHandle &nh, boost::shared_ptr< dynamixel::DynamixelHardwareInterface > hardware_interface) | |
void | jsCallback (const sensor_msgs::JointState::ConstPtr &js) |
void | update (const ros::TimerEvent &e) |
Private Attributes | |
boost::shared_ptr< controller_manager::ControllerManager > | _controller_manager |
struct timespec | _current_time |
double | _cycle_time_error_threshold |
ros::Duration | _desired_update_freq |
ros::Duration | _elapsed_time |
boost::shared_ptr< dynamixel::DynamixelHardwareInterface > | _hardware_interface |
Abstract Hardware Interface for your robot. More... | |
struct timespec | _last_time |
double | _loop_hz |
ros::NodeHandle | _nh |
ros::Timer | _non_realtime_loop |
sensor_msgs::JointState | joint_state |
ros::Subscriber | js_sub |
ros::Publisher | torque_pub |
Definition at line 59 of file dynamixel_loop.hpp.
dynamixel::DynamixelLoop::DynamixelLoop | ( | ros::NodeHandle & | nh, |
boost::shared_ptr< dynamixel::DynamixelHardwareInterface > | hardware_interface | ||
) |
Definition at line 47 of file dynamixel_loop.cpp.
void dynamixel::DynamixelLoop::jsCallback | ( | const sensor_msgs::JointState::ConstPtr & | js | ) |
Definition at line 79 of file dynamixel_loop.cpp.
void dynamixel::DynamixelLoop::update | ( | const ros::TimerEvent & | e | ) |
Timed method that reads current hardware's state, runs the controller code once and sends the new commands to the hardware.
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 83 of file dynamixel_loop.cpp.
|
private |
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 dynamixel_loop.hpp.
|
private |
Definition at line 90 of file dynamixel_loop.hpp.
|
private |
Definition at line 81 of file dynamixel_loop.hpp.
|
private |
Definition at line 80 of file dynamixel_loop.hpp.
|
private |
Definition at line 87 of file dynamixel_loop.hpp.
|
private |
Abstract Hardware Interface for your robot.
Definition at line 101 of file dynamixel_loop.hpp.
|
private |
Definition at line 89 of file dynamixel_loop.hpp.
|
private |
Definition at line 88 of file dynamixel_loop.hpp.
|
private |
Definition at line 75 of file dynamixel_loop.hpp.
|
private |
Definition at line 86 of file dynamixel_loop.hpp.
|
private |
Definition at line 77 of file dynamixel_loop.hpp.
|
private |
Definition at line 78 of file dynamixel_loop.hpp.
|
private |
Definition at line 83 of file dynamixel_loop.hpp.