#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) |
Public Member Functions inherited from controller_interface::Controller< JointInterface > | |
Controller () | |
virtual bool | init (JointInterface *, ros::NodeHandle &, ros::NodeHandle &) |
virtual | ~Controller () |
Public Member Functions inherited from controller_interface::ControllerBase | |
ControllerBase () | |
bool | isRunning () |
bool | isRunning () |
bool | startRequest (const ros::Time &time) |
bool | startRequest (const ros::Time &time) |
bool | stopRequest (const ros::Time &time) |
bool | stopRequest (const ros::Time &time) |
void | updateRequest (const ros::Time &time, const ros::Duration &period) |
void | updateRequest (const ros::Time &time, const ros::Duration &period) |
virtual | ~ControllerBase () |
Protected Member Functions | |
virtual std::shared_ptr< ControllerBase > | initController (ros::NodeHandle &nh) const =0 |
Protected Member Functions inherited from controller_interface::Controller< JointInterface > | |
std::string | getHardwareInterfaceType () const |
virtual bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) |
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_ |
Additional Inherited Members | |
Public Types inherited from controller_interface::ControllerBase | |
typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
Public Attributes inherited from controller_interface::ControllerBase | |
CONSTRUCTED | |
INITIALIZED | |
RUNNING | |
enum controller_interface::ControllerBase:: { ... } | state_ |
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.
|
virtual |
Reimplemented from controller_interface::Controller< JointInterface >.
Definition at line 85 of file ros_control_interface.hpp.
|
protectedpure 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. |
|
virtual |
Reimplemented from controller_interface::ControllerBase.
Definition at line 135 of file ros_control_interface.hpp.
|
virtual |
Reimplemented from controller_interface::ControllerBase.
Definition at line 182 of file ros_control_interface.hpp.
|
virtual |
Implements controller_interface::ControllerBase.
Definition at line 141 of file ros_control_interface.hpp.
|
private |
Definition at line 46 of file ros_control_interface.hpp.
|
private |
Definition at line 49 of file ros_control_interface.hpp.
|
private |
Definition at line 47 of file ros_control_interface.hpp.
|
private |
Definition at line 50 of file ros_control_interface.hpp.
|
private |
Definition at line 51 of file ros_control_interface.hpp.
|
private |
Definition at line 48 of file ros_control_interface.hpp.