$search

pr2_dremel::JointForceController Class Reference

#include <joint_force_controller.h>

Inheritance diagram for pr2_dremel::JointForceController:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 JointForceController ()
virtual void starting ()
virtual void update ()
 ~JointForceController ()

Private Member Functions

double force_effort (double force)
double force_error (double force)
void forceCB (const std_msgs::Float64ConstPtr &msg)
double position_effort (double position, ros::Time time)
double position_error (double position)
void positionCB (const std_msgs::Float64ConstPtr &msg)
void reset_velocity_average ()
double velocity_effort (double velocity, ros::Time time)

Private Attributes

boost::scoped_ptr
< realtime_tools::RealtimePublisher
< pr2_controllers_msgs::JointControllerState > > 
controller_state_publisher_
ros::Duration dt_
double force_
bool force_control_
ros::Subscriber force_sub_
bool initialized_
pr2_mechanism_model::JointStatejoint_state_
ros::Time last_time_
double max_velocity_
ros::NodeHandle node_
double position_
double position_control_limit_
control_toolbox::Pid position_pid_controller_
ros::Subscriber position_sub_
pr2_mechanism_model::RobotStaterobot_
float velocities_ [velocity_window_]
int velocity_id_
control_toolbox::Pid velocity_pid_controller_
float velocity_sum_

Static Private Attributes

static const int velocity_window_ = 30

Detailed Description

Definition at line 71 of file joint_force_controller.h.


Constructor & Destructor Documentation

pr2_dremel::JointForceController::JointForceController (  ) 

Definition at line 51 of file joint_force_controller.cpp.

pr2_dremel::JointForceController::~JointForceController (  ) 

Definition at line 59 of file joint_force_controller.cpp.


Member Function Documentation

double pr2_dremel::JointForceController::force_effort ( double  force  )  [private]

Definition at line 171 of file joint_force_controller.cpp.

double pr2_dremel::JointForceController::force_error ( double  force  )  [private]

Definition at line 166 of file joint_force_controller.cpp.

void pr2_dremel::JointForceController::forceCB ( const std_msgs::Float64ConstPtr &  msg  )  [private]

Definition at line 213 of file joint_force_controller.cpp.

bool pr2_dremel::JointForceController::init ( pr2_mechanism_model::RobotState robot,
ros::NodeHandle n 
) [virtual]

Implements pr2_controller_interface::Controller.

Definition at line 74 of file joint_force_controller.cpp.

double pr2_dremel::JointForceController::position_effort ( double  position,
ros::Time  time 
) [private]

Definition at line 198 of file joint_force_controller.cpp.

double pr2_dremel::JointForceController::position_error ( double  position  )  [private]

Definition at line 176 of file joint_force_controller.cpp.

void pr2_dremel::JointForceController::positionCB ( const std_msgs::Float64ConstPtr &  msg  )  [private]

Definition at line 226 of file joint_force_controller.cpp.

void pr2_dremel::JointForceController::reset_velocity_average (  )  [private]

Definition at line 65 of file joint_force_controller.cpp.

void pr2_dremel::JointForceController::starting (  )  [virtual]

Reimplemented from pr2_controller_interface::Controller.

Definition at line 110 of file joint_force_controller.cpp.

void pr2_dremel::JointForceController::update ( void   )  [virtual]

Implements pr2_controller_interface::Controller.

Definition at line 122 of file joint_force_controller.cpp.

double pr2_dremel::JointForceController::velocity_effort ( double  velocity,
ros::Time  time 
) [private]

Definition at line 206 of file joint_force_controller.cpp.


Member Data Documentation

Definition at line 91 of file joint_force_controller.h.

Definition at line 105 of file joint_force_controller.h.

Definition at line 100 of file joint_force_controller.h.

Definition at line 99 of file joint_force_controller.h.

Definition at line 95 of file joint_force_controller.h.

Definition at line 82 of file joint_force_controller.h.

Definition at line 98 of file joint_force_controller.h.

Last time stamp of update.

Definition at line 87 of file joint_force_controller.h.

Definition at line 102 of file joint_force_controller.h.

Definition at line 93 of file joint_force_controller.h.

Definition at line 101 of file joint_force_controller.h.

Definition at line 103 of file joint_force_controller.h.

Internal position PID controller.

Definition at line 85 of file joint_force_controller.h.

Definition at line 94 of file joint_force_controller.h.

Pointer to robot structure.

Definition at line 84 of file joint_force_controller.h.

Definition at line 119 of file joint_force_controller.h.

Definition at line 118 of file joint_force_controller.h.

Internal velocity PID controller.

Definition at line 86 of file joint_force_controller.h.

Definition at line 120 of file joint_force_controller.h.

const int pr2_dremel::JointForceController::velocity_window_ = 30 [static, private]

Definition at line 117 of file joint_force_controller.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


pr2_dremel_arm_controller
Author(s): Christian Bersch (maintained by Benjamin Pitzer)
autogenerated on Sun Mar 3 11:58:27 2013