Public Member Functions | Public Attributes | Private Attributes | List of all members
katana::Katana300 Class Reference

#include <Katana300.h>

Inheritance diagram for katana::Katana300:
Inheritance graph
[legend]

Public Member Functions

virtual bool allJointsReady ()
 
virtual bool allMotorsReady ()
 
virtual bool executeTrajectory (boost::shared_ptr< SpecifiedTrajectory > traj, boost::function< bool()> isPreemptRequested)
 
virtual void freezeRobot ()
 
 Katana300 ()
 
virtual bool moveJoint (int jointIndex, double turningAngle)
 
virtual void refreshMotorStatus ()
 
virtual void setLimits ()
 
virtual void testSpeed ()
 
virtual ~Katana300 ()
 
- Public Member Functions inherited from katana::Katana
 Katana ()
 
void refreshEncoders ()
 
virtual bool someMotorCrashed ()
 
virtual ~Katana ()
 
- Public Member Functions inherited from katana::AbstractKatana
 AbstractKatana ()
 
virtual std::vector< std::string > getGripperJointNames ()
 
virtual std::vector< int > getGripperJointTypes ()
 
virtual int getJointIndex (std::string joint_name)
 
virtual std::vector< std::string > getJointNames ()
 
virtual std::vector< int > getJointTypes ()
 
virtual std::vector< double > getMotorAngles ()
 
virtual double getMotorLimitMax (std::string joint_name)
 
virtual double getMotorLimitMin (std::string joint_name)
 
virtual std::vector< moveit_msgs::JointLimits > getMotorLimits ()
 
virtual std::vector< double > getMotorVelocities ()
 
virtual ~AbstractKatana ()
 

Public Attributes

const double JOINTS_STOPPED_POS_TOLERANCE = 0.01
 
const double JOINTS_STOPPED_VEL_TOLERANCE = 0.01
 

Private Attributes

std::vector< double > desired_angles_
 

Additional Inherited Members

- Protected Member Functions inherited from katana::Katana
short round (const double x)
 
- Protected Attributes inherited from katana::Katana
KNIConverterconverter
 
boost::shared_ptr< CLMBasekni
 
boost::recursive_mutex kni_mutex
 
std::vector< TMotStsFlgmotor_status_
 
- Protected Attributes inherited from katana::AbstractKatana
std::vector< std::string > gripper_joint_names_
 
std::vector< int > gripper_joint_types_
 
std::vector< std::string > joint_names_
 
std::vector< int > joint_types_
 
std::vector< double > motor_angles_
 
std::vector< moveit_msgs::JointLimits > motor_limits_
 
std::vector< double > motor_velocities_
 

Detailed Description

Definition at line 44 of file Katana300.h.

Constructor & Destructor Documentation

katana::Katana300::Katana300 ( )

Definition at line 33 of file Katana300.cpp.

katana::Katana300::~Katana300 ( )
virtual

Definition at line 40 of file Katana300.cpp.

Member Function Documentation

bool katana::Katana300::allJointsReady ( )
virtual

The Katana 300 never returns MSF_DESPOS or MSF_NLINMOV, so we have to check manually whether the arm stopped at the target position.

Reimplemented from katana::Katana.

Definition at line 103 of file Katana300.cpp.

bool katana::Katana300::allMotorsReady ( )
virtual

The Katana 300 never returns MSF_DESPOS or MSF_NLINMOV, so we have to check manually whether the arm stopped at the target position.

Reimplemented from katana::Katana.

Definition at line 124 of file Katana300.cpp.

bool katana::Katana300::executeTrajectory ( boost::shared_ptr< SpecifiedTrajectory traj,
boost::function< bool()>  isPreemptRequested 
)
virtual

The Katana 300 is not able to perform a trajectory the same the newer Katana versions do. Every point of the trajectory has to be send individually.

Author
Benjamin Reiner

Reimplemented from katana::Katana.

Definition at line 223 of file Katana300.cpp.

void katana::Katana300::freezeRobot ( )
virtual

The Katana 300 moves to a weird configuration whenever flushMoveBuffers() is called. That's why we override freezeRobot() and skip this call.

Reimplemented from katana::Katana.

Definition at line 72 of file Katana300.cpp.

bool katana::Katana300::moveJoint ( int  jointIndex,
double  turningAngle 
)
virtual

Override to store desired_angles_.

Reimplemented from katana::Katana.

Definition at line 81 of file Katana300.cpp.

void katana::Katana300::refreshMotorStatus ( )
virtual

We have to call refreshEncoders() because we're using the destination position instead of the motor status flags in allJointsReady/allMotorsReady.

Reimplemented from katana::Katana.

Definition at line 93 of file Katana300.cpp.

void katana::Katana300::setLimits ( void  )
virtual

Reimplemented from katana::Katana.

Definition at line 44 of file Katana300.cpp.

void katana::Katana300::testSpeed ( )
virtual

Reimplemented from katana::Katana.

Definition at line 140 of file Katana300.cpp.

Member Data Documentation

std::vector<double> katana::Katana300::desired_angles_
private

Definition at line 68 of file Katana300.h.

const double katana::Katana300::JOINTS_STOPPED_POS_TOLERANCE = 0.01

Definition at line 64 of file Katana300.h.

const double katana::Katana300::JOINTS_STOPPED_VEL_TOLERANCE = 0.01

Definition at line 65 of file Katana300.h.


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


katana
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:58