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

Joint Velocity Controller. More...

#include <joint_velocity_controller.h>

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

Public Member Functions

void getCommand (double &cmd)
 Get latest velocity command to the joint: revolute (angle) and prismatic (velocity). More...
 
void getGains (double &p, double &i, double &d, double &i_max, double &i_min)
 Get the PID parameters. More...
 
void getGains (double &p, double &i, double &d, double &i_max, double &i_min, bool &antiwindup)
 Get the PID parameters. More...
 
std::string getJointName ()
 Get the name of the joint this controller uses. More...
 
bool init (hardware_interface::EffortJointInterface *robot, const std::string &joint_name, const control_toolbox::Pid &pid)
 
bool init (hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n)
 The init function is called to initialize the controller from a non-realtime thread with a pointer to the hardware interface, itself, instead of a pointer to a RobotHW. More...
 
 JointVelocityController ()
 
void printDebug ()
 Print debug info to console. More...
 
void setCommand (double cmd)
 Give set velocity of the joint for next update: revolute (angle) and prismatic (velocity) More...
 
void setGains (const double &p, const double &i, const double &d, const double &i_max, const double &i_min, const bool &antiwindup=false)
 Get the PID parameters. More...
 
void starting (const ros::Time &time)
 This is called from within the realtime thread just before the first call to update. More...
 
void update (const ros::Time &time, const ros::Duration &period)
 Issues commands to the joint. Should be called at regular intervals. More...
 
 ~JointVelocityController ()
 
- 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 ()
 
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

double command_
 
hardware_interface::JointHandle joint_
 
- Public Attributes inherited from controller_interface::ControllerBase
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum controller_interface::ControllerBase:: { ... }  state_
 

Private Member Functions

void setCommandCB (const std_msgs::Float64ConstPtr &msg)
 Callback from /command subscriber for setpoint. More...
 

Private Attributes

boost::scoped_ptr< realtime_tools::RealtimePublisher< control_msgs::JointControllerState > > controller_state_publisher_
 
int loop_count_
 
control_toolbox::Pid pid_controller_
 
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

Joint Velocity Controller.

This class controls velocity using a pid loop.

ROS

Parameters
typeMust be "effort_controllers::JointVelocityController"
jointName of the joint to control.
pidContains the gains for the PID loop around velocity. See: control_toolbox::Pid

Subscribes to:

Publishes:

Definition at line 75 of file joint_velocity_controller.h.

Constructor & Destructor Documentation

effort_controllers::JointVelocityController::JointVelocityController ( )

Definition at line 42 of file joint_velocity_controller.cpp.

effort_controllers::JointVelocityController::~JointVelocityController ( )

Definition at line 46 of file joint_velocity_controller.cpp.

Member Function Documentation

void effort_controllers::JointVelocityController::getCommand ( double &  cmd)

Get latest velocity command to the joint: revolute (angle) and prismatic (velocity).

Definition at line 122 of file joint_velocity_controller.cpp.

void effort_controllers::JointVelocityController::getGains ( double &  p,
double &  i,
double &  d,
double &  i_max,
double &  i_min 
)

Get the PID parameters.

Definition at line 99 of file joint_velocity_controller.cpp.

void effort_controllers::JointVelocityController::getGains ( double &  p,
double &  i,
double &  d,
double &  i_max,
double &  i_min,
bool &  antiwindup 
)

Get the PID parameters.

Definition at line 94 of file joint_velocity_controller.cpp.

std::string effort_controllers::JointVelocityController::getJointName ( )

Get the name of the joint this controller uses.

Definition at line 110 of file joint_velocity_controller.cpp.

bool effort_controllers::JointVelocityController::init ( hardware_interface::EffortJointInterface robot,
const std::string &  joint_name,
const control_toolbox::Pid pid 
)

Definition at line 51 of file joint_velocity_controller.cpp.

bool effort_controllers::JointVelocityController::init ( hardware_interface::EffortJointInterface robot,
ros::NodeHandle n 
)
virtual

The init function is called to initialize the controller from a non-realtime thread with a pointer to the hardware interface, itself, instead of a pointer to a RobotHW.

Parameters
robotThe specific hardware interface used by this controller.
nA NodeHandle in the namespace from which the controller should read its configuration, and where it should set up its ROS interface.
Returns
True if initialization was successful and the controller is ready to be started.

Reimplemented from controller_interface::Controller< hardware_interface::EffortJointInterface >.

Definition at line 62 of file joint_velocity_controller.cpp.

void effort_controllers::JointVelocityController::printDebug ( )

Print debug info to console.

Definition at line 105 of file joint_velocity_controller.cpp.

void effort_controllers::JointVelocityController::setCommand ( double  cmd)

Give set velocity of the joint for next update: revolute (angle) and prismatic (velocity)

Parameters
doublepos Velocity command to issue

Definition at line 116 of file joint_velocity_controller.cpp.

void effort_controllers::JointVelocityController::setCommandCB ( const std_msgs::Float64ConstPtr &  msg)
private

Callback from /command subscriber for setpoint.

Definition at line 170 of file joint_velocity_controller.cpp.

void effort_controllers::JointVelocityController::setGains ( const double &  p,
const double &  i,
const double &  d,
const double &  i_max,
const double &  i_min,
const bool &  antiwindup = false 
)

Get the PID parameters.

Definition at line 89 of file joint_velocity_controller.cpp.

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

This is called from within the realtime thread just before the first call to update.

Parameters
timeThe current time

Reimplemented from controller_interface::ControllerBase.

Definition at line 127 of file joint_velocity_controller.cpp.

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

Issues commands to the joint. Should be called at regular intervals.

Implements controller_interface::ControllerBase.

Definition at line 133 of file joint_velocity_controller.cpp.

Member Data Documentation

double effort_controllers::JointVelocityController::command_

Last commanded velocity.

Definition at line 149 of file joint_velocity_controller.h.

boost::scoped_ptr< realtime_tools::RealtimePublisher< control_msgs::JointControllerState> > effort_controllers::JointVelocityController::controller_state_publisher_
private

Definition at line 159 of file joint_velocity_controller.h.

hardware_interface::JointHandle effort_controllers::JointVelocityController::joint_

Definition at line 148 of file joint_velocity_controller.h.

int effort_controllers::JointVelocityController::loop_count_
private

Definition at line 152 of file joint_velocity_controller.h.

control_toolbox::Pid effort_controllers::JointVelocityController::pid_controller_
private

Internal PID controller.

Definition at line 153 of file joint_velocity_controller.h.

ros::Subscriber effort_controllers::JointVelocityController::sub_command_
private

Definition at line 161 of file joint_velocity_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