Public Member Functions | Public Attributes | Private Types | List of all members
controller::JTCartesianController Class Reference

#include <jt_cartesian_controller.h>

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

Public Member Functions

void commandPose (const geometry_msgs::PoseStamped::ConstPtr &command)
 
void commandPosture (const std_msgs::Float64MultiArray::ConstPtr &msg)
 
bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 
 JTCartesianController ()
 
void setGains (const std_msgs::Float64MultiArray::ConstPtr &msg)
 
void starting ()
 
void update ()
 
 ~JTCartesianController ()
 
- 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

pr2_mechanism_model::Chain chain_
 
 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
double jacobian_inverse_damping_
 
JointVec joint_dd_ff_
 
double joint_vel_filter_
 
double k_posture_
 
Eigen::Matrix< double, 6, 1 > Kd
 
boost::scoped_ptr< Kin< Joints > > kin_
 
Eigen::Matrix< double, 6, 1 > Kp
 
Eigen::Affine3d last_pose_
 
ros::Time last_time_
 
CartVec last_wrench_
 
int loop_count_
 
ros::NodeHandle node_
 
double pose_command_filter_
 
realtime_tools::RealtimePublisher< StateMsgpub_state_
 
realtime_tools::RealtimePublisher< geometry_msgs::PoseStamped > pub_x_desi_
 
JointVec q_posture_
 
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_
 
ros::Subscriber sub_gains_
 
ros::Subscriber sub_pose_
 
ros::Subscriber sub_posture_
 
tf::TransformListener tf_
 
std::string tip_name_
 
bool use_posture_
 
double vel_saturation_rot_
 
double vel_saturation_trans_
 
CartVec wrench_desi_
 
Eigen::Affine3d x_desi_
 
Eigen::Affine3d x_desi_filtered_
 
- 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 Types

enum  { Joints = 7 }
 
typedef Eigen::Matrix< double, 6, 1 > CartVec
 
typedef Eigen::Matrix< double, 6, JointsJacobian
 
typedef Eigen::Matrix< double, Joints, 1 > JointVec
 
typedef robot_mechanism_controllers::JTCartesianControllerState StateMsg
 

Detailed Description

Definition at line 134 of file jt_cartesian_controller.h.

Member Typedef Documentation

◆ CartVec

typedef Eigen::Matrix<double, 6, 1> controller::JTCartesianController::CartVec
private

Definition at line 143 of file jt_cartesian_controller.h.

◆ Jacobian

typedef Eigen::Matrix<double, 6, Joints> controller::JTCartesianController::Jacobian
private

Definition at line 144 of file jt_cartesian_controller.h.

◆ JointVec

typedef Eigen::Matrix<double, Joints, 1> controller::JTCartesianController::JointVec
private

Definition at line 142 of file jt_cartesian_controller.h.

◆ StateMsg

typedef robot_mechanism_controllers::JTCartesianControllerState controller::JTCartesianController::StateMsg
private

Definition at line 145 of file jt_cartesian_controller.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
private
Enumerator
Joints 

Definition at line 141 of file jt_cartesian_controller.h.

Constructor & Destructor Documentation

◆ JTCartesianController()

controller::JTCartesianController::JTCartesianController ( )

Definition at line 83 of file jt_cartesian_controller.cpp.

◆ ~JTCartesianController()

controller::JTCartesianController::~JTCartesianController ( )

Definition at line 87 of file jt_cartesian_controller.cpp.

Member Function Documentation

◆ commandPose()

void controller::JTCartesianController::commandPose ( const geometry_msgs::PoseStamped::ConstPtr &  command)
inline

Definition at line 224 of file jt_cartesian_controller.h.

◆ commandPosture()

void controller::JTCartesianController::commandPosture ( const std_msgs::Float64MultiArray::ConstPtr &  msg)
inline

Definition at line 206 of file jt_cartesian_controller.h.

◆ init()

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

Implements pr2_controller_interface::Controller.

Definition at line 95 of file jt_cartesian_controller.cpp.

◆ setGains()

void controller::JTCartesianController::setGains ( const std_msgs::Float64MultiArray::ConstPtr &  msg)
inline

Definition at line 193 of file jt_cartesian_controller.h.

◆ starting()

void controller::JTCartesianController::starting ( )
virtual

Reimplemented from pr2_controller_interface::Controller.

Definition at line 206 of file jt_cartesian_controller.cpp.

◆ update()

void controller::JTCartesianController::update ( )
virtual

Implements pr2_controller_interface::Controller.

Definition at line 232 of file jt_cartesian_controller.cpp.

Member Data Documentation

◆ chain_

pr2_mechanism_model::Chain controller::JTCartesianController::chain_

Definition at line 171 of file jt_cartesian_controller.h.

◆ EIGEN_MAKE_ALIGNED_OPERATOR_NEW

controller::JTCartesianController::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 139 of file jt_cartesian_controller.h.

◆ jacobian_inverse_damping_

double controller::JTCartesianController::jacobian_inverse_damping_

