Wrapper class around the KNI (Katana Native Library). More...
#include <Katana.h>
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 | |
KNIConverter * | converter |
boost::shared_ptr< CLMBase > | kni |
boost::recursive_mutex | kni_mutex |
std::vector< TMotStsFlg > | motor_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) |
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.
katana::Katana::Katana | ( | ) |
Definition at line 31 of file Katana.cpp.
|
virtual |
Definition at line 133 of file Katana.cpp.
|
virtual |
Implements katana::AbstractKatana.
Reimplemented in katana::Katana300.
Definition at line 505 of file Katana.cpp.
|
virtual |
Implements katana::AbstractKatana.
Reimplemented in katana::Katana300.
Definition at line 516 of file Katana.cpp.
|
private |
Definition at line 540 of file Katana.cpp.
|
virtual |
Sends the spline parameters to the Katana.
traj |
Implements katana::AbstractKatana.
Reimplemented in katana::Katana300.
Definition at line 286 of file Katana.cpp.
|
virtual |
Reimplemented from katana::AbstractKatana.
Reimplemented in katana::Katana300.
Definition at line 454 of file Katana.cpp.
|
virtual |
Move the joint to the desired angle. Do not wait for result, but return immediately.
jointIndex | the joint to move |
turningAngle | the target angle |
Implements katana::AbstractKatana.
Reimplemented in katana::Katana300.
Definition at line 461 of file Katana.cpp.
|
virtual |
Implements katana::AbstractKatana.
Definition at line 155 of file Katana.cpp.
|
virtual |
Reimplemented from katana::AbstractKatana.
Reimplemented in katana::Katana300.
Definition at line 228 of file Katana.cpp.
|
inlineprotected |
Round to nearest integer.
Definition at line 532 of file Katana.cpp.
|
virtual |
Reimplemented in katana::Katana300.
Definition at line 145 of file Katana.cpp.
|
virtual |
Implements katana::AbstractKatana.
Definition at line 494 of file Katana.cpp.
|
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.
|
private |
Definition at line 592 of file Katana.cpp.
|
virtual |
Reimplemented in katana::Katana300.
Definition at line 606 of file Katana.cpp.
|
private |
Definition at line 600 of file Katana.cpp.
|
protected |
|
protected |
|
protected |
|
private |
|
private |
|
private |
|
private |