#include <joint_group_velocity_controller.h>
|
void | getCommand (std::vector< double > &cmd) |
| Get latest position command to the joint: revolute (angle) and prismatic (position). More...
|
|
void | getGains (control_toolbox::Pid &pid, double &p, double &i, double &d, double &i_max, double &i_min) |
|
std::vector< std::string > | getJointName () |
|
bool | init (pr2_mechanism_model::RobotState *robot, const std::vector< std::string > &joint_names, const control_toolbox::Pid &pid) |
|
bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
|
| JointGroupVelocityController () |
|
void | setCommand (std::vector< double > cmd) |
| Give set position of the joint for next update: revolute (angle) and prismatic (position) More...
|
|
virtual void | starting () |
| Issues commands to the joint. Should be called at regular intervals. More...
|
|
virtual void | update () |
|
| ~JointGroupVelocityController () |
|
| 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 () |
|
◆ JointGroupVelocityController()
controller::JointGroupVelocityController::JointGroupVelocityController |
( |
| ) |
|
◆ ~JointGroupVelocityController()
controller::JointGroupVelocityController::~JointGroupVelocityController |
( |
| ) |
|
◆ getCommand()
void controller::JointGroupVelocityController::getCommand |
( |
std::vector< double > & |
cmd | ) |
|
◆ getGains()
void controller::JointGroupVelocityController::getGains |
( |
control_toolbox::Pid & |
pid, |
|
|
double & |
p, |
|
|
double & |
i, |
|
|
double & |
d, |
|
|
double & |
i_max, |
|
|
double & |
i_min |
|
) |
| |
◆ getJointName()
std::vector< std::string > controller::JointGroupVelocityController::getJointName |
( |
| ) |
|
◆ init() [1/2]
◆ init() [2/2]
◆ setCommand()
void controller::JointGroupVelocityController::setCommand |
( |
std::vector< 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 136 of file joint_group_velocity_controller.cpp.
◆ setCommandCB()
void controller::JointGroupVelocityController::setCommandCB |
( |
const std_msgs::Float64MultiArrayConstPtr & |
msg | ) |
|
|
private |
◆ starting()
void controller::JointGroupVelocityController::starting |
( |
| ) |
|
|
virtual |
◆ update()
void controller::JointGroupVelocityController::update |
( |
void |
| ) |
|
|
virtual |
◆ JointGroupVelocityControllerNode
friend class JointGroupVelocityControllerNode |
|
friend |
◆ commands_buffer_
◆ controller_state_publisher_
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerStateArray> > controller::JointGroupVelocityController::controller_state_publisher_ |
|
private |
◆ joints_
◆ last_time_
ros::Time controller::JointGroupVelocityController::last_time_ |
|
private |
◆ loop_count_
int controller::JointGroupVelocityController::loop_count_ |
|
private |
◆ n_joints_
unsigned int controller::JointGroupVelocityController::n_joints_ |
◆ node_
◆ pid_controllers_
◆ robot_
◆ sub_command_
The documentation for this class was generated from the following files: