Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes
jog_arm::JogArmServer Class Reference

#include <jog_arm_server.h>

List of all members.

Public Member Functions

 JogArmServer (std::string move_group_name, std::string cmd_topic_name)

Protected Types

typedef Eigen::Matrix< double, 6, 1 > Vector6d

Protected Member Functions

bool addJointIncrements (sensor_msgs::JointState &output, const Eigen::VectorXd &increments) const
bool checkConditionNumber (const Eigen::MatrixXd &matrix, double threshold) const
void commandCB (geometry_msgs::TwistStampedConstPtr msg)
void jointStateCB (sensor_msgs::JointStateConstPtr msg)
Eigen::MatrixXd pseudoInverse (const Eigen::MatrixXd &J) const
Vector6d scaleCommand (const geometry_msgs::TwistStamped &command, const Vector6d &scalar) const

Protected Attributes

moveit::planning_interface::MoveGroup arm_
ros::Subscriber cmd_sub_
sensor_msgs::JointState current_joints_
const
robot_state::JointModelGroup * 
joint_model_group_
std::vector< std::string > joint_names_
ros::Subscriber joint_sub_
robot_state::RobotStatePtr kinematic_state_
tf::TransformListener listener_
ros::NodeHandle nh_
ros::AsyncSpinner spinner_

Detailed Description

Class JogArmServer - Provides the jog_arm action.

Definition at line 54 of file jog_arm_server.h.


Member Typedef Documentation

typedef Eigen::Matrix<double, 6, 1> jog_arm::JogArmServer::Vector6d [protected]

Definition at line 64 of file jog_arm_server.h.


Constructor & Destructor Documentation

jog_arm::JogArmServer::JogArmServer ( std::string  move_group_name,
std::string  cmd_topic_name 
)

: Default constructor for JogArmServer Class.

Topic Setup

MoveIt Setup

Definition at line 35 of file jog_arm_server.cpp.


Member Function Documentation

bool jog_arm::JogArmServer::addJointIncrements ( sensor_msgs::JointState &  output,
const Eigen::VectorXd &  increments 
) const [protected]

Definition at line 176 of file jog_arm_server.cpp.

bool jog_arm::JogArmServer::checkConditionNumber ( const Eigen::MatrixXd &  matrix,
double  threshold 
) const [protected]

Definition at line 190 of file jog_arm_server.cpp.

void jog_arm::JogArmServer::commandCB ( geometry_msgs::TwistStampedConstPtr  msg) [protected]

Definition at line 69 of file jog_arm_server.cpp.

void jog_arm::JogArmServer::jointStateCB ( sensor_msgs::JointStateConstPtr  msg) [protected]

Definition at line 141 of file jog_arm_server.cpp.

Eigen::MatrixXd jog_arm::JogArmServer::pseudoInverse ( const Eigen::MatrixXd &  J) const [protected]

Definition at line 170 of file jog_arm_server.cpp.

JogArmServer::Vector6d jog_arm::JogArmServer::scaleCommand ( const geometry_msgs::TwistStamped &  command,
const Vector6d scalar 
) const [protected]

Definition at line 156 of file jog_arm_server.cpp.


Member Data Documentation

Definition at line 82 of file jog_arm_server.h.

Definition at line 80 of file jog_arm_server.h.

sensor_msgs::JointState jog_arm::JogArmServer::current_joints_ [protected]

Definition at line 86 of file jog_arm_server.h.

const robot_state::JointModelGroup* jog_arm::JogArmServer::joint_model_group_ [protected]

Definition at line 83 of file jog_arm_server.h.

std::vector<std::string> jog_arm::JogArmServer::joint_names_ [protected]

Definition at line 88 of file jog_arm_server.h.

Definition at line 80 of file jog_arm_server.h.

robot_state::RobotStatePtr jog_arm::JogArmServer::kinematic_state_ [protected]

Definition at line 84 of file jog_arm_server.h.

Definition at line 92 of file jog_arm_server.h.

Definition at line 78 of file jog_arm_server.h.

Definition at line 90 of file jog_arm_server.h.


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


jog_arm
Author(s): Brian O'Neil, Blake Anderson , Andy Zelenak
autogenerated on Mon Apr 3 2017 04:04:12