#include <ros_control_interface.hpp>
Public Member Functions | |
bool | init (JointInterface *hw, ros::NodeHandle &nh) |
RosControlInterface () | |
void | starting (const ros::Time &time) |
void | stopping (const ros::Time &time) |
void | update (const ros::Time &time, const ros::Duration &period) |
Protected Member Functions | |
virtual std::shared_ptr < ControllerBase > | initController (ros::NodeHandle &nh) const =0 |
Private Attributes | |
std::shared_ptr< ControllerBase > | controller_ |
std::vector< std::string > | joint_names_ |
JointType | joint_type_ |
std::vector < urdf::JointConstSharedPtr > | joint_urdfs_ |
std::vector < hardware_interface::JointHandle > | joints_ |
unsigned int | n_joints_ |
Embeds a ControllerBase within the ros control architecture.
Definition at line 22 of file ros_control_interface.hpp.
generic_control_toolbox::RosControlInterface< JointInterface >::RosControlInterface | ( | ) |
Definition at line 57 of file ros_control_interface.hpp.
bool generic_control_toolbox::RosControlInterface< JointInterface >::init | ( | JointInterface * | hw, |
ros::NodeHandle & | nh | ||
) | [virtual] |
Reimplemented from controller_interface::Controller< JointInterface >.
Definition at line 85 of file ros_control_interface.hpp.
virtual std::shared_ptr<ControllerBase> generic_control_toolbox::RosControlInterface< JointInterface >::initController | ( | ros::NodeHandle & | nh | ) | const [protected, pure virtual] |
Initializes an instance of a Controller base to be embedded within ROS Control.
nh | The NodeHandle provided by ROS control with the namespace of the controller. |
void generic_control_toolbox::RosControlInterface< JointInterface >::starting | ( | const ros::Time & | time | ) | [virtual] |
Reimplemented from controller_interface::ControllerBase.
Definition at line 135 of file ros_control_interface.hpp.
void generic_control_toolbox::RosControlInterface< JointInterface >::stopping | ( | const ros::Time & | time | ) | [virtual] |
Reimplemented from controller_interface::ControllerBase.
Definition at line 182 of file ros_control_interface.hpp.
void generic_control_toolbox::RosControlInterface< JointInterface >::update | ( | const ros::Time & | time, |
const ros::Duration & | period | ||
) | [virtual] |
Implements controller_interface::ControllerBase.
Definition at line 141 of file ros_control_interface.hpp.
std::shared_ptr<ControllerBase> generic_control_toolbox::RosControlInterface< JointInterface >::controller_ [private] |
Definition at line 46 of file ros_control_interface.hpp.
std::vector<std::string> generic_control_toolbox::RosControlInterface< JointInterface >::joint_names_ [private] |
Definition at line 49 of file ros_control_interface.hpp.
JointType generic_control_toolbox::RosControlInterface< JointInterface >::joint_type_ [private] |
Definition at line 47 of file ros_control_interface.hpp.
std::vector<urdf::JointConstSharedPtr> generic_control_toolbox::RosControlInterface< JointInterface >::joint_urdfs_ [private] |
Definition at line 50 of file ros_control_interface.hpp.
std::vector<hardware_interface::JointHandle> generic_control_toolbox::RosControlInterface< JointInterface >::joints_ [private] |
Definition at line 51 of file ros_control_interface.hpp.
unsigned int generic_control_toolbox::RosControlInterface< JointInterface >::n_joints_ [private] |
Definition at line 48 of file ros_control_interface.hpp.