Public Member Functions | Public Attributes | Private Types
hrl_pr2_force_ctrl::HybridForceController Class Reference
Inheritance diagram for hrl_pr2_force_ctrl::HybridForceController:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void commandForce (const geometry_msgs::WrenchStamped::ConstPtr &msg)
void commandMaxForce (const geometry_msgs::WrenchStamped::ConstPtr &msg)
void commandPose (const geometry_msgs::PoseStamped::ConstPtr &command)
void commandPosture (const std_msgs::Float64MultiArray::ConstPtr &msg)
 HybridForceController ()
bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
void setFTSensorParams (const std_msgs::Float64MultiArray::ConstPtr &msg)
void setGains (const hrl_pr2_force_ctrl::HybridCartesianGains::ConstPtr &msg)
void starting ()
void update ()
void zeroFTSensor (const std_msgs::Bool::ConstPtr &msg)
 ~HybridForceController ()

Public Attributes

pr2_hardware_interface::AnalogInanalog_in_
pr2_mechanism_model::Chain chain_
 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
CartVec F_des_
CartVec F_err_last_
CartVec F_integ_
CartVec F_max_
CartVec F_sensor_zero_
std::vector< boost::shared_ptr
< filters::FilterChain< double > > > 
force_filter_
Eigen::Matrix< double, 6, 1 > force_selector
std::string force_torque_frame_
Eigen::Affine3d ft_transform_
Eigen::Vector3d gripper_com_
double gripper_mass_
double jacobian_inverse_damping_
JointVec joint_dd_ff_
double joint_vel_filter_
CartVec K_effective_
double k_posture_
Eigen::Matrix< double, 6, 1 > Kd
Eigen::Matrix< double, 6, 1 > Kfi
Eigen::Matrix< double, 6, 1 > Kfi_max
Eigen::Matrix< double, 6, 1 > Kfp
boost::scoped_ptr< Kin< Joints > > kin_
Eigen::Matrix< double, 6, 1 > Kp
double last_compliance_
double last_Df_
double last_Dx_
Eigen::Affine3d last_pose_
double last_stiffness_
ros::Time last_time_
CartVec last_wrench_
int loop_count_
Eigen::Matrix< double, 6, 1 > motion_selector
ros::NodeHandle node_
double pose_command_filter_
rosrt::Publisher
< geometry_msgs::WrenchStamped > 
pub_f_cmd_
rosrt::Publisher
< geometry_msgs::WrenchStamped > 
pub_f_err_
rosrt::Publisher
< geometry_msgs::WrenchStamped > 
pub_k_effective_
rosrt::Publisher
< std_msgs::Float64MultiArray > 
pub_qdot_
rosrt::Publisher
< geometry_msgs::WrenchStamped > 
pub_sensor_ft_
rosrt::Publisher
< geometry_msgs::WrenchStamped > 
pub_sensor_raw_ft_
rosrt::Publisher< StateMsgpub_state_
rosrt::Publisher
< std_msgs::Float64MultiArray > 
pub_tau_
rosrt::Publisher
< geometry_msgs::Twist > 
pub_wrench_
rosrt::Publisher
< geometry_msgs::PoseStamped > 
pub_x_
rosrt::Publisher
< geometry_msgs::PoseStamped > 
pub_x_desi_
rosrt::Publisher
< geometry_msgs::Twist > 
pub_x_err_
rosrt::Publisher
< geometry_msgs::Twist > 
pub_xd_
rosrt::Publisher
< geometry_msgs::Twist > 
pub_xd_desi_
JointVec q_posture_
std::vector< boost::shared_ptr
< filters::FilterChain< double > > > 
qdot_filter_
JointVec qdot_filtered_
double res_force_
double res_orientation_
double res_position_
double res_torque_
pr2_mechanism_model::RobotStaterobot_state_
std::string root_name_
JointVec saturation_
Eigen::Matrix< double, 6, 6 > St
ros::Subscriber sub_force_
ros::Subscriber sub_ft_params_
ros::Subscriber sub_ft_zero_
ros::Subscriber sub_gains_
ros::Subscriber sub_max_force_
ros::Subscriber sub_pose_
ros::Subscriber sub_posture_
tf::TransformListener tf_
std::string tip_name_
bool use_posture_
bool use_tip_frame_
double vel_saturation_rot_
double vel_saturation_trans_
CartVec wrench_desi_
Eigen::Affine3d x_desi_
Eigen::Affine3d x_desi_filtered_
std::vector< boost::shared_ptr
< filters::FilterChain< double > > > 
xdot_filter_
bool zero_wrench_

Private Types

enum  { Joints = 7 }
typedef Eigen::Matrix< double, 6, 1 > CartVec
typedef Eigen::Matrix< double,
6, Joints
Jacobian
typedef Eigen::Matrix< double,
Joints, 1 > 
JointVec
typedef
pr2_manipulation_controllers::JTTaskControllerState 
StateMsg

Detailed Description

Definition at line 113 of file hybrid_force_controller.cpp.


