Public Member Functions | Private Types | Private Member Functions | Private Attributes
katana_joint_movement_adapter::JointMovementAdapter Class Reference

#include <joint_movement_adapter.h>

List of all members.

Public Member Functions

void executeCB (const JMAS::GoalConstPtr &goal)
 JointMovementAdapter (std::string name)
void jointStateCb (const pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr &state)
virtual ~JointMovementAdapter ()

Private Types

typedef
actionlib::SimpleActionServer
< katana_msgs::JointMovementAction
JMAS
typedef
actionlib::SimpleActionClient
< pr2_controllers_msgs::JointTrajectoryAction > 
JTAC

Private Member Functions

sensor_msgs::JointState limitJointStates (const sensor_msgs::JointState &jointGoal)
pr2_controllers_msgs::JointTrajectoryGoal makeFullTrajectory (const pr2_controllers_msgs::JointTrajectoryGoal &goal)
pr2_controllers_msgs::JointTrajectoryGoal makeRoughTrajectory (const sensor_msgs::JointState &jointGoal)

Private Attributes

JTAC ac_
JMAS as_
std::map< std::string, double > current_state_
bool got_state_
double max_acc_
double max_vel_
sensor_msgs::JointState movement_goal_
boost::mutex mutex_
urdf::Model robot_model_
ros::Subscriber state_sub_

Detailed Description

Definition at line 52 of file joint_movement_adapter.h.


Member Typedef Documentation

Definition at line 54 of file joint_movement_adapter.h.

typedef actionlib::SimpleActionClient<pr2_controllers_msgs::JointTrajectoryAction> katana_joint_movement_adapter::JointMovementAdapter::JTAC [private]

Definition at line 55 of file joint_movement_adapter.h.


Constructor & Destructor Documentation

Definition at line 35 of file joint_movement_adapter.cpp.

Definition at line 71 of file joint_movement_adapter.cpp.


Member Function Documentation

void katana_joint_movement_adapter::JointMovementAdapter::executeCB ( const JMAS::GoalConstPtr &  goal)

Definition at line 85 of file joint_movement_adapter.cpp.

void katana_joint_movement_adapter::JointMovementAdapter::jointStateCb ( const pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr &  state)

Definition at line 75 of file joint_movement_adapter.cpp.

sensor_msgs::JointState katana_joint_movement_adapter::JointMovementAdapter::limitJointStates ( const sensor_msgs::JointState &  jointGoal) [private]

Definition at line 269 of file joint_movement_adapter.cpp.

pr2_controllers_msgs::JointTrajectoryGoal katana_joint_movement_adapter::JointMovementAdapter::makeFullTrajectory ( const pr2_controllers_msgs::JointTrajectoryGoal &  goal) [private]

Definition at line 198 of file joint_movement_adapter.cpp.

pr2_controllers_msgs::JointTrajectoryGoal katana_joint_movement_adapter::JointMovementAdapter::makeRoughTrajectory ( const sensor_msgs::JointState &  jointGoal) [private]

Definition at line 154 of file joint_movement_adapter.cpp.


Member Data Documentation

Definition at line 71 of file joint_movement_adapter.h.

Definition at line 70 of file joint_movement_adapter.h.

Definition at line 73 of file joint_movement_adapter.h.

Definition at line 75 of file joint_movement_adapter.h.

Definition at line 76 of file joint_movement_adapter.h.

Definition at line 76 of file joint_movement_adapter.h.

Definition at line 81 of file joint_movement_adapter.h.

Definition at line 72 of file joint_movement_adapter.h.

Definition at line 77 of file joint_movement_adapter.h.

Definition at line 74 of file joint_movement_adapter.h.


The documentation for this class was generated from the following files:


katana_joint_movement_adapter
Author(s): Martin Günther
autogenerated on Mon Oct 6 2014 10:47:13