All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends
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 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 32 of file Katana300.cpp.

Definition at line 39 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 100 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 121 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 69 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 78 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 90 of file Katana300.cpp.

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

Reimplemented from katana::Katana.

Definition at line 43 of file Katana300.cpp.

void katana::Katana300::testSpeed ( ) [virtual]

Reimplemented from katana::Katana.

Definition at line 138 of file Katana300.cpp.


Member Data Documentation

Definition at line 65 of file Katana300.h.

Definition at line 61 of file Katana300.h.

Definition at line 62 of file Katana300.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends


katana
Author(s): Martin Günther
autogenerated on Tue May 28 2013 14:54:05