Public Member Functions | Static Public Attributes | Private Attributes
katana::Katana300 Class Reference

#include <Katana300.h>

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

List of all members.

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 ()

Static Public Attributes

static const double JOINTS_STOPPED_POS_TOLERANCE = 0.01
static const double JOINTS_STOPPED_VEL_TOLERANCE = 0.01

Private Attributes

std::vector< double > desired_angles_

Detailed Description

Definition at line 44 of file Katana300.h.


Constructor & Destructor Documentation

Definition at line 33 of file Katana300.cpp.

Definition at line 40 of file Katana300.cpp.


Member Function Documentation

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.

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.

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.

Definition at line 64 of file Katana300.h.

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 Mon Oct 6 2014 10:46:04