Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
effort_controllers::JointVelocityController Class Reference

Joint Velocity Controller. More...

#include <joint_velocity_controller.h>

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

List of all members.

Public Member Functions

void getCommand (double &cmd)
 Get latest velocity command to the joint: revolute (angle) and prismatic (velocity).
void getGains (double &p, double &i, double &d, double &i_max, double &i_min)
 Get the PID parameters.
std::string getJointName ()
 Get the name of the joint this controller uses.
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.
 JointVelocityController ()
void printDebug ()
 Print debug info to console.
void setCommand (double cmd)
 Give set velocity of the joint for next update: revolute (angle) and prismatic (velocity)
void setGains (const double &p, const double &i, const double &d, const double &i_max, const double &i_min)
 Get the PID parameters.
void starting (const ros::Time &time)
 This is called from within the realtime thread just before the first call to update.
void update (const ros::Time &time, const ros::Duration &period)
 Issues commands to the joint. Should be called at regular intervals.
 ~JointVelocityController ()

Public Attributes

double command_
hardware_interface::JointHandle joint_

Private Member Functions

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

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_

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

Definition at line 42 of file joint_velocity_controller.cpp.

Definition at line 46 of file joint_velocity_controller.cpp.


Member Function Documentation

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

Definition at line 118 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 96 of file joint_velocity_controller.cpp.

Get the name of the joint this controller uses.

Definition at line 106 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.

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.

Print debug info to console.

Definition at line 101 of file joint_velocity_controller.cpp.

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

Parameters:
doublepos Velocity command to issue

Definition at line 112 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 163 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 
)

Get the PID parameters.

Definition at line 90 of file joint_velocity_controller.cpp.

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 123 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 129 of file joint_velocity_controller.cpp.


Member Data Documentation

Last commanded velocity.

Definition at line 144 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 154 of file joint_velocity_controller.h.

Definition at line 143 of file joint_velocity_controller.h.

Definition at line 147 of file joint_velocity_controller.h.

Internal PID controller.

Definition at line 148 of file joint_velocity_controller.h.

Definition at line 156 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 Fri Aug 28 2015 12:37:06