Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
JointTrajectoryExecuter Class Reference

Public Member Functions

 JointTrajectoryExecuter (ros::NodeHandle &n)
 
 ~JointTrajectoryExecuter ()
 

Private Types

typedef JTAS::GoalHandle GoalHandle
 
typedef actionlib::ActionServer< pr2_controllers_msgs::JointTrajectoryAction > JTAS
 

Private Member Functions

void cancelCB (GoalHandle gh)
 
void controllerStateCB (const pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr &msg)
 
void goalCB (GoalHandle gh)
 
void watchdog (const ros::TimerEvent &e)
 

Static Private Member Functions

static bool setsEqual (const std::vector< std::string > &a, const std::vector< std::string > &b)
 

Private Attributes

JTAS action_server_
 
GoalHandle active_goal_
 
trajectory_msgs::JointTrajectory current_traj_
 
std::map< std::string, double > goal_constraints_
 
double goal_time_constraint_
 
bool has_active_goal_
 
std::vector< std::string > joint_names_
 
pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr last_controller_state_
 
ros::NodeHandle node_
 
ros::Publisher pub_controller_command_
 
double stopped_velocity_tolerance_
 
ros::Subscriber sub_controller_state_
 
std::map< std::string, double > trajectory_constraints_
 
ros::Timer watchdog_timer_
 

Detailed Description

Definition at line 41 of file joint_trajectory_action.cpp.

Member Typedef Documentation

Definition at line 45 of file joint_trajectory_action.cpp.

typedef actionlib::ActionServer<pr2_controllers_msgs::JointTrajectoryAction> JointTrajectoryExecuter::JTAS
private

Definition at line 44 of file joint_trajectory_action.cpp.

Constructor & Destructor Documentation

JointTrajectoryExecuter::JointTrajectoryExecuter ( ros::NodeHandle n)
inline

Definition at line 47 of file joint_trajectory_action.cpp.

JointTrajectoryExecuter::~JointTrajectoryExecuter ( )
inline

Definition at line 121 of file joint_trajectory_action.cpp.

Member Function Documentation

void JointTrajectoryExecuter::cancelCB ( GoalHandle  gh)
inlineprivate

Definition at line 215 of file joint_trajectory_action.cpp.

void JointTrajectoryExecuter::controllerStateCB ( const pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr &  msg)
inlineprivate

Definition at line 249 of file joint_trajectory_action.cpp.

void JointTrajectoryExecuter::goalCB ( GoalHandle  gh)
inlineprivate

Definition at line 183 of file joint_trajectory_action.cpp.

static bool JointTrajectoryExecuter::setsEqual ( const std::vector< std::string > &  a,
const std::vector< std::string > &  b 
)
inlinestaticprivate

Definition at line 130 of file joint_trajectory_action.cpp.

void JointTrajectoryExecuter::watchdog ( const ros::TimerEvent e)
inlineprivate

Definition at line 149 of file joint_trajectory_action.cpp.

Member Data Documentation

JTAS JointTrajectoryExecuter::action_server_
private

Definition at line 232 of file joint_trajectory_action.cpp.

GoalHandle JointTrajectoryExecuter::active_goal_
private

Definition at line 238 of file joint_trajectory_action.cpp.

trajectory_msgs::JointTrajectory JointTrajectoryExecuter::current_traj_
private

Definition at line 239 of file joint_trajectory_action.cpp.

std::map<std::string,double> JointTrajectoryExecuter::goal_constraints_
private

Definition at line 243 of file joint_trajectory_action.cpp.

double JointTrajectoryExecuter::goal_time_constraint_
private

Definition at line 245 of file joint_trajectory_action.cpp.

bool JointTrajectoryExecuter::has_active_goal_
private

Definition at line 237 of file joint_trajectory_action.cpp.

std::vector<std::string> JointTrajectoryExecuter::joint_names_
private

Definition at line 242 of file joint_trajectory_action.cpp.

pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr JointTrajectoryExecuter::last_controller_state_
private

Definition at line 248 of file joint_trajectory_action.cpp.

ros::NodeHandle JointTrajectoryExecuter::node_
private

Definition at line 231 of file joint_trajectory_action.cpp.

ros::Publisher JointTrajectoryExecuter::pub_controller_command_
private

Definition at line 233 of file joint_trajectory_action.cpp.

double JointTrajectoryExecuter::stopped_velocity_tolerance_
private

Definition at line 246 of file joint_trajectory_action.cpp.

ros::Subscriber JointTrajectoryExecuter::sub_controller_state_
private

Definition at line 234 of file joint_trajectory_action.cpp.

std::map<std::string,double> JointTrajectoryExecuter::trajectory_constraints_
private

Definition at line 244 of file joint_trajectory_action.cpp.

ros::Timer JointTrajectoryExecuter::watchdog_timer_
private

Definition at line 235 of file joint_trajectory_action.cpp.


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


joint_trajectory_action
Author(s): Stuart Glaser
autogenerated on Mon Jun 10 2019 14:26:21