Member Typedef Documentation

typedef Eigen::Matrix<double, 6, 1> hrl_pr2_force_ctrl::HybridForceController::CartVec [private]

Definition at line 122 of file hybrid_force_controller.cpp.

typedef Eigen::Matrix<double, 6, Joints> hrl_pr2_force_ctrl::HybridForceController::Jacobian [private]

Definition at line 123 of file hybrid_force_controller.cpp.

typedef Eigen::Matrix<double, Joints, 1> hrl_pr2_force_ctrl::HybridForceController::JointVec [private]

Definition at line 121 of file hybrid_force_controller.cpp.

typedef pr2_manipulation_controllers::JTTaskControllerState hrl_pr2_force_ctrl::HybridForceController::StateMsg [private]

Definition at line 124 of file hybrid_force_controller.cpp.


Member Enumeration Documentation

anonymous enum [private]
Enumerator:
Joints 

Definition at line 120 of file hybrid_force_controller.cpp.


Constructor & Destructor Documentation

Definition at line 383 of file hybrid_force_controller.cpp.

Definition at line 387 of file hybrid_force_controller.cpp.


Member Function Documentation

void hrl_pr2_force_ctrl::HybridForceController::commandForce ( const geometry_msgs::WrenchStamped::ConstPtr &  msg) [inline]

Definition at line 345 of file hybrid_force_controller.cpp.

void hrl_pr2_force_ctrl::HybridForceController::commandMaxForce ( const geometry_msgs::WrenchStamped::ConstPtr &  msg) [inline]

Definition at line 374 of file hybrid_force_controller.cpp.

void hrl_pr2_force_ctrl::HybridForceController::commandPose ( const geometry_msgs::PoseStamped::ConstPtr &  command) [inline]

Definition at line 329 of file hybrid_force_controller.cpp.

void hrl_pr2_force_ctrl::HybridForceController::commandPosture ( const std_msgs::Float64MultiArray::ConstPtr &  msg) [inline]

Definition at line 311 of file hybrid_force_controller.cpp.

Implements pr2_controller_interface::Controller.

Definition at line 401 of file hybrid_force_controller.cpp.

void hrl_pr2_force_ctrl::HybridForceController::setFTSensorParams ( const std_msgs::Float64MultiArray::ConstPtr &  msg) [inline]

Definition at line 293 of file hybrid_force_controller.cpp.

void hrl_pr2_force_ctrl::HybridForceController::setGains ( const hrl_pr2_force_ctrl::HybridCartesianGains::ConstPtr &  msg) [inline]

Definition at line 203 of file hybrid_force_controller.cpp.

Reimplemented from pr2_controller_interface::Controller.

Definition at line 642 of file hybrid_force_controller.cpp.

Implements pr2_controller_interface::Controller.

Definition at line 677 of file hybrid_force_controller.cpp.

void hrl_pr2_force_ctrl::HybridForceController::zeroFTSensor ( const std_msgs::Bool::ConstPtr &  msg) [inline]

Definition at line 288 of file hybrid_force_controller.cpp.


Member Data Documentation

Definition at line 191 of file hybrid_force_controller.cpp.

Definition at line 162 of file hybrid_force_controller.cpp.

Definition at line 118 of file hybrid_force_controller.cpp.

Definition at line 197 of file hybrid_force_controller.cpp.

Definition at line 197 of file hybrid_force_controller.cpp.

Definition at line 197 of file hybrid_force_controller.cpp.

Definition at line 197 of file hybrid_force_controller.cpp.

Definition at line 193 of file hybrid_force_controller.cpp.

Definition at line 201 of file hybrid_force_controller.cpp.

Definition at line 167 of file hybrid_force_controller.cpp.

Definition at line 192 of file hybrid_force_controller.cpp.

Definition at line 196 of file hybrid_force_controller.cpp.

Definition at line 195 of file hybrid_force_controller.cpp.

Definition at line 194 of file hybrid_force_controller.cpp.

Definition at line 173 of file hybrid_force_controller.cpp.

Definition at line 171 of file hybrid_force_controller.cpp.

Definition at line 172 of file hybrid_force_controller.cpp.

Definition at line 197 of file hybrid_force_controller.cpp.

Definition at line 175 of file hybrid_force_controller.cpp.

Definition at line 164 of file hybrid_force_controller.cpp.

Definition at line 167 of file hybrid_force_controller.cpp.

Definition at line 167 of file hybrid_force_controller.cpp.

Definition at line 167 of file hybrid_force_controller.cpp.

Definition at line 163 of file hybrid_force_controller.cpp.

Definition at line 164 of file hybrid_force_controller.cpp.

Definition at line 184 of file hybrid_force_controller.cpp.

Definition at line 185 of file hybrid_force_controller.cpp.

Definition at line 185 of file hybrid_force_controller.cpp.

Definition at line 182 of file hybrid_force_controller.cpp.

Definition at line 184 of file hybrid_force_controller.cpp.

Definition at line 158 of file hybrid_force_controller.cpp.

