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

Wrapper class around the KNI (Katana Native Library). More...

#include <Katana.h>

Inheritance diagram for katana::Katana:
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 ()
 
 Katana ()
 
virtual bool moveJoint (int jointIndex, double turningAngle)
 
void refreshEncoders ()
 
virtual void refreshMotorStatus ()
 
virtual void setLimits (void)
 
virtual bool someMotorCrashed ()
 
virtual void testSpeed ()
 
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 ()
 

Protected Member Functions

short round (const double x)
 

Protected Attributes

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_
 

Private Member Functions

void calibrate ()
 
bool switchMotorsOff (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
 
bool switchMotorsOn (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
 
bool testSpeedSrv (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
 

Private Attributes

CCdlBasedevice
 
ros::Time last_encoder_update_
 
CCplSerialCRCprotocol
 
ros::ServiceServer switch_motors_off_srv_
 
ros::ServiceServer switch_motors_on_srv_
 
ros::ServiceServer test_speed_srv_
 

Detailed Description

Wrapper class around the KNI (Katana Native Library).

All access to the Katana hardware should happen through this class. There must always be only one instance of this class. This class should be thread-safe.

Definition at line 48 of file Katana.h.

Constructor & Destructor Documentation

katana::Katana::Katana ( )

Definition at line 31 of file Katana.cpp.

katana::Katana::~Katana ( )
virtual

Definition at line 133 of file Katana.cpp.

Member Function Documentation

bool katana::Katana::allJointsReady ( )
virtual

Implements katana::AbstractKatana.

Reimplemented in katana::Katana300.

Definition at line 505 of file Katana.cpp.

bool katana::Katana::allMotorsReady ( )
virtual

Implements katana::AbstractKatana.

Reimplemented in katana::Katana300.

Definition at line 516 of file Katana.cpp.

void katana::Katana::calibrate ( void  )
private

Definition at line 540 of file Katana.cpp.

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

Sends the spline parameters to the Katana.

Parameters
traj

Implements katana::AbstractKatana.

Reimplemented in katana::Katana300.

Definition at line 286 of file Katana.cpp.

void katana::Katana::freezeRobot ( )
virtual

Reimplemented from katana::AbstractKatana.

Reimplemented in katana::Katana300.

Definition at line 454 of file Katana.cpp.

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

Move the joint to the desired angle. Do not wait for result, but return immediately.

Parameters
jointIndexthe joint to move
turningAnglethe target angle
Returns
true iff command was successfully sent to Katana

Implements katana::AbstractKatana.

Reimplemented in katana::Katana300.

Definition at line 461 of file Katana.cpp.

void katana::Katana::refreshEncoders ( )
virtual

Implements katana::AbstractKatana.

Definition at line 155 of file Katana.cpp.

void katana::Katana::refreshMotorStatus ( )
virtual

Reimplemented from katana::AbstractKatana.

Reimplemented in katana::Katana300.

Definition at line 228 of file Katana.cpp.

short katana::Katana::round ( const double  x)
inlineprotected

Round to nearest integer.

Definition at line 532 of file Katana.cpp.

void katana::Katana::setLimits ( void  )
virtual

Reimplemented in katana::Katana300.

Definition at line 145 of file Katana.cpp.

bool katana::Katana::someMotorCrashed ( )
virtual

Implements katana::AbstractKatana.

Definition at line 494 of file Katana.cpp.

bool katana::Katana::switchMotorsOff ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
)
private

This service is dangerous to call! It will switch all motors off. If the arm is not in a stable position, it will crash down, potentially damaging itself or the environment!

Definition at line 584 of file Katana.cpp.

bool katana::Katana::switchMotorsOn ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
)
private

Definition at line 592 of file Katana.cpp.

void katana::Katana::testSpeed ( )
virtual

Reimplemented in katana::Katana300.

Definition at line 606 of file Katana.cpp.

bool katana::Katana::testSpeedSrv ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
)
private

Definition at line 600 of file Katana.cpp.

Member Data Documentation

KNIConverter* katana::Katana::converter
protected

Definition at line 75 of file Katana.h.

CCdlBase* katana::Katana::device
private

Definition at line 85 of file Katana.h.

boost::shared_ptr<CLMBase> katana::Katana::kni
protected

Definition at line 71 of file Katana.h.

boost::recursive_mutex katana::Katana::kni_mutex
protected

Definition at line 72 of file Katana.h.

ros::Time katana::Katana::last_encoder_update_
private

Definition at line 87 of file Katana.h.

std::vector<TMotStsFlg> katana::Katana::motor_status_
protected

Definition at line 73 of file Katana.h.

CCplSerialCRC* katana::Katana::protocol
private

Definition at line 84 of file Katana.h.

ros::ServiceServer katana::Katana::switch_motors_off_srv_
private

Definition at line 80 of file Katana.h.

ros::ServiceServer katana::Katana::switch_motors_on_srv_
private

Definition at line 81 of file Katana.h.

ros::ServiceServer katana::Katana::test_speed_srv_
private

Definition at line 82 of file Katana.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