Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jog_arm::JogCalcs Class Reference

#include <jog_arm_server.h>

Public Member Functions

 JogCalcs (const jog_arm_parameters &parameters, jog_arm_shared &shared_variables, const std::unique_ptr< robot_model_loader::RobotModelLoader > &model_loader_ptr)
 

Protected Member Functions

bool addJointIncrements (sensor_msgs::JointState &output, const Eigen::VectorXd &increments) const
 
bool applyVelocityScaling (jog_arm_shared &shared_variables, trajectory_msgs::JointTrajectory &new_jt_traj, const Eigen::VectorXd &delta_theta, double singularity_scale)
 
bool cartesianJogCalcs (const geometry_msgs::TwistStamped &cmd, jog_arm_shared &shared_variables)
 
bool checkIfJointsWithinBounds (trajectory_msgs::JointTrajectory_< std::allocator< void >> &new_jt_traj)
 
trajectory_msgs::JointTrajectory composeOutgoingMessage (sensor_msgs::JointState &joint_state, const ros::Time &stamp) const
 
double decelerateForSingularity (Eigen::MatrixXd jacobian, const Eigen::VectorXd commanded_velocity)
 
void enforceJointVelocityLimits (Eigen::VectorXd &calculated_joint_vel)
 
void halt (trajectory_msgs::JointTrajectory &jt_traj)
 
void insertRedundantPointsIntoTrajectory (trajectory_msgs::JointTrajectory &trajectory, int count) const
 
bool jointJogCalcs (const jog_msgs::JogJoint &cmd, jog_arm_shared &shared_variables)
 
void lowPassFilterPositions ()
 
void lowPassFilterVelocities (const Eigen::VectorXd &joint_vel)
 
Eigen::MatrixXd pseudoInverse (const Eigen::MatrixXd &J) const
 
Eigen::MatrixXd pseudoInverse (const Eigen::MatrixXd &u_matrix, const Eigen::MatrixXd &v_matrix, const Eigen::MatrixXd &s_diagonals) const
 
void publishWarning (bool active) const
 
void resetVelocityFilters ()
 
Eigen::VectorXd scaleCartesianCommand (const geometry_msgs::TwistStamped &command) const
 
Eigen::VectorXd scaleJointCommand (const jog_msgs::JogJoint &command) const
 
bool updateJoints ()
 

Protected Attributes

sensor_msgs::JointState incoming_jts_
 
const robot_state::JointModelGroup * joint_model_group_
 
sensor_msgs::JointState jt_state_
 
robot_state::RobotStatePtr kinematic_state_
 
tf::TransformListener listener_
 
moveit::planning_interface::MoveGroupInterface move_group_
 
trajectory_msgs::JointTrajectory new_traj_
 
ros::NodeHandle nh_
 
sensor_msgs::JointState original_jts_
 
jog_arm_parameters parameters_
 
std::vector< jog_arm::LowPassFilterposition_filters_
 
std::vector< jog_arm::LowPassFiltervelocity_filters_
 
ros::Publisher warning_pub_
 

Detailed Description

Class JogCalcs - Perform the Jacobian calculations.

Definition at line 198 of file jog_arm_server.h.

Constructor & Destructor Documentation

jog_arm::JogCalcs::JogCalcs ( const jog_arm_parameters parameters,
jog_arm_shared shared_variables,
const std::unique_ptr< robot_model_loader::RobotModelLoader > &  model_loader_ptr 
)

Definition at line 302 of file jog_arm_server.cpp.

Member Function Documentation

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

Definition at line 1023 of file jog_arm_server.cpp.

bool jog_arm::JogCalcs::applyVelocityScaling ( jog_arm_shared shared_variables,
trajectory_msgs::JointTrajectory &  new_jt_traj,
const Eigen::VectorXd &  delta_theta,
double  singularity_scale 
)
protected

Definition at line 713 of file jog_arm_server.cpp.

bool jog_arm::JogCalcs::cartesianJogCalcs ( const geometry_msgs::TwistStamped &  cmd,
jog_arm_shared shared_variables 
)
protected

Definition at line 470 of file jog_arm_server.cpp.

bool jog_arm::JogCalcs::checkIfJointsWithinBounds ( trajectory_msgs::JointTrajectory_< std::allocator< void >> &  new_jt_traj)
protected

Definition at line 827 of file jog_arm_server.cpp.

trajectory_msgs::JointTrajectory jog_arm::JogCalcs::composeOutgoingMessage ( sensor_msgs::JointState &  joint_state,
const ros::Time stamp 
) const
protected

Definition at line 682 of file jog_arm_server.cpp.