Definition at line 183 of file hybrid_force_controller.cpp.

Definition at line 159 of file hybrid_force_controller.cpp.

Definition at line 167 of file hybrid_force_controller.cpp.

Definition at line 136 of file hybrid_force_controller.cpp.

Definition at line 168 of file hybrid_force_controller.cpp.

rosrt::Publisher<geometry_msgs::WrenchStamped> hrl_pr2_force_ctrl::HybridForceController::pub_f_cmd_

Definition at line 154 of file hybrid_force_controller.cpp.

rosrt::Publisher<geometry_msgs::WrenchStamped> hrl_pr2_force_ctrl::HybridForceController::pub_f_err_

Definition at line 154 of file hybrid_force_controller.cpp.

rosrt::Publisher<geometry_msgs::WrenchStamped> hrl_pr2_force_ctrl::HybridForceController::pub_k_effective_

Definition at line 155 of file hybrid_force_controller.cpp.

rosrt::Publisher<std_msgs::Float64MultiArray> hrl_pr2_force_ctrl::HybridForceController::pub_qdot_

Definition at line 151 of file hybrid_force_controller.cpp.

rosrt::Publisher<geometry_msgs::WrenchStamped> hrl_pr2_force_ctrl::HybridForceController::pub_sensor_ft_

Definition at line 152 of file hybrid_force_controller.cpp.

rosrt::Publisher<geometry_msgs::WrenchStamped> hrl_pr2_force_ctrl::HybridForceController::pub_sensor_raw_ft_

Definition at line 153 of file hybrid_force_controller.cpp.

Definition at line 146 of file hybrid_force_controller.cpp.

rosrt::Publisher<std_msgs::Float64MultiArray> hrl_pr2_force_ctrl::HybridForceController::pub_tau_

Definition at line 150 of file hybrid_force_controller.cpp.

rosrt::Publisher<geometry_msgs::Twist> hrl_pr2_force_ctrl::HybridForceController::pub_wrench_

Definition at line 149 of file hybrid_force_controller.cpp.

rosrt::Publisher<geometry_msgs::PoseStamped> hrl_pr2_force_ctrl::HybridForceController::pub_x_

Definition at line 147 of file hybrid_force_controller.cpp.

rosrt::Publisher<geometry_msgs::PoseStamped> hrl_pr2_force_ctrl::HybridForceController::pub_x_desi_

Definition at line 147 of file hybrid_force_controller.cpp.

rosrt::Publisher<geometry_msgs::Twist> hrl_pr2_force_ctrl::HybridForceController::pub_x_err_

Definition at line 149 of file hybrid_force_controller.cpp.

rosrt::Publisher<geometry_msgs::Twist> hrl_pr2_force_ctrl::HybridForceController::pub_xd_

Definition at line 148 of file hybrid_force_controller.cpp.

rosrt::Publisher<geometry_msgs::Twist> hrl_pr2_force_ctrl::HybridForceController::pub_xd_desi_

Definition at line 148 of file hybrid_force_controller.cpp.

Definition at line 174 of file hybrid_force_controller.cpp.

Definition at line 201 of file hybrid_force_controller.cpp.

Definition at line 188 of file hybrid_force_controller.cpp.

Definition at line 179 of file hybrid_force_controller.cpp.

Definition at line 180 of file hybrid_force_controller.cpp.

Definition at line 179 of file hybrid_force_controller.cpp.

Definition at line 180 of file hybrid_force_controller.cpp.

Definition at line 160 of file hybrid_force_controller.cpp.

Definition at line 157 of file hybrid_force_controller.cpp.

Definition at line 170 of file hybrid_force_controller.cpp.

Definition at line 165 of file hybrid_force_controller.cpp.

Definition at line 140 of file hybrid_force_controller.cpp.

Definition at line 143 of file hybrid_force_controller.cpp.

Definition at line 142 of file hybrid_force_controller.cpp.

Definition at line 137 of file hybrid_force_controller.cpp.

Definition at line 141 of file hybrid_force_controller.cpp.

Definition at line 139 of file hybrid_force_controller.cpp.

Definition at line 138 of file hybrid_force_controller.cpp.

Definition at line 144 of file hybrid_force_controller.cpp.

Definition at line 157 of file hybrid_force_controller.cpp.

Definition at line 176 of file hybrid_force_controller.cpp.

Definition at line 166 of file hybrid_force_controller.cpp.

Definition at line 169 of file hybrid_force_controller.cpp.

Definition at line 169 of file hybrid_force_controller.cpp.

Definition at line 134 of file hybrid_force_controller.cpp.

Definition at line 133 of file hybrid_force_controller.cpp.

Definition at line 133 of file hybrid_force_controller.cpp.

Definition at line 201 of file hybrid_force_controller.cpp.

Definition at line 198 of file hybrid_force_controller.cpp.


The documentation for this class was generated from the following file:


hrl_pr2_force_ctrl
Author(s): Kelsey Hawkins
autogenerated on Wed Nov 27 2013 11:42:28