47 #include <std_msgs/Int8.h> 96 bool addJointIncrements(sensor_msgs::JointState& output,
const Eigen::VectorXd& increments)
const;
101 void suddenHalt(trajectory_msgs::JointTrajectory& joint_traj);
117 const Eigen::JacobiSVD<Eigen::MatrixXd>& svd,
118 const Eigen::MatrixXd& jacobian,
const Eigen::MatrixXd& pseudo_inverse);
154 void removeDimension(Eigen::MatrixXd& matrix, Eigen::VectorXd& delta_x,
unsigned int row_to_remove);
void enforceSRDFAccelVelLimits(Eigen::ArrayXd &delta_theta)
Scale the delta theta to match joint velocity/acceleration limits.
Eigen::ArrayXd prev_joint_velocity_
ros::Publisher status_pub_
moveit::core::RobotStatePtr kinematic_state_
void lowPassFilterPositions(sensor_msgs::JointState &joint_state)
Smooth position commands with a lowpass filter.
std::vector< LowPassFilter > position_filters_
trajectory_msgs::JointTrajectory composeJointTrajMessage(sensor_msgs::JointState &joint_state) const
Compose the outgoing JointTrajectory message.
double velocityScalingFactorForSingularity(const Eigen::VectorXd &commanded_velocity, const Eigen::JacobiSVD< Eigen::MatrixXd > &svd, const Eigen::MatrixXd &jacobian, const Eigen::MatrixXd &pseudo_inverse)
Possibly calculate a velocity scaling factor, due to proximity of singularity and direction of motion...
void insertRedundantPointsIntoTrajectory(trajectory_msgs::JointTrajectory &trajectory, int count) const
Gazebo simulations have very strict message timestamp requirements. Satisfy Gazebo by stuffing multip...
void updateCachedStatus(JogArmShared &shared_variables)
Update the stashed status so it can be retrieved asynchronously.
bool addJointIncrements(sensor_msgs::JointState &output, const Eigen::VectorXd &increments) const
JogCalcs(const JogArmParameters ¶meters, const robot_model_loader::RobotModelLoaderPtr &model_loader_ptr)
bool enforceSRDFPositionLimits(trajectory_msgs::JointTrajectory &new_joint_traj)
Avoid overshooting joint limits.
bool jointJogCalcs(const control_msgs::JointJog &cmd, JogArmShared &shared_variables)
Do jogging calculations for direct commands to a joint.
bool convertDeltasToOutgoingCmd()
Convert joint deltas to an outgoing JointTrajectory command. This happens for joint commands and Cart...
ros::Rate default_sleep_rate_
bool isInitialized()
Check if the robot state is being updated and the end effector transform is known.
bool cartesianJogCalcs(geometry_msgs::TwistStamped &cmd, JogArmShared &shared_variables)
Do jogging calculations for Cartesian twist commands.
void applyVelocityScaling(JogArmShared &shared_variables, Eigen::ArrayXd &delta_theta, double singularity_scale)
JogArmParameters parameters_
sensor_msgs::JointState incoming_joint_state_
Eigen::VectorXd scaleJointCommand(const control_msgs::JointJog &command) const
If incoming velocity commands are from a unitless joystick, scale them to physical units...
std::map< std::string, std::size_t > joint_state_name_map_
sensor_msgs::JointState internal_joint_state_
void calculateJointVelocities(sensor_msgs::JointState &joint_state, const Eigen::ArrayXd &delta_theta)
Convert an incremental position command to joint velocity message.
void publishStatus() const
Publish the status of the jogger to a ROS topic.
std::atomic< bool > is_initialized_
void suddenHalt(trajectory_msgs::JointTrajectory &joint_traj)
Suddenly halt for a joint limit or other critical issue. Is handled differently for position vs...
const int gazebo_redundant_message_count_
bool updateJoints(JogArmShared &shared_variables)
Parse the incoming joint msg for the joints of our MoveGroup.
const moveit::core::JointModelGroup * joint_model_group_
Eigen::VectorXd scaleCartesianCommand(const geometry_msgs::TwistStamped &command) const
If incoming velocity commands are from a unitless joystick, scale them to physical units...
sensor_msgs::JointState original_joint_state_
Eigen::Isometry3d tf_moveit_to_cmd_frame_
void removeDimension(Eigen::MatrixXd &matrix, Eigen::VectorXd &delta_x, unsigned int row_to_remove)
Eigen::ArrayXd delta_theta_
void startMainLoop(JogArmShared &shared_variables)
trajectory_msgs::JointTrajectory outgoing_command_