Public Member Functions | Protected Types | Protected Attributes | Private Member Functions | Private Attributes
TrajectoryExecuter Class Reference

#include <SchunkServer.h>

Inheritance diagram for TrajectoryExecuter:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void init (RobotArm *arm, std::map< std::string, RobotArm::IDType > &joints_name_to_number_map)
bool isRunning ()
bool isWaiting ()
void main ()
void start (const trajectory_msgs::JointTrajectory &newtraj)
void stop ()
void trajectoryActionCallback (const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)
 TrajectoryExecuter (ros::NodeHandle &nh)
 ~TrajectoryExecuter ()

Protected Types

typedef
actionlib::SimpleActionServer
< control_msgs::FollowJointTrajectoryAction > 
ActionServerType

Protected Attributes

std::string action_name_
ActionServerTypeas_
control_msgs::FollowJointTrajectoryFeedback feedback_
ros::NodeHandle nh_
control_msgs::FollowJointTrajectoryResult result_

Private Member Functions

void followTrajectory ()

Private Attributes

RobotArmarm_
boost::condition_variable cond_
std::map< std::string,
RobotArm::IDType
joints_name_to_number_map_
boost::mutex mut_
bool run_
control_msgs::JointTrajectoryControllerState state_msg_
ros::Publisher state_publisher_
trajectory_msgs::JointTrajectory traj_
bool waiting_

Detailed Description

Definition at line 41 of file SchunkServer.h.


Member Typedef Documentation

typedef actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction> TrajectoryExecuter::ActionServerType [protected]

Definition at line 394 of file SchunkServer.h.


Constructor & Destructor Documentation

Definition at line 43 of file SchunkServer.h.

Definition at line 83 of file SchunkServer.h.


Member Function Documentation

void TrajectoryExecuter::followTrajectory ( ) [inline, private]

Definition at line 404 of file SchunkServer.h.

void TrajectoryExecuter::init ( RobotArm arm,
std::map< std::string, RobotArm::IDType > &  joints_name_to_number_map 
) [inline]

Definition at line 56 of file SchunkServer.h.

bool TrajectoryExecuter::isRunning ( ) [inline]

Definition at line 162 of file SchunkServer.h.

bool TrajectoryExecuter::isWaiting ( ) [inline]

Definition at line 167 of file SchunkServer.h.

void TrajectoryExecuter::main ( ) [inline]

Definition at line 87 of file SchunkServer.h.

void TrajectoryExecuter::start ( const trajectory_msgs::JointTrajectory &  newtraj) [inline]

Definition at line 142 of file SchunkServer.h.

void TrajectoryExecuter::stop ( ) [inline]

Definition at line 157 of file SchunkServer.h.

void TrajectoryExecuter::trajectoryActionCallback ( const control_msgs::FollowJointTrajectoryGoalConstPtr &  goal) [inline]

Definition at line 174 of file SchunkServer.h.


Member Data Documentation

std::string TrajectoryExecuter::action_name_ [protected]

Definition at line 396 of file SchunkServer.h.

Definition at line 446 of file SchunkServer.h.

Definition at line 395 of file SchunkServer.h.

boost::condition_variable TrajectoryExecuter::cond_ [private]

Definition at line 451 of file SchunkServer.h.

control_msgs::FollowJointTrajectoryFeedback TrajectoryExecuter::feedback_ [protected]

Definition at line 398 of file SchunkServer.h.

Definition at line 447 of file SchunkServer.h.

boost::mutex TrajectoryExecuter::mut_ [private]

Definition at line 452 of file SchunkServer.h.

Definition at line 393 of file SchunkServer.h.

control_msgs::FollowJointTrajectoryResult TrajectoryExecuter::result_ [protected]

Definition at line 399 of file SchunkServer.h.

bool TrajectoryExecuter::run_ [private]

Definition at line 449 of file SchunkServer.h.

control_msgs::JointTrajectoryControllerState TrajectoryExecuter::state_msg_ [private]

Definition at line 453 of file SchunkServer.h.

Definition at line 454 of file SchunkServer.h.

trajectory_msgs::JointTrajectory TrajectoryExecuter::traj_ [private]

Definition at line 448 of file SchunkServer.h.

Definition at line 450 of file SchunkServer.h.


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


metralabs_ros
Author(s): Yianni Gatsoulis and Chris Burbridge and Lorenzo Riano and Felix Kolbe
autogenerated on Mon Oct 6 2014 07:27:58