Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | Friends
controller::JointVelocityController Class Reference

#include <joint_velocity_controller.h>

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

List of all members.

Public Member Functions

void getCommand (double &cmd)
 Get latest position command to the joint: revolute (angle) and prismatic (position).
void getGains (double &p, double &i, double &d, double &i_max, double &i_min)
std::string getJointName ()
bool init (pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)
bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 JointVelocityController ()
void setCommand (double cmd)
 Give set position of the joint for next update: revolute (angle) and prismatic (position)
void setGains (const double &p, const double &i, const double &d, const double &i_max, const double &i_min)
virtual void starting ()
 Issues commands to the joint. Should be called at regular intervals.
virtual void update ()
 ~JointVelocityController ()

Public Attributes

double command_
ros::Duration dt_
pr2_mechanism_model::JointStatejoint_state_

Private Member Functions

void setCommandCB (const std_msgs::Float64ConstPtr &msg)

Private Attributes

boost::scoped_ptr
< realtime_tools::RealtimePublisher
< pr2_controllers_msgs::JointControllerState > > 
controller_state_publisher_
ros::Time last_time_
int loop_count_
ros::NodeHandle node_
control_toolbox::Pid pid_controller_
pr2_mechanism_model::RobotStaterobot_
ros::Subscriber sub_command_

Friends

class JointVelocityControllerNode

Detailed Description

Definition at line 80 of file joint_velocity_controller.h.


Constructor & Destructor Documentation

Definition at line 44 of file joint_velocity_controller.cpp.

Definition at line 49 of file joint_velocity_controller.cpp.


Member Function Documentation

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

Definition at line 128 of file joint_velocity_controller.cpp.

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

Definition at line 111 of file joint_velocity_controller.cpp.

Definition at line 116 of file joint_velocity_controller.cpp.

bool controller::JointVelocityController::init ( pr2_mechanism_model::RobotState robot,
const std::string &  joint_name,
const control_toolbox::Pid pid 
)

Definition at line 54 of file joint_velocity_controller.cpp.

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

Parameters:
doublepos Velocity command to issue

Definition at line 122 of file joint_velocity_controller.cpp.

void controller::JointVelocityController::setCommandCB ( const std_msgs::Float64ConstPtr &  msg) [private]

Definition at line 168 of file joint_velocity_controller.cpp.

void controller::JointVelocityController::setGains ( const double &  p,
const double &  i,
const double &  d,
const double &  i_max,
const double &  i_min 
)

Definition at line 105 of file joint_velocity_controller.cpp.

virtual void controller::JointVelocityController::starting ( ) [inline, virtual]

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

Reimplemented from pr2_controller_interface::Controller.

Definition at line 106 of file joint_velocity_controller.h.


Friends And Related Function Documentation

friend class JointVelocityControllerNode [friend]

Definition at line 127 of file joint_velocity_controller.h.


Member Data Documentation

Last commanded position.

Definition at line 119 of file joint_velocity_controller.h.

boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerState> > controller::JointVelocityController::controller_state_publisher_ [private]

Definition at line 131 of file joint_velocity_controller.h.

Definition at line 117 of file joint_velocity_controller.h.

Joint we're controlling.

Definition at line 116 of file joint_velocity_controller.h.

Last time stamp of update.

Definition at line 124 of file joint_velocity_controller.h.

Definition at line 125 of file joint_velocity_controller.h.

Definition at line 121 of file joint_velocity_controller.h.

Internal PID controller.

Definition at line 123 of file joint_velocity_controller.h.

Pointer to robot structure.

Definition at line 122 of file joint_velocity_controller.h.

Definition at line 133 of file joint_velocity_controller.h.


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


robot_mechanism_controllers
Author(s): John Hsu, Melonee Wise, Stuart Glaser
autogenerated on Thu Aug 27 2015 14:22:46