Public Member Functions | Protected Attributes | List of all members
ros_controllers_cartesian::JointBasedController< HWInterface, HandleType > Class Template Reference

A common base class for joint-based control policies. More...

#include <control_policies.h>

Inheritance diagram for ros_controllers_cartesian::JointBasedController< HWInterface, HandleType >:
Inheritance graph
[legend]

Public Member Functions

CartesianState getState () const
 
virtual bool init (hardware_interface::RobotHW *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
 
 JointBasedController ()
 
- Public Member Functions inherited from controller_interface::MultiInterfaceController< T >
virtual bool init (hardware_interface::RobotHW *, ros::NodeHandle &)
 
 MultiInterfaceController (bool allow_optional_interfaces=false)
 
- 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
 
virtual void starting (const ros::Time &)
 
virtual void starting (const ros::Time &)
 
bool startRequest (const ros::Time &time)
 
bool startRequest (const ros::Time &time)
 
virtual void stopping (const ros::Time &)
 
virtual void stopping (const ros::Time &)
 
bool stopRequest (const ros::Time &time)
 
bool stopRequest (const ros::Time &time)
 
virtual void update (const ros::Time &time, const ros::Duration &period)=0
 
virtual void update (const ros::Time &time, const ros::Duration &period)=0
 
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 Attributes

std::unique_ptr< KDL::ChainFkSolverVel_recursivefk_solver_
 
std::vector< HandleType > joint_handles_
 
std::string robot_base_
 
KDL::Chain robot_chain_
 
std::string robot_tip_
 
- Protected Attributes inherited from controller_interface::MultiInterfaceController< T >
bool allow_optional_interfaces_
 
hardware_interface::RobotHW robot_hw_ctrl_
 

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
 
- Protected Member Functions inherited from controller_interface::MultiInterfaceController< T >
bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
 
- Static Protected Member Functions inherited from controller_interface::MultiInterfaceController< T >
static void clearClaims (hardware_interface::RobotHW *robot_hw)
 
static void extractInterfaceResources (hardware_interface::RobotHW *robot_hw_in, hardware_interface::RobotHW *robot_hw_out)
 
static bool hasRequiredInterfaces (hardware_interface::RobotHW *robot_hw)
 
static void populateClaimedResources (hardware_interface::RobotHW *robot_hw, ClaimedResources &claimed_resources)
 

Detailed Description

template<class HWInterface, class HandleType>
class ros_controllers_cartesian::JointBasedController< HWInterface, HandleType >

A common base class for joint-based control policies.

Template Parameters
HWInterfaceThe hardware interface for joint actuation
HandleTypeThe type of joint handles to use.

Definition at line 67 of file control_policies.h.

Constructor & Destructor Documentation

◆ JointBasedController()

template<class HWInterface, class HandleType>
ros_controllers_cartesian::JointBasedController< HWInterface, HandleType >::JointBasedController ( )
inline

Definition at line 70 of file control_policies.h.

Member Function Documentation

◆ getState()

template<class HWInterface , class HandleType >
CartesianState ros_controllers_cartesian::JointBasedController< HWInterface, HandleType >::getState ( ) const

Definition at line 121 of file control_policies.hpp.

◆ init()

template<class HWInterface , class HandleType >
bool ros_controllers_cartesian::JointBasedController< HWInterface, HandleType >::init ( hardware_interface::RobotHW hw,
ros::NodeHandle root_nh,
ros::NodeHandle controller_nh 
)
overridevirtual

Member Data Documentation

◆ fk_solver_

template<class HWInterface, class HandleType>
std::unique_ptr<KDL::ChainFkSolverVel_recursive> ros_controllers_cartesian::JointBasedController< HWInterface, HandleType >::fk_solver_
protected

Definition at line 78 of file control_policies.h.

◆ joint_handles_

template<class HWInterface, class HandleType>
std::vector<HandleType> ros_controllers_cartesian::JointBasedController< HWInterface, HandleType >::joint_handles_
protected

Definition at line 77 of file control_policies.h.

◆ robot_base_

template<class HWInterface, class HandleType>
std::string ros_controllers_cartesian::JointBasedController< HWInterface, HandleType >::robot_base_
protected

Definition at line 80 of file control_policies.h.

◆ robot_chain_

template<class HWInterface, class HandleType>
KDL::Chain ros_controllers_cartesian::JointBasedController< HWInterface, HandleType >::robot_chain_
protected

Definition at line 79 of file control_policies.h.

◆ robot_tip_

template<class HWInterface, class HandleType>
std::string ros_controllers_cartesian::JointBasedController< HWInterface, HandleType >::robot_tip_
protected

Definition at line 81 of file control_policies.h.


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


cartesian_trajectory_controller
Author(s):
autogenerated on Thu Feb 23 2023 03:10:48