#include <SchunkServer.h>

Public Member Functions | |
| void | init (RobotArm *arm, std::map< std::string, unsigned int > &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_ |
| ActionServerType * | as_ |
| control_msgs::FollowJointTrajectoryFeedback | feedback_ |
| ros::NodeHandle | nh_ |
| control_msgs::FollowJointTrajectoryResult | result_ |
Private Member Functions | |
| void | followTrajectory () |
Private Attributes | |
| RobotArm * | arm_ |
| boost::condition_variable | cond_ |
| std::map< std::string, unsigned int > | 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_ |
Definition at line 41 of file SchunkServer.h.
typedef actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction> TrajectoryExecuter::ActionServerType [protected] |
Definition at line 319 of file SchunkServer.h.
| TrajectoryExecuter::TrajectoryExecuter | ( | ros::NodeHandle & | nh | ) | [inline] |
Definition at line 43 of file SchunkServer.h.
| TrajectoryExecuter::~TrajectoryExecuter | ( | ) | [inline] |
Definition at line 78 of file SchunkServer.h.
| void TrajectoryExecuter::followTrajectory | ( | ) | [inline, private] |
Definition at line 329 of file SchunkServer.h.
| void TrajectoryExecuter::init | ( | RobotArm * | arm, |
| std::map< std::string, unsigned int > & | joints_name_to_number_map | ||
| ) | [inline] |
Definition at line 52 of file SchunkServer.h.
| bool TrajectoryExecuter::isRunning | ( | ) | [inline] |
Definition at line 158 of file SchunkServer.h.
| bool TrajectoryExecuter::isWaiting | ( | ) | [inline] |
Definition at line 163 of file SchunkServer.h.
| void TrajectoryExecuter::main | ( | ) | [inline] |
Definition at line 83 of file SchunkServer.h.
| void TrajectoryExecuter::start | ( | const trajectory_msgs::JointTrajectory & | newtraj | ) | [inline] |
Definition at line 138 of file SchunkServer.h.
| void TrajectoryExecuter::stop | ( | ) | [inline] |
Definition at line 153 of file SchunkServer.h.
| void TrajectoryExecuter::trajectoryActionCallback | ( | const control_msgs::FollowJointTrajectoryGoalConstPtr & | goal | ) | [inline] |
std::string TrajectoryExecuter::action_name_ [protected] |
Definition at line 321 of file SchunkServer.h.
RobotArm* TrajectoryExecuter::arm_ [private] |
Definition at line 371 of file SchunkServer.h.
ActionServerType* TrajectoryExecuter::as_ [protected] |
Definition at line 320 of file SchunkServer.h.
boost::condition_variable TrajectoryExecuter::cond_ [private] |
Definition at line 376 of file SchunkServer.h.
control_msgs::FollowJointTrajectoryFeedback TrajectoryExecuter::feedback_ [protected] |
Definition at line 323 of file SchunkServer.h.
std::map<std::string, unsigned int> TrajectoryExecuter::joints_name_to_number_map_ [private] |
Definition at line 372 of file SchunkServer.h.
boost::mutex TrajectoryExecuter::mut_ [private] |
Definition at line 377 of file SchunkServer.h.
ros::NodeHandle TrajectoryExecuter::nh_ [protected] |
Definition at line 318 of file SchunkServer.h.
control_msgs::FollowJointTrajectoryResult TrajectoryExecuter::result_ [protected] |
Definition at line 324 of file SchunkServer.h.
bool TrajectoryExecuter::run_ [private] |
Definition at line 374 of file SchunkServer.h.
control_msgs::JointTrajectoryControllerState TrajectoryExecuter::state_msg_ [private] |
Definition at line 378 of file SchunkServer.h.
Definition at line 379 of file SchunkServer.h.
trajectory_msgs::JointTrajectory TrajectoryExecuter::traj_ [private] |
Definition at line 373 of file SchunkServer.h.
bool TrajectoryExecuter::waiting_ [private] |
Definition at line 375 of file SchunkServer.h.