Wrapper class around the KNI (Katana Native Library). More...
#include <Katana.h>
Public Member Functions | |
virtual bool | allJointsReady () |
virtual bool | allMotorsReady () |
bool | executeTrajectory (boost::shared_ptr< SpecifiedTrajectory > traj) |
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 () |
Protected Attributes | |
KNIConverter * | converter |
boost::shared_ptr< CLMBase > | kni |
boost::recursive_mutex | kni_mutex |
std::vector< TMotStsFlg > | motor_status_ |
Private Member Functions | |
void | calibrate () |
short | round (const double x) |
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 | |
CCdlBase * | device |
ros::Time | last_encoder_update_ |
CCplSerialCRC * | protocol |
ros::ServiceServer | switch_motors_off_srv_ |
ros::ServiceServer | switch_motors_on_srv_ |
ros::ServiceServer | test_speed_srv_ |
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 31 of file Katana.cpp.
katana::Katana::~Katana | ( | ) | [virtual] |
Definition at line 133 of file Katana.cpp.
bool katana::Katana::allJointsReady | ( | ) | [virtual] |
Implements katana::AbstractKatana.
Reimplemented in katana::Katana300.
Definition at line 497 of file Katana.cpp.
bool katana::Katana::allMotorsReady | ( | ) | [virtual] |
Implements katana::AbstractKatana.
Reimplemented in katana::Katana300.
Definition at line 508 of file Katana.cpp.
void katana::Katana::calibrate | ( | void | ) | [private] |
Definition at line 532 of file Katana.cpp.
bool katana::Katana::executeTrajectory | ( | boost::shared_ptr< SpecifiedTrajectory > | traj | ) | [virtual] |
Sends the spline parameters to the Katana.
traj |
Implements katana::AbstractKatana.
Definition at line 279 of file Katana.cpp.
void katana::Katana::freezeRobot | ( | ) | [virtual] |
Reimplemented from katana::AbstractKatana.
Reimplemented in katana::Katana300.
Definition at line 446 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.
jointIndex | the joint to move |
turningAngle | the target angle |
Implements katana::AbstractKatana.
Reimplemented in katana::Katana300.
Definition at line 453 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 221 of file Katana.cpp.
short katana::Katana::round | ( | const double | x | ) | [inline, private] |
Round to nearest integer.
Definition at line 524 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 486 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 576 of file Katana.cpp.
bool katana::Katana::switchMotorsOn | ( | std_srvs::Empty::Request & | request, |
std_srvs::Empty::Response & | response | ||
) | [private] |
Definition at line 584 of file Katana.cpp.
void katana::Katana::testSpeed | ( | ) | [virtual] |
Reimplemented in katana::Katana300.
Definition at line 598 of file Katana.cpp.
bool katana::Katana::testSpeedSrv | ( | std_srvs::Empty::Request & | request, |
std_srvs::Empty::Response & | response | ||
) | [private] |
Definition at line 592 of file Katana.cpp.
KNIConverter* katana::Katana::converter [protected] |
CCdlBase* katana::Katana::device [private] |
boost::shared_ptr<CLMBase> katana::Katana::kni [protected] |
boost::recursive_mutex katana::Katana::kni_mutex [protected] |
std::vector<TMotStsFlg> katana::Katana::motor_status_ [protected] |
CCplSerialCRC* katana::Katana::protocol [private] |