double jog_arm::JogCalcs::decelerateForSingularity ( Eigen::MatrixXd  jacobian,
const Eigen::VectorXd  commanded_velocity 
)
protected

Definition at line 748 of file jog_arm_server.cpp.

void jog_arm::JogCalcs::enforceJointVelocityLimits ( Eigen::VectorXd &  calculated_joint_vel)
protected

Definition at line 736 of file jog_arm_server.cpp.

void jog_arm::JogCalcs::halt ( trajectory_msgs::JointTrajectory &  jt_traj)
protected

Definition at line 894 of file jog_arm_server.cpp.

void jog_arm::JogCalcs::insertRedundantPointsIntoTrajectory ( trajectory_msgs::JointTrajectory &  trajectory,
int  count 
) const
protected

Definition at line 639 of file jog_arm_server.cpp.

bool jog_arm::JogCalcs::jointJogCalcs ( const jog_msgs::JogJoint &  cmd,
jog_arm_shared shared_variables 
)
protected

Definition at line 580 of file jog_arm_server.cpp.

void jog_arm::JogCalcs::lowPassFilterPositions ( )
protected

Definition at line 651 of file jog_arm_server.cpp.

void jog_arm::JogCalcs::lowPassFilterVelocities ( const Eigen::VectorXd &  joint_vel)
protected

Definition at line 666 of file jog_arm_server.cpp.

Eigen::MatrixXd jog_arm::JogCalcs::pseudoInverse ( const Eigen::MatrixXd &  J) const
protected

Definition at line 1012 of file jog_arm_server.cpp.

Eigen::MatrixXd jog_arm::JogCalcs::pseudoInverse ( const Eigen::MatrixXd &  u_matrix,
const Eigen::MatrixXd &  v_matrix,
const Eigen::MatrixXd &  s_diagonals 
) const
protected

Definition at line 1017 of file jog_arm_server.cpp.

void jog_arm::JogCalcs::publishWarning ( bool  active) const
protected

Definition at line 885 of file jog_arm_server.cpp.

void jog_arm::JogCalcs::resetVelocityFilters ( )
protected

Definition at line 911 of file jog_arm_server.cpp.

Eigen::VectorXd jog_arm::JogCalcs::scaleCartesianCommand ( const geometry_msgs::TwistStamped &  command) const
protected

Definition at line 948 of file jog_arm_server.cpp.

Eigen::VectorXd jog_arm::JogCalcs::scaleJointCommand ( const jog_msgs::JogJoint &  command) const
protected

Definition at line 978 of file jog_arm_server.cpp.

bool jog_arm::JogCalcs::updateJoints ( )
protected

Definition at line 918 of file jog_arm_server.cpp.

Member Data Documentation

sensor_msgs::JointState jog_arm::JogCalcs::incoming_jts_
protected

Definition at line 209 of file jog_arm_server.h.

const robot_state::JointModelGroup* jog_arm::JogCalcs::joint_model_group_
protected

Definition at line 259 of file jog_arm_server.h.

sensor_msgs::JointState jog_arm::JogCalcs::jt_state_
protected

Definition at line 263 of file jog_arm_server.h.

robot_state::RobotStatePtr jog_arm::JogCalcs::kinematic_state_
protected

Definition at line 261 of file jog_arm_server.h.

tf::TransformListener jog_arm::JogCalcs::listener_
protected

Definition at line 266 of file jog_arm_server.h.

moveit::planning_interface::MoveGroupInterface jog_arm::JogCalcs::move_group_
protected

Definition at line 207 of file jog_arm_server.h.

trajectory_msgs::JointTrajectory jog_arm::JogCalcs::new_traj_
protected

Definition at line 264 of file jog_arm_server.h.

ros::NodeHandle jog_arm::JogCalcs::nh_
protected

Definition at line 205 of file jog_arm_server.h.

sensor_msgs::JointState jog_arm::JogCalcs::original_jts_
protected

Definition at line 263 of file jog_arm_server.h.

jog_arm_parameters jog_arm::JogCalcs::parameters_
protected

Definition at line 273 of file jog_arm_server.h.

std::vector<jog_arm::LowPassFilter> jog_arm::JogCalcs::position_filters_
protected

Definition at line 269 of file jog_arm_server.h.

std::vector<jog_arm::LowPassFilter> jog_arm::JogCalcs::velocity_filters_
protected

Definition at line 268 of file jog_arm_server.h.

ros::Publisher jog_arm::JogCalcs::warning_pub_
protected

Definition at line 271 of file jog_arm_server.h.


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


jog_arm
Author(s): Brian O'Neil, Andy Zelenak , Blake Anderson, Nitish Sharma, Alexander Rössler
autogenerated on Mon Jun 10 2019 13:47:53