Public Member Functions | Protected Attributes
FollowJointTrajectoryControllerHandler Class Reference

Controller handler for joint state trajectories. More...

#include <follow_joint_trajectory_controller_handler.h>

Inheritance diagram for FollowJointTrajectoryControllerHandler:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void cancelExecution ()
 cancel the execution of the trajectory. This should be implemented by derived classes.
void controllerActiveCallback ()
void controllerDoneCallback (const actionlib::SimpleClientGoalState &state, const control_msgs::FollowJointTrajectoryResultConstPtr &result)
void controllerFeedbackCallback (const control_msgs::FollowJointTrajectoryFeedbackConstPtr &feedback)
bool executeTrajectory (const trajectory_msgs::JointTrajectory &trajectory, boost::shared_ptr< trajectory_execution_monitor::TrajectoryRecorder > &recorder, const trajectory_execution_monitor::TrajectoryFinishedCallbackFunction &traj_callback)
 Execute the trajectory while recording using recorder. Call the callback function when finished. To enable overshoot monitoring, call enableOvershoot function. Overshoot is not monitored by default.
 FollowJointTrajectoryControllerHandler (const std::string &group_name, const std::string &controller_name)

Protected Attributes

actionlib::SimpleActionClient
< control_msgs::FollowJointTrajectoryAction > 
follow_joint_trajectory_action_client_

Detailed Description

Controller handler for joint state trajectories.

Author:
E. Gil Jones

Definition at line 47 of file follow_joint_trajectory_controller_handler.h.


Constructor & Destructor Documentation

FollowJointTrajectoryControllerHandler::FollowJointTrajectoryControllerHandler ( const std::string &  group_name,
const std::string &  controller_name 
) [inline]

Definition at line 51 of file follow_joint_trajectory_controller_handler.h.


Member Function Documentation

cancel the execution of the trajectory. This should be implemented by derived classes.

Implements trajectory_execution_monitor::TrajectoryControllerHandler.

Definition at line 82 of file follow_joint_trajectory_controller_handler.h.

void FollowJointTrajectoryControllerHandler::controllerDoneCallback ( const actionlib::SimpleClientGoalState state,
const control_msgs::FollowJointTrajectoryResultConstPtr &  result 
) [inline]

Definition at line 85 of file follow_joint_trajectory_controller_handler.h.

void FollowJointTrajectoryControllerHandler::controllerFeedbackCallback ( const control_msgs::FollowJointTrajectoryFeedbackConstPtr &  feedback) [inline]
bool FollowJointTrajectoryControllerHandler::executeTrajectory ( const trajectory_msgs::JointTrajectory &  trajectory,
boost::shared_ptr< trajectory_execution_monitor::TrajectoryRecorder > &  recorder,
const trajectory_execution_monitor::TrajectoryFinishedCallbackFunction traj_callback 
) [inline, virtual]

Execute the trajectory while recording using recorder. Call the callback function when finished. To enable overshoot monitoring, call enableOvershoot function. Overshoot is not monitored by default.

Implements trajectory_execution_monitor::TrajectoryControllerHandler.

Definition at line 61 of file follow_joint_trajectory_controller_handler.h.


Member Data Documentation


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


trajectory_execution_monitor
Author(s): Gil Jones
autogenerated on Fri Dec 6 2013 21:09:24