25 #ifndef ABSTRACTKATANA_H_ 26 #define ABSTRACTKATANA_H_ 30 #include <urdf_model/joint.h> 35 #include <moveit_msgs/JointLimits.h> 48 boost::function<
bool()> isPreemptRequested) = 0;
59 virtual bool moveJoint(
int jointIndex,
double turningAngle) = 0;
virtual std::vector< std::string > getJointNames()
virtual int getJointIndex(std::string joint_name)
virtual bool executeTrajectory(boost::shared_ptr< SpecifiedTrajectory > traj, boost::function< bool()> isPreemptRequested)=0
virtual double getMotorLimitMin(std::string joint_name)
std::vector< double > motor_angles_
std::vector< int > joint_types_
virtual bool allJointsReady()=0
std::vector< int > gripper_joint_types_
virtual std::vector< int > getGripperJointTypes()
std::vector< double > motor_velocities_
std::vector< std::string > joint_names_
virtual bool someMotorCrashed()=0
virtual bool allMotorsReady()=0
virtual bool moveJoint(int jointIndex, double turningAngle)=0
std::vector< moveit_msgs::JointLimits > motor_limits_
virtual ~AbstractKatana()
virtual std::vector< std::string > getGripperJointNames()
virtual std::vector< double > getMotorVelocities()
virtual std::vector< double > getMotorAngles()
virtual void refreshEncoders()=0
virtual void freezeRobot()
std::vector< std::string > gripper_joint_names_
virtual std::vector< int > getJointTypes()
virtual void refreshMotorStatus()
virtual double getMotorLimitMax(std::string joint_name)
virtual std::vector< moveit_msgs::JointLimits > getMotorLimits()