Public Member Functions | Protected Member Functions | Private Attributes | List of all members
generic_control_toolbox::RosControlInterface< JointInterface > Class Template Referenceabstract

#include <ros_control_interface.hpp>

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

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 >
virtual bool init (T *, ros::NodeHandle &)
 
virtual bool init (T *, ros::NodeHandle &, ros::NodeHandle &)
 
- Public Member Functions inherited from controller_interface::ControllerBase
virtual void aborting (const ros::Time &)
 
virtual void aborting (const ros::Time &)
 
bool abortRequest (const ros::Time &time)
 
bool abortRequest (const ros::Time &time)
 
 ControllerBase ()=default
 
 ControllerBase (const ControllerBase &)=delete
 
 ControllerBase (ControllerBase &&)=delete
 
bool isAborted () const
 
bool isAborted () const
 
bool isInitialized () const
 
bool isInitialized () const
 
bool isRunning () const
 
bool isRunning () const
 
bool isStopped () const
 
bool isStopped () const
 
bool isWaiting () const
 
bool isWaiting () const
 
ControllerBaseoperator= (const ControllerBase &)=delete
 
ControllerBaseoperator= (ControllerBase &&)=delete
 
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 void waiting (const ros::Time &)
 
virtual void waiting (const ros::Time &)
 
bool waitRequest (const ros::Time &time)
 
bool waitRequest (const ros::Time &time)
 
virtual ~ControllerBase ()=default
 

Protected Member Functions

virtual std::shared_ptr< ControllerBaseinitController (ros::NodeHandle &nh) const =0
 
- Protected Member Functions inherited from controller_interface::Controller< JointInterface >
std::string getHardwareInterfaceType () const
 
bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
 

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::JointHandlejoints_
 
unsigned int n_joints_
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
- Public Attributes inherited from controller_interface::ControllerBase
 ABORTED
 
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 
 STOPPED
 
 WAITING
 

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

◆ RosControlInterface()

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

Definition at line 57 of file ros_control_interface.hpp.

Member Function Documentation

◆ init()

template<class JointInterface >
bool generic_control_toolbox::RosControlInterface< JointInterface >::init ( JointInterface *  hw,
ros::NodeHandle nh 
)

Definition at line 85 of file ros_control_interface.hpp.

◆ initController()

template<class JointInterface >
virtual std::shared_ptr<ControllerBase> generic_control_toolbox::RosControlInterface< JointInterface >::initController ( ros::NodeHandle nh) const
protectedpure 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

◆ starting()

template<class JointInterface >
void generic_control_toolbox::RosControlInterface< JointInterface >::starting ( const ros::Time time)
virtual

Reimplemented from controller_interface::ControllerBase.

Definition at line 143 of file ros_control_interface.hpp.

◆ stopping()

template<class JointInterface >
void generic_control_toolbox::RosControlInterface< JointInterface >::stopping ( const ros::Time time)
virtual

Reimplemented from controller_interface::ControllerBase.

Definition at line 190 of file ros_control_interface.hpp.

◆ update()

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 149 of file ros_control_interface.hpp.

Member Data Documentation

◆ controller_

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

Definition at line 46 of file ros_control_interface.hpp.

◆ joint_names_

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.

◆ joint_type_

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

Definition at line 47 of file ros_control_interface.hpp.

◆ joint_urdfs_

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.

◆ joints_

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.

◆ n_joints_

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 Mon Feb 28 2022 22:24:38