Classes | Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
effort_controllers::JointPositionController Class Reference

Joint Position Controller. More...

#include <joint_position_controller.h>

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

List of all members.

Classes

struct  Commands
 Store position and velocity command in struct to allow easier realtime buffer usage. More...

Public Member Functions

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.
double getPosition ()
 Get the current position of the joint.
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.
 JointPositionController ()
void printDebug ()
 Print debug info to console.
void setCommand (double pos_target)
 Give set position of the joint for next update: revolute (angle) and prismatic (position)
void setCommand (double pos_target, double vel_target)
 Give set position of the joint for next update: revolute (angle) and prismatic (position) Also supports a target 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.
 ~JointPositionController ()

Public Attributes

realtime_tools::RealtimeBuffer
< Commands
command_
Commands command_struct_
hardware_interface::JointHandle joint_
boost::shared_ptr< const
urdf::Joint > 
joint_urdf_

Private Member Functions

void enforceJointLimits (double &command)
 Check that the command is within the hard limits of the joint. Checks for joint type first. Sets command to limit if out of bounds.
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 Position Controller.

This class controls positon using a pid loop.

ROS

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

Subscribes to:

Publishes:

Definition at line 78 of file joint_position_controller.h.


Constructor & Destructor Documentation

Definition at line 48 of file joint_position_controller.cpp.

Definition at line 52 of file joint_position_controller.cpp.


Member Function Documentation

Check that the command is within the hard limits of the joint. Checks for joint type first. Sets command to limit if out of bounds.

Parameters:
command- the input to test

Definition at line 244 of file joint_position_controller.cpp.

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

Get the PID parameters.

Definition at line 103 of file joint_position_controller.cpp.

Get the name of the joint this controller uses.

Definition at line 113 of file joint_position_controller.cpp.

Get the current position of the joint.

Returns:
current position

Definition at line 118 of file joint_position_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 57 of file joint_position_controller.cpp.

Print debug info to console.

Definition at line 108 of file joint_position_controller.cpp.

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

Parameters:
command

Definition at line 124 of file joint_position_controller.cpp.

void effort_controllers::JointPositionController::setCommand ( double  pos_target,
double  vel_target 
)

Give set position of the joint for next update: revolute (angle) and prismatic (position) Also supports a target velocity.

Parameters:
pos_target- position setpoint
vel_target- velocity setpoint

Definition at line 136 of file joint_position_controller.cpp.

void effort_controllers::JointPositionController::setCommandCB ( const std_msgs::Float64ConstPtr &  msg) [private]

Callback from /command subscriber for setpoint.

Definition at line 238 of file joint_position_controller.cpp.

void effort_controllers::JointPositionController::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 98 of file joint_position_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 145 of file joint_position_controller.cpp.

void effort_controllers::JointPositionController::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 160 of file joint_position_controller.cpp.


Member Data Documentation

Definition at line 166 of file joint_position_controller.h.

Definition at line 167 of file joint_position_controller.h.

boost::scoped_ptr< realtime_tools::RealtimePublisher< control_msgs::JointControllerState> > effort_controllers::JointPositionController::controller_state_publisher_ [private]

Definition at line 175 of file joint_position_controller.h.

Definition at line 164 of file joint_position_controller.h.

boost::shared_ptr<const urdf::Joint> effort_controllers::JointPositionController::joint_urdf_

Definition at line 165 of file joint_position_controller.h.

Definition at line 170 of file joint_position_controller.h.

Internal PID controller.

Definition at line 171 of file joint_position_controller.h.

Definition at line 177 of file joint_position_controller.h.


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


effort_controllers
Author(s): Vijay Pradeep
autogenerated on Thu Jun 6 2019 18:58:55