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 update (const ros::Time &, const ros::Duration &)
 
 ~JointGroupPositionController ()
 
- Public Member Functions inherited from controller_interface::Controller< hardware_interface::EffortJointInterface >
 Controller ()
 
virtual bool init (hardware_interface::EffortJointInterface *, ros::NodeHandle &, ros::NodeHandle &)
 
virtual ~Controller ()
 
- Public Member Functions inherited from controller_interface::ControllerBase
 ControllerBase ()
 
bool isRunning ()
 
bool isRunning ()
 
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)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
void updateRequest (const ros::Time &time, const ros::Duration &period)
 
virtual ~ControllerBase ()
 

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
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  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
 
- Protected Member Functions inherited from controller_interface::Controller< hardware_interface::EffortJointInterface >
std::string getHardwareInterfaceType () const
 
virtual bool initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources)
 

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

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

Subscribes to:

Definition at line 68 of file joint_group_position_controller.h.

Constructor & Destructor Documentation

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

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 58 of file joint_group_position_controller.cpp.

effort_controllers::JointGroupPositionController::~JointGroupPositionController ( )

Definition at line 59 of file joint_group_position_controller.cpp.

Member Function Documentation

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

Definition at line 163 of file joint_group_position_controller.cpp.

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

Definition at line 173 of file joint_group_position_controller.cpp.

bool effort_controllers::JointGroupPositionController::init ( hardware_interface::EffortJointInterface hw,
ros::NodeHandle n 
)
virtual
void effort_controllers::JointGroupPositionController::update ( const ros::Time time,
const ros::Duration period 
)
virtual

Member Data Documentation

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

Definition at line 79 of file joint_group_position_controller.h.

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

Definition at line 77 of file joint_group_position_controller.h.

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

Definition at line 87 of file joint_group_position_controller.h.

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

Definition at line 78 of file joint_group_position_controller.h.

unsigned int effort_controllers::JointGroupPositionController::n_joints_

Definition at line 80 of file joint_group_position_controller.h.

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

Internal PID controllers.

Definition at line 85 of file joint_group_position_controller.h.

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

Definition at line 83 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 Sat Apr 18 2020 03:58:11