Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
effort_controllers::JointGroupPositionController Class Reference

Forward command controller for a set of effort controlled joints (torque or force). More...

#include <joint_group_position_controller.h>

Inheritance diagram for effort_controllers::JointGroupPositionController:
Inheritance graph
[legend]

Public Member Functions

bool init (hardware_interface::EffortJointInterface *hw, ros::NodeHandle &n)
 
 JointGroupPositionController ()
 Forward command controller for a set of effort controlled joints (torque or force). More...
 
void starting (const ros::Time &)
 
void update (const ros::Time &, const ros::Duration &)
 
 ~JointGroupPositionController ()
 
- Public Member Functions inherited from controller_interface::Controller< hardware_interface::EffortJointInterface >
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)
 
virtual void stopping (const ros::Time &)
 
virtual void stopping (const ros::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
 

Public Attributes

realtime_tools::RealtimeBuffer< std::vector< double > > commands_buffer_
 
std::vector< std::string > joint_names_
 
std::vector< hardware_interface::JointHandlejoints_
 
unsigned int n_joints_
 
- Public Attributes inherited from controller_interface::ControllerBase
ControllerState state_
 

Private Member Functions

void commandCB (const std_msgs::Float64MultiArrayConstPtr &msg)
 
void enforceJointLimits (double &command, unsigned int index)
 

Private Attributes

std::vector< urdf::JointConstSharedPtr > joint_urdfs_
 
std::vector< control_toolbox::Pidpid_controllers_
 
ros::Subscriber sub_command_
 

Additional Inherited Members

- Public Types inherited from controller_interface::ControllerBase
typedef std::vector< hardware_interface::InterfaceResourcesClaimedResources
 
enum  ControllerState {
  ControllerState::CONSTRUCTED, ControllerState::INITIALIZED, ControllerState::RUNNING, ControllerState::STOPPED,
  ControllerState::WAITING, ControllerState::ABORTED
}
 
- Protected Member Functions inherited from controller_interface::Controller< hardware_interface::EffortJointInterface >
std::string getHardwareInterfaceType () const
 
bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) override
 

Detailed Description

Forward command controller for a set of effort controlled joints (torque or force).

This class forwards the commanded efforts down to a set of joints.

ROS interface

Parameters
typeMust be "JointGroupEffortController".
jointsList of names of the joints to control.

Subscribes to:

Definition at line 102 of file joint_group_position_controller.h.

Constructor & Destructor Documentation

◆ JointGroupPositionController()

effort_controllers::JointGroupPositionController::JointGroupPositionController ( )

Forward command controller for a set of effort controlled joints (torque or force).

This class forwards the commanded efforts down to a set of joints.

ROS interface

Parameters
typeMust be "JointGroupEffortController".
jointsList of names of the joints to control.

Subscribes to:

  • command (std_msgs::Float64MultiArray) : The joint efforts to apply

Definition at line 93 of file joint_group_position_controller.cpp.

◆ ~JointGroupPositionController()

effort_controllers::JointGroupPositionController::~JointGroupPositionController ( )

Definition at line 94 of file joint_group_position_controller.cpp.

Member Function Documentation

◆ commandCB()

void effort_controllers::JointGroupPositionController::commandCB ( const std_msgs::Float64MultiArrayConstPtr &  msg)
private

Definition at line 212 of file joint_group_position_controller.cpp.

◆ enforceJointLimits()

void effort_controllers::JointGroupPositionController::enforceJointLimits ( double &  command,
unsigned int  index 
)
private

Definition at line 222 of file joint_group_position_controller.cpp.

◆ init()

bool effort_controllers::JointGroupPositionController::init ( hardware_interface::EffortJointInterface hw,
ros::NodeHandle n 
)

Definition at line 96 of file joint_group_position_controller.cpp.

◆ starting()

void effort_controllers::JointGroupPositionController::starting ( const ros::Time time)
virtual

Reimplemented from controller_interface::ControllerBase.

Definition at line 158 of file joint_group_position_controller.cpp.

◆ update()

void effort_controllers::JointGroupPositionController::update ( const ros::Time time,
const ros::Duration period 
)
virtual

Member Data Documentation

◆ commands_buffer_

realtime_tools::RealtimeBuffer<std::vector<double> > effort_controllers::JointGroupPositionController::commands_buffer_

Definition at line 149 of file joint_group_position_controller.h.

◆ joint_names_

std::vector< std::string > effort_controllers::JointGroupPositionController::joint_names_

Definition at line 147 of file joint_group_position_controller.h.

◆ joint_urdfs_

std::vector<urdf::JointConstSharedPtr> effort_controllers::JointGroupPositionController::joint_urdfs_
private

Definition at line 157 of file joint_group_position_controller.h.

◆ joints_

std::vector< hardware_interface::JointHandle > effort_controllers::JointGroupPositionController::joints_

Definition at line 148 of file joint_group_position_controller.h.

◆ n_joints_

unsigned int effort_controllers::JointGroupPositionController::n_joints_

Definition at line 150 of file joint_group_position_controller.h.

◆ pid_controllers_

std::vector<control_toolbox::Pid> effort_controllers::JointGroupPositionController::pid_controllers_
private

Internal PID controllers.

Definition at line 155 of file joint_group_position_controller.h.

◆ sub_command_

ros::Subscriber effort_controllers::JointGroupPositionController::sub_command_
private

Definition at line 153 of file joint_group_position_controller.h.


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


effort_controllers
Author(s): Vijay Pradeep
autogenerated on Fri May 24 2024 02:41:22