#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 () |
|
void | stopping (const ros::Time &time) |
|
virtual void | stopping () |
|
bool | stopRequest () |
|
void | update (const ros::Time &time, const ros::Duration &period) |
|
void | updateRequest () |
|
virtual | ~Controller () |
|
Definition at line 80 of file joint_velocity_controller.h.
controller::JointVelocityController::JointVelocityController |
( |
| ) |
|
controller::JointVelocityController::~JointVelocityController |
( |
| ) |
|
void controller::JointVelocityController::getCommand |
( |
double & |
cmd | ) |
|
void controller::JointVelocityController::getGains |
( |
double & |
p, |
|
|
double & |
i, |
|
|
double & |
d, |
|
|
double & |
i_max, |
|
|
double & |
i_min |
|
) |
| |
std::string controller::JointVelocityController::getJointName |
( |
| ) |
|
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.
void controller::JointVelocityController::setCommandCB |
( |
const std_msgs::Float64ConstPtr & |
msg | ) |
|
|
private |
void controller::JointVelocityController::setGains |
( |
const double & |
p, |
|
|
const double & |
i, |
|
|
const double & |
d, |
|
|
const double & |
i_max, |
|
|
const double & |
i_min |
|
) |
| |
virtual void controller::JointVelocityController::starting |
( |
| ) |
|
|
inlinevirtual |
void controller::JointVelocityController::update |
( |
void |
| ) |
|
|
virtual |
friend class JointVelocityControllerNode |
|
friend |
double controller::JointVelocityController::command_ |
ros::Time controller::JointVelocityController::last_time_ |
|
private |
int controller::JointVelocityController::loop_count_ |
|
private |
The documentation for this class was generated from the following files: