Public Member Functions | Protected Member Functions | Private Attributes
generic_control_toolbox::RosControlInterface< JointInterface > Class Template Reference

#include <ros_control_interface.hpp>

Inheritance diagram for generic_control_toolbox::RosControlInterface< JointInterface >:
Inheritance graph
[legend]

List of all members.

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< ControllerBasecontroller_
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_

Detailed Description

template<class JointInterface>
class generic_control_toolbox::RosControlInterface< JointInterface >

Embeds a ControllerBase within the ros control architecture.

Definition at line 22 of file ros_control_interface.hpp.


Constructor & Destructor Documentation

template<class JointInterface >
generic_control_toolbox::RosControlInterface< JointInterface >::RosControlInterface ( )

Definition at line 57 of file ros_control_interface.hpp.


Member Function Documentation

template<class JointInterface >
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.

template<class JointInterface >
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.

Parameters:
nhThe NodeHandle provided by ROS control with the namespace of the controller.
Returns:
A shared pointer to the instantiated controller base
template<class JointInterface >
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.

template<class JointInterface >
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.

template<class JointInterface >
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.


Member Data Documentation

template<class JointInterface >
std::shared_ptr<ControllerBase> generic_control_toolbox::RosControlInterface< JointInterface >::controller_ [private]

Definition at line 46 of file ros_control_interface.hpp.

template<class JointInterface >
std::vector<std::string> generic_control_toolbox::RosControlInterface< JointInterface >::joint_names_ [private]

Definition at line 49 of file ros_control_interface.hpp.

template<class JointInterface >
JointType generic_control_toolbox::RosControlInterface< JointInterface >::joint_type_ [private]

Definition at line 47 of file ros_control_interface.hpp.

template<class JointInterface >
std::vector<urdf::JointConstSharedPtr> generic_control_toolbox::RosControlInterface< JointInterface >::joint_urdfs_ [private]

Definition at line 50 of file ros_control_interface.hpp.

template<class JointInterface >
std::vector<hardware_interface::JointHandle> generic_control_toolbox::RosControlInterface< JointInterface >::joints_ [private]

Definition at line 51 of file ros_control_interface.hpp.

template<class JointInterface >
unsigned int generic_control_toolbox::RosControlInterface< JointInterface >::n_joints_ [private]

Definition at line 48 of file ros_control_interface.hpp.


The documentation for this class was generated from the following file:


generic_control_toolbox
Author(s): diogo
autogenerated on Thu Jun 6 2019 18:02:57