#include <joint_velocity_controller.h>
|  | 
| void | getCommand (double &cmd) | 
|  | Get latest position command to the joint: revolute (angle) and prismatic (position).  More... 
 | 
|  | 
| 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)  More... 
 | 
|  | 
| 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.  More... 
 | 
|  | 
| virtual void | update () | 
|  | 
|  | ~JointVelocityController () | 
|  | 
|  | Controller () | 
|  | 
| bool | getController (const std::string &name, int sched, ControllerType *&c) | 
|  | 
| bool | initRequest (ControllerProvider *cp, pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) | 
|  | 
| bool | isRunning () | 
|  | 
| void | starting (const ros::Time &time) | 
|  | 
| bool | startRequest () | 
|  | 
| virtual void | stopping () | 
|  | 
| void | stopping (const ros::Time &time) | 
|  | 
| bool | stopRequest () | 
|  | 
| void | update (const ros::Time &time, const ros::Duration &period) | 
|  | 
| void | updateRequest () | 
|  | 
| virtual | ~Controller () | 
|  | 
Definition at line 79 of file joint_velocity_controller.h.
 
◆ JointVelocityController()
      
        
          | controller::JointVelocityController::JointVelocityController | ( |  | ) |  | 
      
 
 
◆ ~JointVelocityController()
      
        
          | controller::JointVelocityController::~JointVelocityController | ( |  | ) |  | 
      
 
 
◆ getCommand()
      
        
          | void controller::JointVelocityController::getCommand | ( | double & | cmd | ) |  | 
      
 
 
◆ getGains()
      
        
          | void controller::JointVelocityController::getGains | ( | double & | p, | 
        
          |  |  | double & | i, | 
        
          |  |  | double & | d, | 
        
          |  |  | double & | i_max, | 
        
          |  |  | double & | i_min | 
        
          |  | ) |  |  | 
      
 
 
◆ getJointName()
      
        
          | std::string controller::JointVelocityController::getJointName | ( |  | ) |  | 
      
 
 
◆ init() [1/2]
◆ init() [2/2]
◆ setCommand()
      
        
          | void controller::JointVelocityController::setCommand | ( | double | cmd | ) |  | 
      
 
Give set position of the joint for next update: revolute (angle) and prismatic (position) 
- Parameters
- 
  
    | double | pos Velocity command to issue |  
 
Definition at line 122 of file joint_velocity_controller.cpp.
 
 
◆ setCommandCB()
  
  | 
        
          | void controller::JointVelocityController::setCommandCB | ( | const std_msgs::Float64ConstPtr & | msg | ) |  |  | private | 
 
 
◆ setGains()
      
        
          | void controller::JointVelocityController::setGains | ( | const double & | p, | 
        
          |  |  | const double & | i, | 
        
          |  |  | const double & | d, | 
        
          |  |  | const double & | i_max, | 
        
          |  |  | const double & | i_min | 
        
          |  | ) |  |  | 
      
 
 
◆ starting()
  
  | 
        
          | virtual void controller::JointVelocityController::starting | ( |  | ) |  |  | inlinevirtual | 
 
 
◆ update()
  
  | 
        
          | void controller::JointVelocityController::update | ( |  | ) |  |  | virtual | 
 
 
◆ JointVelocityControllerNode
  
  | 
        
          | friend class JointVelocityControllerNode |  | friend | 
 
 
◆ command_
      
        
          | double controller::JointVelocityController::command_ | 
      
 
 
◆ controller_state_publisher_
◆ dt_
◆ joint_state_
◆ last_time_
  
  | 
        
          | ros::Time controller::JointVelocityController::last_time_ |  | private | 
 
 
◆ loop_count_
  
  | 
        
          | int controller::JointVelocityController::loop_count_ |  | private | 
 
 
◆ node_
◆ pid_controller_
◆ robot_
◆ sub_command_
The documentation for this class was generated from the following files: