Joint Position Controller. More...
#include <joint_position_controller.h>
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. 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... | |
double | getPosition () |
Get the current position of the joint. More... | |
bool | init (hardware_interface::VelocityJointInterface *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... | |
JointPositionController () | |
void | printDebug () |
Print debug info to console. More... | |
void | setCommand (double pos_target) |
Give set position of the joint for next update: revolute (angle) and prismatic (position) More... | |
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. 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... | |
~JointPositionController () | |
Public Member Functions inherited from controller_interface::Controller< hardware_interface::VelocityJointInterface > | |
Controller () | |
virtual bool | init (hardware_interface::VelocityJointInterface *, 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 | |
realtime_tools::RealtimeBuffer< Commands > | command_ |
Commands | command_struct_ |
hardware_interface::JointHandle | joint_ |
urdf::JointConstSharedPtr | joint_urdf_ |
Public Attributes inherited from controller_interface::ControllerBase | |
CONSTRUCTED | |
INITIALIZED | |
RUNNING | |
enum controller_interface::ControllerBase:: { ... } | state_ |
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. More... | |
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::InterfaceResources > | ClaimedResources |
Protected Member Functions inherited from controller_interface::Controller< hardware_interface::VelocityJointInterface > | |
std::string | getHardwareInterfaceType () const |
virtual bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) |
Joint Position Controller.
This class controls positon using a pid loop.
type | Must be "velocity_controllers::JointPositionController" |
joint | Name of the joint to control. |
pid | Contains the gains for the PID loop around position. See: control_toolbox::Pid |
Subscribes to:
Publishes:
Definition at line 85 of file joint_position_controller.h.
velocity_controllers::JointPositionController::JointPositionController | ( | ) |
Definition at line 49 of file joint_position_controller.cpp.
velocity_controllers::JointPositionController::~JointPositionController | ( | ) |
Definition at line 53 of file joint_position_controller.cpp.
|
private |
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.
command | - the input to test |
Definition at line 254 of file joint_position_controller.cpp.
void velocity_controllers::JointPositionController::getGains | ( | double & | p, |
double & | i, | ||
double & | d, | ||
double & | i_max, | ||
double & | i_min | ||
) |
Get the PID parameters.
Definition at line 104 of file joint_position_controller.cpp.
void velocity_controllers::JointPositionController::getGains | ( | double & | p, |
double & | i, | ||
double & | d, | ||
double & | i_max, | ||
double & | i_min, | ||
bool & | antiwindup | ||
) |
Get the PID parameters.
Definition at line 110 of file joint_position_controller.cpp.
std::string velocity_controllers::JointPositionController::getJointName | ( | ) |
Get the name of the joint this controller uses.
Definition at line 120 of file joint_position_controller.cpp.
double velocity_controllers::JointPositionController::getPosition | ( | ) |
Get the current position of the joint.
Definition at line 125 of file joint_position_controller.cpp.
|
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.
robot | The specific hardware interface used by this controller. |
n | A NodeHandle in the namespace from which the controller should read its configuration, and where it should set up its ROS interface. |
Reimplemented from controller_interface::Controller< hardware_interface::VelocityJointInterface >.
Definition at line 58 of file joint_position_controller.cpp.
void velocity_controllers::JointPositionController::printDebug | ( | ) |
Print debug info to console.
Definition at line 115 of file joint_position_controller.cpp.
void velocity_controllers::JointPositionController::setCommand | ( | double | pos_target | ) |
Give set position of the joint for next update: revolute (angle) and prismatic (position)
command |
Definition at line 131 of file joint_position_controller.cpp.
void velocity_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.
pos_target | - position setpoint |
vel_target | - velocity setpoint |
Definition at line 143 of file joint_position_controller.cpp.
|
private |
Callback from /command subscriber for setpoint.
Definition at line 248 of file joint_position_controller.cpp.
void velocity_controllers::JointPositionController::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 99 of file joint_position_controller.cpp.
|
virtual |
This is called from within the realtime thread just before the first call to update.
time | The current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 152 of file joint_position_controller.cpp.
|
virtual |
Issues commands to the joint. Should be called at regular intervals.
Implements controller_interface::ControllerBase.
Definition at line 167 of file joint_position_controller.cpp.
realtime_tools::RealtimeBuffer<Commands> velocity_controllers::JointPositionController::command_ |
Definition at line 178 of file joint_position_controller.h.
Commands velocity_controllers::JointPositionController::command_struct_ |
Definition at line 179 of file joint_position_controller.h.
|
private |
Definition at line 187 of file joint_position_controller.h.
hardware_interface::JointHandle velocity_controllers::JointPositionController::joint_ |
Definition at line 176 of file joint_position_controller.h.
urdf::JointConstSharedPtr velocity_controllers::JointPositionController::joint_urdf_ |
Definition at line 177 of file joint_position_controller.h.
|
private |
Definition at line 182 of file joint_position_controller.h.
|
private |
Internal PID controller.
Definition at line 183 of file joint_position_controller.h.
|
private |
Definition at line 189 of file joint_position_controller.h.