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

#include <SimulatedKatana.h>

Inheritance diagram for katana::SimulatedKatana:
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 moveGripper (double openingAngle)
 
virtual bool moveJoint (int jointIndex, double turningAngle)
 
virtual void refreshEncoders ()
 
 SimulatedKatana ()
 
virtual bool someMotorCrashed ()
 
virtual ~SimulatedKatana ()
 
- Public Member Functions inherited from katana::AbstractKatana
 AbstractKatana ()
 
virtual void freezeRobot ()
 
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 void refreshMotorStatus ()
 
virtual ~AbstractKatana ()
 

Private Attributes

boost::shared_ptr< SpecifiedTrajectorycurrent_trajectory_
 

Additional Inherited Members

- 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_
 

Detailed Description

Definition at line 34 of file SimulatedKatana.h.

Constructor & Destructor Documentation

katana::SimulatedKatana::SimulatedKatana ( )

Definition at line 30 of file SimulatedKatana.cpp.

katana::SimulatedKatana::~SimulatedKatana ( )
virtual

Definition at line 50 of file SimulatedKatana.cpp.

Member Function Documentation

bool katana::SimulatedKatana::allJointsReady ( )
virtual

Implements katana::AbstractKatana.

Definition at line 124 of file SimulatedKatana.cpp.

bool katana::SimulatedKatana::allMotorsReady ( )
virtual

Implements katana::AbstractKatana.

Definition at line 128 of file SimulatedKatana.cpp.

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

Implements katana::AbstractKatana.

Definition at line 76 of file SimulatedKatana.cpp.

void katana::SimulatedKatana::moveGripper ( double  openingAngle)
virtual

Definition at line 85 of file SimulatedKatana.cpp.

bool katana::SimulatedKatana::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.

Definition at line 115 of file SimulatedKatana.cpp.

void katana::SimulatedKatana::refreshEncoders ( )
virtual

Implements katana::AbstractKatana.

Definition at line 54 of file SimulatedKatana.cpp.

bool katana::SimulatedKatana::someMotorCrashed ( )
virtual

Implements katana::AbstractKatana.

Definition at line 120 of file SimulatedKatana.cpp.

Member Data Documentation

boost::shared_ptr<SpecifiedTrajectory> katana::SimulatedKatana::current_trajectory_
private

Definition at line 51 of file SimulatedKatana.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