Public Member Functions | Private Types | Private Member Functions | Private Attributes
katana::JointMovementActionController Class Reference

#include <joint_movement_action_controller.h>

List of all members.

Public Member Functions

 JointMovementActionController (boost::shared_ptr< AbstractKatana > katana)
virtual ~JointMovementActionController ()

Private Types

typedef
actionlib::SimpleActionClient
< katana_msgs::JointMovementAction
JMAC
typedef
actionlib::SimpleActionServer
< katana_msgs::JointMovementAction
JMAS

Private Member Functions

sensor_msgs::JointState adjustJointGoalPositionsToMotorLimits (const sensor_msgs::JointState &jointGoal)
void executeCB (const JMAS::GoalConstPtr &goal)
bool suitableJointGoal (const std::vector< std::string > &jointGoalNames)

Private Attributes

JMAS action_server_
std::vector< std::string > gripper_joints_
std::vector< std::string > joints_
boost::shared_ptr< AbstractKatanakatana_
sensor_msgs::JointState movement_goal_

Detailed Description

Definition at line 44 of file joint_movement_action_controller.h.


Member Typedef Documentation

Definition at line 47 of file joint_movement_action_controller.h.

Definition at line 46 of file joint_movement_action_controller.h.


Constructor & Destructor Documentation

Definition at line 34 of file joint_movement_action_controller.cpp.

Definition at line 43 of file joint_movement_action_controller.cpp.


Member Function Documentation

sensor_msgs::JointState katana::JointMovementActionController::adjustJointGoalPositionsToMotorLimits ( const sensor_msgs::JointState &  jointGoal) [private]

Definition at line 77 of file joint_movement_action_controller.cpp.

void katana::JointMovementActionController::executeCB ( const JMAS::GoalConstPtr &  goal) [private]

Definition at line 110 of file joint_movement_action_controller.cpp.

bool katana::JointMovementActionController::suitableJointGoal ( const std::vector< std::string > &  jointGoalNames) [private]

Checks if all joints in the joint goal match a among joints of the katana

Definition at line 50 of file joint_movement_action_controller.cpp.


Member Data Documentation

Definition at line 63 of file joint_movement_action_controller.h.

std::vector<std::string> katana::JointMovementActionController::gripper_joints_ [private]

Definition at line 56 of file joint_movement_action_controller.h.

std::vector<std::string> katana::JointMovementActionController::joints_ [private]

Definition at line 55 of file joint_movement_action_controller.h.

Definition at line 57 of file joint_movement_action_controller.h.

sensor_msgs::JointState katana::JointMovementActionController::movement_goal_ [private]

Definition at line 59 of file joint_movement_action_controller.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