Definition at line 179 of file jt_cartesian_controller.h.

◆ joint_dd_ff_

JointVec controller::JTCartesianController::joint_dd_ff_

Definition at line 177 of file jt_cartesian_controller.h.

◆ joint_vel_filter_

double controller::JTCartesianController::joint_vel_filter_

Definition at line 178 of file jt_cartesian_controller.h.

◆ k_posture_

double controller::JTCartesianController::k_posture_

Definition at line 181 of file jt_cartesian_controller.h.

◆ Kd

Eigen::Matrix<double,6,1> controller::JTCartesianController::Kd

Definition at line 173 of file jt_cartesian_controller.h.

◆ kin_

boost::scoped_ptr<Kin<Joints> > controller::JTCartesianController::kin_

Definition at line 172 of file jt_cartesian_controller.h.

◆ Kp

Eigen::Matrix<double,6,1> controller::JTCartesianController::Kp

Definition at line 173 of file jt_cartesian_controller.h.

◆ last_pose_

Eigen::Affine3d controller::JTCartesianController::last_pose_

Definition at line 188 of file jt_cartesian_controller.h.

◆ last_time_

ros::Time controller::JTCartesianController::last_time_

Definition at line 167 of file jt_cartesian_controller.h.

◆ last_wrench_

CartVec controller::JTCartesianController::last_wrench_

Definition at line 189 of file jt_cartesian_controller.h.

◆ loop_count_

int controller::JTCartesianController::loop_count_

Definition at line 168 of file jt_cartesian_controller.h.

◆ node_

ros::NodeHandle controller::JTCartesianController::node_

Definition at line 157 of file jt_cartesian_controller.h.

◆ pose_command_filter_

double controller::JTCartesianController::pose_command_filter_

Definition at line 174 of file jt_cartesian_controller.h.

◆ pub_state_

realtime_tools::RealtimePublisher<StateMsg> controller::JTCartesianController::pub_state_

Definition at line 163 of file jt_cartesian_controller.h.

◆ pub_x_desi_

realtime_tools::RealtimePublisher<geometry_msgs::PoseStamped> controller::JTCartesianController::pub_x_desi_

Definition at line 164 of file jt_cartesian_controller.h.

◆ q_posture_

JointVec controller::JTCartesianController::q_posture_

Definition at line 180 of file jt_cartesian_controller.h.

◆ qdot_filtered_

JointVec controller::JTCartesianController::qdot_filtered_

Definition at line 191 of file jt_cartesian_controller.h.

◆ res_force_

double controller::JTCartesianController::res_force_

Definition at line 185 of file jt_cartesian_controller.h.

◆ res_orientation_

double controller::JTCartesianController::res_orientation_

Definition at line 186 of file jt_cartesian_controller.h.

◆ res_position_

double controller::JTCartesianController::res_position_

Definition at line 185 of file jt_cartesian_controller.h.

◆ res_torque_

double controller::JTCartesianController::res_torque_

Definition at line 186 of file jt_cartesian_controller.h.

◆ robot_state_

pr2_mechanism_model::RobotState* controller::JTCartesianController::robot_state_

Definition at line 169 of file jt_cartesian_controller.h.

◆ root_name_

std::string controller::JTCartesianController::root_name_

Definition at line 166 of file jt_cartesian_controller.h.

◆ saturation_

JointVec controller::JTCartesianController::saturation_

Definition at line 176 of file jt_cartesian_controller.h.

◆ sub_gains_

ros::Subscriber controller::JTCartesianController::sub_gains_

Definition at line 158 of file jt_cartesian_controller.h.

◆ sub_pose_

ros::Subscriber controller::JTCartesianController::sub_pose_

Definition at line 160 of file jt_cartesian_controller.h.

◆ sub_posture_

ros::Subscriber controller::JTCartesianController::sub_posture_

Definition at line 159 of file jt_cartesian_controller.h.

◆ tf_

tf::TransformListener controller::JTCartesianController::tf_

Definition at line 161 of file jt_cartesian_controller.h.

◆ tip_name_

std::string controller::JTCartesianController::tip_name_

Definition at line 166 of file jt_cartesian_controller.h.

◆ use_posture_

bool controller::JTCartesianController::use_posture_

Definition at line 182 of file jt_cartesian_controller.h.

◆ vel_saturation_rot_

double controller::JTCartesianController::vel_saturation_rot_

Definition at line 175 of file jt_cartesian_controller.h.

◆ vel_saturation_trans_

double controller::JTCartesianController::vel_saturation_trans_

Definition at line 175 of file jt_cartesian_controller.h.

◆ wrench_desi_

CartVec controller::JTCartesianController::wrench_desi_

Definition at line 155 of file jt_cartesian_controller.h.

◆ x_desi_

Eigen::Affine3d controller::JTCartesianController::x_desi_

Definition at line 154 of file jt_cartesian_controller.h.

◆ x_desi_filtered_

Eigen::Affine3d controller::JTCartesianController::x_desi_filtered_

Definition at line 154 of file jt_cartesian_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