Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | Friends | List of all members
controller::JointGroupVelocityController Class Reference

#include <joint_group_velocity_controller.h>

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

Public Member Functions

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 ()
 
- Public Member Functions inherited from pr2_controller_interface::Controller
 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 ()
 

Public Attributes

unsigned int n_joints_
 
- Public Attributes inherited from pr2_controller_interface::Controller
std::vector< std::string > after_list_
 
 AFTER_ME
 
std::vector< std::string > before_list_
 
 BEFORE_ME
 
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum pr2_controller_interface::Controller:: { ... }  state_
 

Private Member Functions

void setCommandCB (const std_msgs::Float64MultiArrayConstPtr &msg)
 

Private Attributes

realtime_tools::RealtimeBuffer< std::vector< double > > commands_buffer_
 
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerStateArray > > controller_state_publisher_
 
std::vector< pr2_mechanism_model::JointState * > joints_
 
ros::Time last_time_
 
int loop_count_
 
ros::NodeHandle node_
 
std::vector< control_toolbox::Pidpid_controllers_
 
pr2_mechanism_model::RobotStaterobot_
 
ros::Subscriber sub_command_
 

Friends

class JointGroupVelocityControllerNode
 

Detailed Description

Definition at line 82 of file joint_group_velocity_controller.h.

Constructor & Destructor Documentation

◆ JointGroupVelocityController()

controller::JointGroupVelocityController::JointGroupVelocityController ( )

Definition at line 44 of file joint_group_velocity_controller.cpp.

◆ ~JointGroupVelocityController()

controller::JointGroupVelocityController::~JointGroupVelocityController ( )

Definition at line 49 of file joint_group_velocity_controller.cpp.

Member Function Documentation

◆ getCommand()

void controller::JointGroupVelocityController::getCommand ( std::vector< double > &  cmd)

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

Definition at line 142 of file joint_group_velocity_controller.cpp.

◆ getGains()

void controller::JointGroupVelocityController::getGains ( control_toolbox::Pid pid,
double &  p,
double &  i,
double &  d,
double &  i_max,
double &  i_min 
)

Definition at line 120 of file joint_group_velocity_controller.cpp.

◆ getJointName()

std::vector< std::string > controller::JointGroupVelocityController::getJointName ( )

Definition at line 125 of file joint_group_velocity_controller.cpp.

◆ init() [1/2]

bool controller::JointGroupVelocityController::init ( pr2_mechanism_model::RobotState robot,
const std::vector< std::string > &  joint_names,
const control_toolbox::Pid pid 
)

◆ init() [2/2]

bool controller::JointGroupVelocityController::init ( pr2_mechanism_model::RobotState robot,
ros::NodeHandle n 
)
virtual

◆ setCommand()

void controller::JointGroupVelocityController::setCommand ( std::vector< double >  cmd)

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

Parameters
doublepos 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

Definition at line 202 of file joint_group_velocity_controller.cpp.

◆ starting()

void controller::JointGroupVelocityController::starting ( )
virtual

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

Reimplemented from pr2_controller_interface::Controller.

Definition at line 147 of file joint_group_velocity_controller.cpp.

◆ update()

void controller::JointGroupVelocityController::update ( )
virtual

Friends And Related Function Documentation

◆ JointGroupVelocityControllerNode

friend class JointGroupVelocityControllerNode
friend

Definition at line 127 of file joint_group_velocity_controller.h.

Member Data Documentation

◆ commands_buffer_

realtime_tools::RealtimeBuffer<std::vector<double> > controller::JointGroupVelocityController::commands_buffer_
private

Last commanded position.

Definition at line 125 of file joint_group_velocity_controller.h.

◆ controller_state_publisher_

boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerStateArray> > controller::JointGroupVelocityController::controller_state_publisher_
private

Definition at line 131 of file joint_group_velocity_controller.h.

◆ joints_

std::vector<pr2_mechanism_model::JointState*> controller::JointGroupVelocityController::joints_
private

Joint we're controlling.

Definition at line 121 of file joint_group_velocity_controller.h.

◆ last_time_

ros::Time controller::JointGroupVelocityController::last_time_
private

Last time stamp of update.

Definition at line 122 of file joint_group_velocity_controller.h.

◆ loop_count_

int controller::JointGroupVelocityController::loop_count_
private

Definition at line 123 of file joint_group_velocity_controller.h.

◆ n_joints_

unsigned int controller::JointGroupVelocityController::n_joints_

Definition at line 115 of file joint_group_velocity_controller.h.

◆ node_

ros::NodeHandle controller::JointGroupVelocityController::node_
private

Definition at line 118 of file joint_group_velocity_controller.h.

◆ pid_controllers_

std::vector<control_toolbox::Pid> controller::JointGroupVelocityController::pid_controllers_
private

Internal PID controller.

Definition at line 120 of file joint_group_velocity_controller.h.

◆ robot_

pr2_mechanism_model::RobotState* controller::JointGroupVelocityController::robot_
private

Pointer to robot structure.

Definition at line 119 of file joint_group_velocity_controller.h.

◆ sub_command_

ros::Subscriber controller::JointGroupVelocityController::sub_command_
private

Definition at line 133 of file joint_group_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 Sat Nov 12 2022 03:33:22