Classes | Typedefs | Functions | Variables
katana Namespace Reference

Classes

class  AbstractKatana
 
class  JointMovementActionController
 
class  JointStatePublisher
 
class  JointTrajectoryActionController
 
class  Katana
 Wrapper class around the KNI (Katana Native Library). More...
 
class  Katana300
 
class  KatanaGripperGraspController
 
class  KatanaNode
 This is the node providing all publishers/services/actions relating to the Katana arm. More...
 
class  KNIConverter
 
class  KNIKinematics
 
struct  Segment
 
class  SimulatedKatana
 
struct  Spline
 

Typedefs

typedef std::vector< SegmentSpecifiedTrajectory
 

Functions

void generatePowers (int n, double x, double *powers)
 
void getCubicSplineCoefficients (double start_pos, double start_vel, double end_pos, double end_vel, double time, std::vector< double > &coefficients)
 
void sampleCubicSpline (const std::vector< double > &coefficients, double time, double &position, double &velocity, double &acceleration)
 Samples a cubic spline segment at a particular time. More...
 
void sampleSplineWithTimeBounds (const std::vector< double > &coefficients, double duration, double time, double &position, double &velocity, double &acceleration)
 
static bool setsEqual (const std::vector< std::string > &a, const std::vector< std::string > &b)
 
void splineCoefficients (int steps, double *timearray, double *encoderarray, double *arr_p1, double *arr_p2, double *arr_p3, double *arr_p4)
 

Variables

static const double GRIPPER_CLOSED_ANGLE = -0.44
 Constants for gripper fully open or fully closed (should be equal to the value in the urdf description) More...
 
const size_t GRIPPER_INDEX = NUM_MOTORS - 1
 The motor index of the gripper (used in all vectors – e.g., motor_angles_) More...
 
static const double GRIPPER_OPEN_ANGLE = 0.30
 Constants for gripper fully open or fully closed (should be equal to the value in the urdf description) More...
 
static const double GRIPPER_OPENING_CLOSING_DURATION = 3.0
 The maximum time it takes to open or close the gripper. More...
 
static const double KNI_GRIPPER_CLOSED_ANGLE = 0.21652991032554647
 constants for converting between the KNI gripper angle and the URDF gripper angle More...
 
static const double KNI_GRIPPER_OPEN_ANGLE = -2.057443
 
static const int KNI_MAX_ACCELERATION = 2
 acceleration limit = 1 or 2 [enc / (10 ms)^2] More...
 
static const int KNI_MAX_VELOCITY = 180
 velocity limit <= 180 [enc / 10 ms] More...
 
static const double KNI_TO_ROS_LENGTH = 0.001
 the conversion factor from KNI coordinates (in mm) to ROS coordinates (in m) More...
 
static const double KNI_TO_ROS_TIME = 100.0
 KNI time is in 10 milliseconds (most of the time), ROS time is in seconds. More...
 
static const double KNI_TO_URDF_GRIPPER_FACTOR
 
static const size_t MOVE_BUFFER_SIZE = 16
 
const size_t NUM_GRIPPER_JOINTS = 2
 The number of gripper_joints in the katana (= the two gripper finger joints) More...
 
const size_t NUM_JOINTS = NUM_MOTORS - 1
 The number of joints in the katana (= only the 5 "real" joints) More...
 
const size_t NUM_MOTORS = 6
 The number of motors in the katana (= all 5 "real" joints + the gripper) More...
 

Typedef Documentation

typedef std::vector<Segment> katana::SpecifiedTrajectory

Definition at line 48 of file SpecifiedTrajectory.h.

Function Documentation

void katana::generatePowers ( int  n,
double  x,
double *  powers 
)
inline

Definition at line 29 of file spline_functions.cpp.

void katana::getCubicSplineCoefficients ( double  start_pos,
double  start_vel,
double  end_pos,
double  end_vel,
double  time,
std::vector< double > &  coefficients 
)

Definition at line 50 of file spline_functions.cpp.

void katana::sampleCubicSpline ( const std::vector< double > &  coefficients,
double  time,
double &  position,
double &  velocity,
double &  acceleration 
)

Samples a cubic spline segment at a particular time.

Definition at line 38 of file spline_functions.cpp.

void katana::sampleSplineWithTimeBounds ( const std::vector< double > &  coefficients,
double  duration,
double  time,
double &  position,
double &  velocity,
double &  acceleration 
)

Samples, but handling time bounds. When the time is past the end of the spline duration, the position is the last valid position, and the derivatives are all 0.

Definition at line 185 of file spline_functions.cpp.

static bool katana::setsEqual ( const std::vector< std::string > &  a,
const std::vector< std::string > &  b 
)
static

Compares two vectors if they are set-equal (contain same elements in any order)

Definition at line 403 of file joint_trajectory_action_controller.cpp.

void katana::splineCoefficients ( int  steps,
double *  timearray,
double *  encoderarray,
double *  arr_p1,
double *  arr_p2,
double *  arr_p3,
double *  arr_p4 
)

copied from KNI: lmBase.cpp

Calculates the spline coefficients for a single motor. Assumptions: velocity and acceleration at start and end of trajectory = 0.

Parameters
stepsnumber of segments (input)
timearraytimearray[0]: start time of trajectory, timearray[i+1]: end time of segment i. Only the differences are important for the result, so if timearray[0] is set to 0.0, then timearray[i+1] = duration of segment i (input, size [steps + 1], unit: seconds!)
encoderarrayencoderarray[0]: starting position of encoders, encoderarray[i+1]: target position after segment i (input, size [steps + 1], unit: motor encoders)
arr_p1arr_p1[i]: segment i's spline coefficients for t^0 (= position) (output, size [steps])
arr_p2arr_p2[i]: segment i's spline coefficients for t^1 (= velocity) (output, size [steps])
arr_p3arr_p3[i]: segment i's spline coefficients for t^2 (= acceleration) (output, size [steps])
arr_p4arr_p4[i]: segment i's spline coefficients for t^3 (= jerk) (output, size [steps])

Definition at line 75 of file spline_functions.cpp.

Variable Documentation

const double katana::GRIPPER_CLOSED_ANGLE = -0.44
static

Constants for gripper fully open or fully closed (should be equal to the value in the urdf description)

Definition at line 46 of file katana_constants.h.

const size_t katana::GRIPPER_INDEX = NUM_MOTORS - 1

The motor index of the gripper (used in all vectors – e.g., motor_angles_)

Definition at line 40 of file katana_constants.h.

const double katana::GRIPPER_OPEN_ANGLE = 0.30
static

Constants for gripper fully open or fully closed (should be equal to the value in the urdf description)

Definition at line 43 of file katana_constants.h.

const double katana::GRIPPER_OPENING_CLOSING_DURATION = 3.0
static

The maximum time it takes to open or close the gripper.

Definition at line 49 of file katana_constants.h.

const double katana::KNI_GRIPPER_CLOSED_ANGLE = 0.21652991032554647
static

constants for converting between the KNI gripper angle and the URDF gripper angle

Definition at line 52 of file katana_constants.h.

const double katana::KNI_GRIPPER_OPEN_ANGLE = -2.057443
static

Definition at line 53 of file katana_constants.h.

const int katana::KNI_MAX_ACCELERATION = 2
static

acceleration limit = 1 or 2 [enc / (10 ms)^2]

Definition at line 68 of file katana_constants.h.

const int katana::KNI_MAX_VELOCITY = 180
static

velocity limit <= 180 [enc / 10 ms]

Definition at line 65 of file katana_constants.h.

const double katana::KNI_TO_ROS_LENGTH = 0.001
static

the conversion factor from KNI coordinates (in mm) to ROS coordinates (in m)

Definition at line 62 of file katana_constants.h.

const double katana::KNI_TO_ROS_TIME = 100.0
static

KNI time is in 10 milliseconds (most of the time), ROS time is in seconds.

Definition at line 59 of file katana_constants.h.

const double katana::KNI_TO_URDF_GRIPPER_FACTOR
static
Initial value:
static const double KNI_GRIPPER_OPEN_ANGLE
static const double GRIPPER_OPEN_ANGLE
Constants for gripper fully open or fully closed (should be equal to the value in the urdf descriptio...
static const double KNI_GRIPPER_CLOSED_ANGLE
constants for converting between the KNI gripper angle and the URDF gripper angle ...
static const double GRIPPER_CLOSED_ANGLE
Constants for gripper fully open or fully closed (should be equal to the value in the urdf descriptio...

Definition at line 55 of file katana_constants.h.

const size_t katana::MOVE_BUFFER_SIZE = 16
static

Definition at line 70 of file katana_constants.h.

const size_t katana::NUM_GRIPPER_JOINTS = 2

The number of gripper_joints in the katana (= the two gripper finger joints)

Definition at line 37 of file katana_constants.h.

const size_t katana::NUM_JOINTS = NUM_MOTORS - 1

The number of joints in the katana (= only the 5 "real" joints)

Definition at line 34 of file katana_constants.h.

const size_t katana::NUM_MOTORS = 6

The number of motors in the katana (= all 5 "real" joints + the gripper)

Definition at line 31 of file katana_constants.h.



katana
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:58